Skip to content

Commit 5fb99ff

Browse files
gennartanstevedanomodolor
authored andcommitted
[RotationShimController] Fix test for rotate to goal heading (ros-navigation#4289) (ros-navigation#4391)
* Fix rotate to goal heading tests Signed-off-by: Antoine Gennart <[email protected]> Signed-off-by: stevedanomodolor <[email protected]>
1 parent 628537a commit 5fb99ff

File tree

1 file changed

+17
-5
lines changed

1 file changed

+17
-5
lines changed

nav2_rotation_shim_controller/test/test_shim_controller.cpp

Lines changed: 17 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -343,13 +343,16 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
343343

344344
// Test state update and path setting
345345
nav_msgs::msg::Path path;
346-
path.header.frame_id = "fake_frame";
346+
path.header.frame_id = "base_link";
347347
path.poses.resize(4);
348348

349349
geometry_msgs::msg::PoseStamped pose;
350350
pose.header.frame_id = "base_link";
351351
geometry_msgs::msg::Twist velocity;
352352
nav2_controller::SimpleGoalChecker checker;
353+
node->declare_parameter(
354+
"checker.xy_goal_tolerance",
355+
1.0);
353356
checker.initialize(node, "checker", costmap);
354357

355358
path.header.frame_id = "base_link";
@@ -359,15 +362,24 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
359362
path.poses[1].pose.position.y = 0.05;
360363
path.poses[2].pose.position.x = 0.10;
361364
path.poses[2].pose.position.y = 0.10;
365+
// goal position within checker xy_goal_tolerance
362366
path.poses[3].pose.position.x = 0.20;
363367
path.poses[3].pose.position.y = 0.20;
368+
// goal heading 45 degrees to the left
369+
path.poses[3].pose.orientation.z = -0.3826834;
370+
path.poses[3].pose.orientation.w = 0.9238795;
364371
path.poses[3].header.frame_id = "base_link";
365372

366-
// this should make the goal checker to validated the fact that the robot is in range
367-
// of the goal. The rotation shim controller should rotate toward the goal heading
368-
// then it will throw an exception because the costmap is bogus
369373
controller->setPlan(path);
370-
EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error);
374+
auto cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker);
375+
EXPECT_EQ(cmd_vel.twist.angular.z, -1.8);
376+
377+
// goal heading 45 degrees to the right
378+
path.poses[3].pose.orientation.z = 0.3826834;
379+
path.poses[3].pose.orientation.w = 0.9238795;
380+
controller->setPlan(path);
381+
cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker);
382+
EXPECT_EQ(cmd_vel.twist.angular.z, 1.8);
371383
}
372384

373385
TEST(RotationShimControllerTest, testDynamicParameter)

0 commit comments

Comments
 (0)