@@ -309,6 +309,84 @@ TEST(RotationShimControllerTest, computeVelocityTests)
309309 EXPECT_THROW (controller->computeVelocityCommands (pose, velocity, &checker), std::runtime_error);
310310}
311311
312+ TEST (RotationShimControllerTest, openLoopRotationTests) {
313+ auto ctrl = std::make_shared<RotationShimShim>();
314+ auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(" ShimControllerTest" );
315+ std::string name = " PathFollower" ;
316+ auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock ());
317+ auto listener = std::make_shared<tf2_ros::TransformListener>(*tf, node, true );
318+ auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>(" fake_costmap" );
319+ rclcpp_lifecycle::State state;
320+ costmap->on_configure (state);
321+ auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
322+
323+ geometry_msgs::msg::TransformStamped transform;
324+ transform.header .frame_id = " base_link" ;
325+ transform.child_frame_id = " odom" ;
326+ transform.transform .rotation .x = 0.0 ;
327+ transform.transform .rotation .y = 0.0 ;
328+ transform.transform .rotation .z = 0.0 ;
329+ transform.transform .rotation .w = 1.0 ;
330+ tf_broadcaster->sendTransform (transform);
331+
332+ // set a valid primary controller so we can do lifecycle
333+ node->declare_parameter (
334+ " PathFollower.primary_controller" ,
335+ std::string (" nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" ));
336+ node->declare_parameter (
337+ " controller_frequency" ,
338+ 20.0 );
339+ node->declare_parameter (
340+ " PathFollower.rotate_to_goal_heading" ,
341+ true );
342+ node->declare_parameter (
343+ " PathFollower.closed_loop" ,
344+ false );
345+
346+ auto controller = std::make_shared<RotationShimShim>();
347+ controller->configure (node, name, tf, costmap);
348+ controller->activate ();
349+
350+ // Test state update and path setting
351+ nav_msgs::msg::Path path;
352+ path.header .frame_id = " base_link" ;
353+ path.poses .resize (4 );
354+
355+ geometry_msgs::msg::PoseStamped pose;
356+ pose.header .frame_id = " base_link" ;
357+ geometry_msgs::msg::Twist velocity;
358+ nav2_controller::SimpleGoalChecker checker;
359+ node->declare_parameter (
360+ " checker.xy_goal_tolerance" ,
361+ 1.0 );
362+ checker.initialize (node, " checker" , costmap);
363+
364+ path.header .frame_id = " base_link" ;
365+ path.poses [0 ].pose .position .x = 0.0 ;
366+ path.poses [0 ].pose .position .y = 0.0 ;
367+ path.poses [1 ].pose .position .x = 0.05 ;
368+ path.poses [1 ].pose .position .y = 0.05 ;
369+ path.poses [2 ].pose .position .x = 0.10 ;
370+ path.poses [2 ].pose .position .y = 0.10 ;
371+ // goal position within checker xy_goal_tolerance
372+ path.poses [3 ].pose .position .x = 0.20 ;
373+ path.poses [3 ].pose .position .y = 0.20 ;
374+ // goal heading 45 degrees to the left
375+ path.poses [3 ].pose .orientation .z = -0.3826834 ;
376+ path.poses [3 ].pose .orientation .w = 0.9238795 ;
377+ path.poses [3 ].header .frame_id = " base_link" ;
378+
379+ // Calculate first velocity command
380+ controller->setPlan (path);
381+ auto cmd_vel = controller->computeVelocityCommands (pose, velocity, &checker);
382+ EXPECT_NEAR (cmd_vel.twist .angular .z , -0.16 , 1e-4 );
383+
384+ // Test second velocity command with wrong odometry
385+ velocity.angular .z = 1.8 ;
386+ cmd_vel = controller->computeVelocityCommands (pose, velocity, &checker);
387+ EXPECT_NEAR (cmd_vel.twist .angular .z , -0.32 , 1e-4 );
388+ }
389+
312390TEST (RotationShimControllerTest, computeVelocityGoalRotationTests) {
313391 auto ctrl = std::make_shared<RotationShimShim>();
314392 auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(" ShimControllerTest" );
@@ -412,7 +490,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
412490 rclcpp::Parameter (" test.max_angular_accel" , 7.0 ),
413491 rclcpp::Parameter (" test.simulate_ahead_time" , 7.0 ),
414492 rclcpp::Parameter (" test.primary_controller" , std::string (" HI" )),
415- rclcpp::Parameter (" test.rotate_to_goal_heading" , true )});
493+ rclcpp::Parameter (" test.rotate_to_goal_heading" , true ),
494+ rclcpp::Parameter (" test.closed_loop" , false )});
416495
417496 rclcpp::spin_until_future_complete (
418497 node->get_node_base_interface (),
@@ -424,4 +503,5 @@ TEST(RotationShimControllerTest, testDynamicParameter)
424503 EXPECT_EQ (node->get_parameter (" test.max_angular_accel" ).as_double (), 7.0 );
425504 EXPECT_EQ (node->get_parameter (" test.simulate_ahead_time" ).as_double (), 7.0 );
426505 EXPECT_EQ (node->get_parameter (" test.rotate_to_goal_heading" ).as_bool (), true );
506+ EXPECT_EQ (node->get_parameter (" test.closed_loop" ).as_bool (), false );
427507}
0 commit comments