@@ -62,6 +62,11 @@ class RotationShimShim : public nav2_rotation_shim_controller::RotationShimContr
6262 return getSampledPathPt ();
6363 }
6464
65+ bool isGoalChangedWrapper (const nav_msgs::msg::Path & path)
66+ {
67+ return isGoalChanged (path);
68+ }
69+
6570 geometry_msgs::msg::Pose transformPoseToBaseFrameWrapper (geometry_msgs::msg::PoseStamped pt)
6671 {
6772 return transformPoseToBaseFrame (pt);
@@ -382,6 +387,57 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
382387 EXPECT_EQ (cmd_vel.twist .angular .z , 1.8 );
383388}
384389
390+ TEST (RotationShimControllerTest, isGoalChangedTest)
391+ {
392+ auto ctrl = std::make_shared<RotationShimShim>();
393+ auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(" ShimControllerTest" );
394+ std::string name = " PathFollower" ;
395+ auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock ());
396+ auto listener = std::make_shared<tf2_ros::TransformListener>(*tf, node, true );
397+ auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>(" fake_costmap" );
398+ rclcpp_lifecycle::State state;
399+ costmap->on_configure (state);
400+ auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
401+
402+ geometry_msgs::msg::TransformStamped transform;
403+ transform.header .frame_id = " base_link" ;
404+ transform.child_frame_id = " odom" ;
405+ transform.transform .rotation .x = 0.0 ;
406+ transform.transform .rotation .y = 0.0 ;
407+ transform.transform .rotation .z = 0.0 ;
408+ transform.transform .rotation .w = 1.0 ;
409+ tf_broadcaster->sendTransform (transform);
410+
411+ // set a valid primary controller so we can do lifecycle
412+ node->declare_parameter (
413+ " PathFollower.primary_controller" ,
414+ std::string (" nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" ));
415+ node->declare_parameter (
416+ " PathFollower.rotate_to_heading_once" ,
417+ true );
418+
419+ auto controller = std::make_shared<RotationShimShim>();
420+ controller->configure (node, name, tf, costmap);
421+ controller->activate ();
422+
423+ nav_msgs::msg::Path path;
424+ path.header .frame_id = " base_link" ;
425+ path.poses .resize (2 );
426+ path.poses .back ().pose .position .x = 2.0 ;
427+ path.poses .back ().pose .position .y = 2.0 ;
428+
429+ // Test: Current path is empty, should return true
430+ EXPECT_EQ (controller->isGoalChangedWrapper (path), true );
431+
432+ // Test: Last pose of the current path is the same, should return false
433+ controller->setPlan (path);
434+ EXPECT_EQ (controller->isGoalChangedWrapper (path), false );
435+
436+ // Test: Last pose of the current path differs, should return true
437+ path.poses .back ().pose .position .x = 3.0 ;
438+ EXPECT_EQ (controller->isGoalChangedWrapper (path), true );
439+ }
440+
385441TEST (RotationShimControllerTest, testDynamicParameter)
386442{
387443 auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(" ShimControllerTest" );
@@ -412,7 +468,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
412468 rclcpp::Parameter (" test.max_angular_accel" , 7.0 ),
413469 rclcpp::Parameter (" test.simulate_ahead_time" , 7.0 ),
414470 rclcpp::Parameter (" test.primary_controller" , std::string (" HI" )),
415- rclcpp::Parameter (" test.rotate_to_goal_heading" , true )});
471+ rclcpp::Parameter (" test.rotate_to_goal_heading" , true ),
472+ rclcpp::Parameter (" test.rotate_to_heading_once" , true )});
416473
417474 rclcpp::spin_until_future_complete (
418475 node->get_node_base_interface (),
@@ -424,4 +481,5 @@ TEST(RotationShimControllerTest, testDynamicParameter)
424481 EXPECT_EQ (node->get_parameter (" test.max_angular_accel" ).as_double (), 7.0 );
425482 EXPECT_EQ (node->get_parameter (" test.simulate_ahead_time" ).as_double (), 7.0 );
426483 EXPECT_EQ (node->get_parameter (" test.rotate_to_goal_heading" ).as_bool (), true );
484+ EXPECT_EQ (node->get_parameter (" test.rotate_to_heading_once" ).as_bool (), true );
427485}
0 commit comments