@@ -390,6 +390,84 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
390390 EXPECT_EQ (cmd_vel.twist .angular .z , 1.8 );
391391}
392392
393+ TEST (RotationShimControllerTest, accelerationTests) {
394+ auto ctrl = std::make_shared<RotationShimShim>();
395+ auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(" ShimControllerTest" );
396+ std::string name = " PathFollower" ;
397+ auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock ());
398+ auto listener = std::make_shared<tf2_ros::TransformListener>(*tf, node, true );
399+ auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>(" fake_costmap" );
400+ rclcpp_lifecycle::State state;
401+ costmap->on_configure (state);
402+ auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
403+
404+ geometry_msgs::msg::TransformStamped transform;
405+ transform.header .frame_id = " base_link" ;
406+ transform.child_frame_id = " odom" ;
407+ transform.transform .rotation .x = 0.0 ;
408+ transform.transform .rotation .y = 0.0 ;
409+ transform.transform .rotation .z = 0.0 ;
410+ transform.transform .rotation .w = 1.0 ;
411+ tf_broadcaster->sendTransform (transform);
412+
413+ // set a valid primary controller so we can do lifecycle
414+ node->declare_parameter (
415+ " PathFollower.primary_controller" ,
416+ std::string (" nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" ));
417+ node->declare_parameter (
418+ " controller_frequency" ,
419+ 20.0 );
420+ node->declare_parameter (
421+ " PathFollower.rotate_to_goal_heading" ,
422+ true );
423+ node->declare_parameter (
424+ " PathFollower.max_angular_accel" ,
425+ 0.5 );
426+
427+ auto controller = std::make_shared<RotationShimShim>();
428+ controller->configure (node, name, tf, costmap);
429+ controller->activate ();
430+
431+ // Test state update and path setting
432+ nav_msgs::msg::Path path;
433+ path.header .frame_id = " base_link" ;
434+ path.poses .resize (4 );
435+
436+ geometry_msgs::msg::PoseStamped pose;
437+ pose.header .frame_id = " base_link" ;
438+ geometry_msgs::msg::Twist velocity;
439+ nav2_controller::SimpleGoalChecker checker;
440+ node->declare_parameter (
441+ " checker.xy_goal_tolerance" ,
442+ 1.0 );
443+ checker.initialize (node, " checker" , costmap);
444+
445+ path.header .frame_id = " base_link" ;
446+ path.poses [0 ].pose .position .x = 0.0 ;
447+ path.poses [0 ].pose .position .y = 0.0 ;
448+ path.poses [1 ].pose .position .x = 0.05 ;
449+ path.poses [1 ].pose .position .y = 0.05 ;
450+ path.poses [2 ].pose .position .x = 0.10 ;
451+ path.poses [2 ].pose .position .y = 0.10 ;
452+ // goal position within checker xy_goal_tolerance
453+ path.poses [3 ].pose .position .x = 0.20 ;
454+ path.poses [3 ].pose .position .y = 0.20 ;
455+ // goal heading 45 degrees to the left
456+ path.poses [3 ].pose .orientation .z = -0.3826834 ;
457+ path.poses [3 ].pose .orientation .w = 0.9238795 ;
458+ path.poses [3 ].header .frame_id = " base_link" ;
459+
460+ // Test acceleration limits
461+ controller->setPlan (path);
462+ auto cmd_vel = controller->computeVelocityCommands (pose, velocity, &checker);
463+ EXPECT_EQ (cmd_vel.twist .angular .z , -0.025 );
464+
465+ // Test slowing down to avoid overshooting
466+ velocity.angular .z = -1.8 ;
467+ cmd_vel = controller->computeVelocityCommands (pose, velocity, &checker);
468+ EXPECT_NEAR (cmd_vel.twist .angular .z , -std::sqrt (2 * 0.5 * M_PI / 4 ), 1e-4 );
469+ }
470+
393471TEST (RotationShimControllerTest, isGoalChangedTest)
394472{
395473 auto ctrl = std::make_shared<RotationShimShim>();
0 commit comments