@@ -562,6 +562,92 @@ TEST_F(
562
562
EXPECT_EQ ((*(controller_->input_ref_ .readFromNonRT ()))->twist .angular .z , 0.0 );
563
563
}
564
564
565
+ TEST_F (MecanumDriveControllerTest, SideToSideAndRotationOdometryTest)
566
+ {
567
+ // Initialize controller
568
+ SetUpController (" test_mecanum_drive_controller_with_rotation" );
569
+
570
+ // Configure
571
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
572
+
573
+ // Check on the base frame offset is set by the params
574
+ EXPECT_EQ (controller_->odometry_ .getBaseFrameOffset ()[0 ], 1.0 );
575
+ EXPECT_EQ (controller_->odometry_ .getBaseFrameOffset ()[1 ], 2.0 );
576
+ EXPECT_EQ (controller_->odometry_ .getBaseFrameOffset ()[2 ], 3.0 );
577
+
578
+ // Activate in chained mode
579
+ controller_->set_chained_mode (true );
580
+ ASSERT_EQ (controller_->on_activate (rclcpp_lifecycle::State ()), NODE_SUCCESS);
581
+ ASSERT_EQ (controller_->is_in_chained_mode (), true );
582
+
583
+ // Setup reference interfaces for side to side motion
584
+ auto side_to_side_motion = [this ](double linear_y)
585
+ {
586
+ controller_->reference_interfaces_ [0 ] = 0 ; // linear x
587
+ controller_->reference_interfaces_ [1 ] = linear_y; // linear y
588
+ controller_->reference_interfaces_ [2 ] = 0 ; // angular z
589
+ };
590
+
591
+ // Setup reference interfaces for rotation
592
+ auto rotation_motion = [this ](double rotation_velocity)
593
+ {
594
+ controller_->reference_interfaces_ [0 ] = 0 ; // linear x
595
+ controller_->reference_interfaces_ [1 ] = 0 ; // linear y
596
+ controller_->reference_interfaces_ [2 ] = rotation_velocity; // angular z
597
+ };
598
+
599
+ const double update_rate = 50.0 ; // 50 Hz
600
+ const double dt = 1.0 / update_rate;
601
+ const double test_duration = 1.0 ; // 1 second test
602
+ auto current_time = controller_->get_node ()->now ();
603
+
604
+ auto count = 0 ;
605
+ for (double t = 0 ; t < test_duration; t += dt)
606
+ {
607
+ switch (count % 4 )
608
+ {
609
+ case 0 :
610
+ side_to_side_motion (2.0 );
611
+ break ;
612
+ case 1 :
613
+ rotation_motion (-0.5 );
614
+ break ;
615
+ case 2 :
616
+ side_to_side_motion (-2.0 );
617
+ break ;
618
+ case 3 :
619
+ rotation_motion (0.5 );
620
+ }
621
+
622
+ // Call update method
623
+ ASSERT_EQ (
624
+ controller_->update (current_time, rclcpp::Duration::from_seconds (dt)),
625
+ controller_interface::return_type::OK);
626
+
627
+ current_time += rclcpp::Duration::from_seconds (dt);
628
+ count++;
629
+
630
+ // Update the state of the wheels for subsequent loop
631
+ size_t fl_index = controller_->get_front_left_wheel_index ();
632
+ size_t fr_index = controller_->get_front_right_wheel_index ();
633
+ size_t rl_index = controller_->get_rear_left_wheel_index ();
634
+ size_t rr_index = controller_->get_rear_right_wheel_index ();
635
+ joint_state_values_[fl_index] = controller_->command_interfaces_ [fl_index].get_value ();
636
+ joint_state_values_[fr_index] = controller_->command_interfaces_ [fr_index].get_value ();
637
+ joint_state_values_[rl_index] = controller_->command_interfaces_ [rl_index].get_value ();
638
+ joint_state_values_[rr_index] = controller_->command_interfaces_ [rr_index].get_value ();
639
+ }
640
+
641
+ RCLCPP_INFO (
642
+ controller_->get_node ()->get_logger (), " odometry: %f, %f, %f" , controller_->odometry_ .getX (),
643
+ controller_->odometry_ .getY (), controller_->odometry_ .getRz ());
644
+
645
+ // Verify odometry remains bounded
646
+ EXPECT_LT (std::abs (controller_->odometry_ .getX ()), 1.0 );
647
+ EXPECT_LT (std::abs (controller_->odometry_ .getY ()), 1.0 );
648
+ EXPECT_LT (std::abs (controller_->odometry_ .getRz ()), M_PI);
649
+ }
650
+
565
651
int main (int argc, char ** argv)
566
652
{
567
653
::testing::InitGoogleTest (&argc, argv);
0 commit comments