-
Notifications
You must be signed in to change notification settings - Fork 1.8k
[RotationShimController] Rotate to goal heading #4332
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
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,60 @@ | ||
| // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov | ||
| // Copyright (c) 2023 Open Navigation LLC | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #ifndef NAV2_ROTATION_SHIM_CONTROLLER__TOOLS__UTILS_HPP_ | ||
| #define NAV2_ROTATION_SHIM_CONTROLLER__TOOLS__UTILS_HPP_ | ||
|
|
||
| #include "nav2_core/goal_checker.hpp" | ||
| #include "geometry_msgs/msg/pose_stamped.hpp" | ||
| #include "rclcpp/rclcpp.hpp" | ||
|
|
||
| namespace nav2_rotation_shim_controller::utils | ||
| { | ||
|
|
||
| /** | ||
| * @brief get the current pose of the robot | ||
| * @param goal_checker goal checker to get tolerances | ||
| * @param robot robot pose | ||
| * @param goal goal pose | ||
| * @return bool Whether the robot is in the distance tolerance ignoring rotation and speed | ||
| */ | ||
| inline bool withinPositionGoalTolerance( | ||
| nav2_core::GoalChecker * goal_checker, | ||
| const geometry_msgs::msg::Pose & robot, | ||
| const geometry_msgs::msg::Pose & goal) | ||
| { | ||
| if (goal_checker) { | ||
| geometry_msgs::msg::Pose pose_tolerance; | ||
| geometry_msgs::msg::Twist velocity_tolerance; | ||
| goal_checker->getTolerances(pose_tolerance, velocity_tolerance); | ||
|
|
||
| const auto pose_tolerance_sq = pose_tolerance.position.x * pose_tolerance.position.x; | ||
|
|
||
| auto dx = robot.position.x - goal.position.x; | ||
| auto dy = robot.position.y - goal.position.y; | ||
|
|
||
| auto dist_sq = dx * dx + dy * dy; | ||
|
|
||
| if (dist_sq < pose_tolerance_sq) { | ||
| return true; | ||
| } | ||
| } | ||
|
|
||
| return false; | ||
| } | ||
|
|
||
| } // namespace nav2_rotation_shim_controller::utils | ||
|
|
||
| #endif // NAV2_ROTATION_SHIM_CONTROLLER__TOOLS__UTILS_HPP_ |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -309,6 +309,67 @@ TEST(RotationShimControllerTest, computeVelocityTests) | |
| EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error); | ||
| } | ||
|
|
||
| TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) { | ||
| auto ctrl = std::make_shared<RotationShimShim>(); | ||
| auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest"); | ||
| std::string name = "PathFollower"; | ||
| auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock()); | ||
| auto listener = std::make_shared<tf2_ros::TransformListener>(*tf, node, true); | ||
| auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>("fake_costmap"); | ||
| rclcpp_lifecycle::State state; | ||
| costmap->on_configure(state); | ||
| auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node); | ||
|
|
||
| geometry_msgs::msg::TransformStamped transform; | ||
| transform.header.frame_id = "base_link"; | ||
| transform.child_frame_id = "odom"; | ||
| transform.transform.rotation.x = 0.0; | ||
| transform.transform.rotation.y = 0.0; | ||
| transform.transform.rotation.z = 0.0; | ||
| transform.transform.rotation.w = 1.0; | ||
| tf_broadcaster->sendTransform(transform); | ||
|
|
||
| // set a valid primary controller so we can do lifecycle | ||
| node->declare_parameter( | ||
| "PathFollower.primary_controller", | ||
| std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController")); | ||
| node->declare_parameter( | ||
| "PathFollower.rotate_to_goal_heading", | ||
| true); | ||
|
|
||
| auto controller = std::make_shared<RotationShimShim>(); | ||
| controller->configure(node, name, tf, costmap); | ||
| controller->activate(); | ||
|
|
||
| // Test state update and path setting | ||
| nav_msgs::msg::Path path; | ||
| path.header.frame_id = "fake_frame"; | ||
| path.poses.resize(4); | ||
|
|
||
| geometry_msgs::msg::PoseStamped pose; | ||
| pose.header.frame_id = "base_link"; | ||
| geometry_msgs::msg::Twist velocity; | ||
| nav2_controller::SimpleGoalChecker checker; | ||
| checker.initialize(node, "checker", costmap); | ||
|
|
||
| path.header.frame_id = "base_link"; | ||
| path.poses[0].pose.position.x = 0.0; | ||
| path.poses[0].pose.position.y = 0.0; | ||
| path.poses[1].pose.position.x = 0.05; | ||
| path.poses[1].pose.position.y = 0.05; | ||
| path.poses[2].pose.position.x = 0.10; | ||
| path.poses[2].pose.position.y = 0.10; | ||
| path.poses[3].pose.position.x = 0.20; | ||
| path.poses[3].pose.position.y = 0.20; | ||
| 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); | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This test consistently fails for me on rolling. @gennartan would it be possible for you to check it out? It failed on CI too . No idea how it passed for the PR
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Ah sorry, just saw Steve commented already
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I fixed the error related to the But I am still getting error while testing and I cannot figure out what is causing it. Could you help me @tonynajjar or @SteveMacenski ?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It seems that I am only getting these test error locally, I created a PR and this error doesn't show up. See the PR: #4391 However the release tests still fails, but not for the rotationShimController |
||
| } | ||
|
|
||
| TEST(RotationShimControllerTest, testDynamicParameter) | ||
| { | ||
| auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest"); | ||
|
|
@@ -338,7 +399,8 @@ TEST(RotationShimControllerTest, testDynamicParameter) | |
| rclcpp::Parameter("test.rotate_to_heading_angular_vel", 7.0), | ||
| rclcpp::Parameter("test.max_angular_accel", 7.0), | ||
| rclcpp::Parameter("test.simulate_ahead_time", 7.0), | ||
| rclcpp::Parameter("test.primary_controller", std::string("HI"))}); | ||
| rclcpp::Parameter("test.primary_controller", std::string("HI")), | ||
| rclcpp::Parameter("test.rotate_to_goal_heading", true)}); | ||
|
|
||
| rclcpp::spin_until_future_complete( | ||
| node->get_node_base_interface(), | ||
|
|
@@ -349,4 +411,5 @@ TEST(RotationShimControllerTest, testDynamicParameter) | |
| EXPECT_EQ(node->get_parameter("test.rotate_to_heading_angular_vel").as_double(), 7.0); | ||
| EXPECT_EQ(node->get_parameter("test.max_angular_accel").as_double(), 7.0); | ||
| EXPECT_EQ(node->get_parameter("test.simulate_ahead_time").as_double(), 7.0); | ||
| EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true); | ||
| } | ||
Uh oh!
There was an error while loading. Please reload this page.