Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[RotationShimController] Fix test for rotate to goal heading (#4289) #4391

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 17 additions & 5 deletions nav2_rotation_shim_controller/test/test_shim_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,13 +343,16 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {

// Test state update and path setting
nav_msgs::msg::Path path;
path.header.frame_id = "fake_frame";
path.header.frame_id = "base_link";
path.poses.resize(4);

geometry_msgs::msg::PoseStamped pose;
pose.header.frame_id = "base_link";
geometry_msgs::msg::Twist velocity;
nav2_controller::SimpleGoalChecker checker;
node->declare_parameter(
"checker.xy_goal_tolerance",
1.0);
checker.initialize(node, "checker", costmap);

path.header.frame_id = "base_link";
Expand All @@ -359,15 +362,24 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
path.poses[1].pose.position.y = 0.05;
path.poses[2].pose.position.x = 0.10;
path.poses[2].pose.position.y = 0.10;
// goal position within checker xy_goal_tolerance
path.poses[3].pose.position.x = 0.20;
path.poses[3].pose.position.y = 0.20;
// goal heading 45 degrees to the left
path.poses[3].pose.orientation.z = -0.3826834;
path.poses[3].pose.orientation.w = 0.9238795;
path.poses[3].header.frame_id = "base_link";

// this should make the goal checker to validated the fact that the robot is in range
// of the goal. The rotation shim controller should rotate toward the goal heading
// then it will throw an exception because the costmap is bogus
controller->setPlan(path);
EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error);
auto cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker);
EXPECT_EQ(cmd_vel.twist.angular.z, -1.8);

// goal heading 45 degrees to the right
path.poses[3].pose.orientation.z = 0.3826834;
path.poses[3].pose.orientation.w = 0.9238795;
controller->setPlan(path);
cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker);
EXPECT_EQ(cmd_vel.twist.angular.z, 1.8);
}

TEST(RotationShimControllerTest, testDynamicParameter)
Expand Down
Loading