Skip to content

Commit 30e2cde

Browse files
authored
[RotationShimController] Rotate to goal heading (ros-navigation#4332)
When arriving in the goal xy tolerance, the rotation shim controller takes back the control to command the robot to rotate in the goal heading orientation. The initial goal of the rotationShimController was to rotate the robot at the beginning of a navigation towards the paths orientation because some controllers are not good at performing in place rotations. For the same reason, the rotationShimController should be able to rotate the robot towards the goal heading. Signed-off-by: Antoine Gennart <[email protected]>
1 parent b0abc78 commit 30e2cde

File tree

5 files changed

+191
-1
lines changed

5 files changed

+191
-1
lines changed

nav2_rotation_shim_controller/README.md

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@ This is useful for situations when working with plugins that are either too spec
1212

1313
As such, this controller will check the rough heading difference with respect to the robot and a newly received path. If within a threshold, it will pass the request onto the controller to execute. If it is outside of the threshold, this controller will rotate the robot towards that path heading. Once it is within the tolerance, it will then pass off control-execution from this rotation shim controller onto the primary controller plugin. At this point, the robot is still going to be rotating, allowing the current plugin to take control for a smooth hand off into path tracking. It is recommended to be more generous than strict in the angular threshold to allow for a smoother transition, but should be tuned for a specific application's desired behaviors.
1414

15+
When the `rotate_to_goal_heading` parameter is set to true, this controller is also able to take back control of the robot when reaching the XY goal tolerance of the goal checker. In this case, the robot will rotate towards the goal heading until the goal checker validate the goal and ends the current navigation task.
16+
1517
The Rotation Shim Controller is suitable for:
1618
- Robots that can rotate in place, such as differential and omnidirectional robots.
1719
- Preference to rotate in place rather than 'spiral out' when starting to track a new path that is at a significantly different heading than the robot's current heading.
@@ -35,6 +37,7 @@ See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/
3537
| `primary_controller` | Internal controller plugin to use for actual control behavior after rotating to heading |
3638
| `max_angular_accel` | Maximum angular acceleration for rotation to heading |
3739
| `simulate_ahead_time` | Time in seconds to forward simulate a rotation command to check for collisions. If a collision is found, forwards control back to the primary controller plugin. |
40+
| `rotate_to_goal_heading` | If true, the rotationShimController will take back control of the robot when in XY tolerance of the goal and start rotating to the goal heading |
3841

3942
Example fully-described XML with default parameter values:
4043

@@ -66,6 +69,7 @@ controller_server:
6669
rotate_to_heading_angular_vel: 1.8
6770
max_angular_accel: 3.2
6871
simulate_ahead_time: 1.0
72+
rotate_to_goal_heading: false
6973
7074
# DWB parameters
7175
...

nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,13 @@ class RotationShimController : public nav2_core::Controller
115115
*/
116116
geometry_msgs::msg::PoseStamped getSampledPathPt();
117117

118+
/**
119+
* @brief Find the goal point in path
120+
* May throw exception if the path is empty
121+
* @return pt location of the output point
122+
*/
123+
geometry_msgs::msg::PoseStamped getSampledPathGoal();
124+
118125
/**
119126
* @brief Uses TF to find the location of the sampled path point in base frame
120127
* @param pt location of the sampled path point
@@ -168,6 +175,7 @@ class RotationShimController : public nav2_core::Controller
168175
double forward_sampling_distance_, angular_dist_threshold_;
169176
double rotate_to_heading_angular_vel_, max_angular_accel_;
170177
double control_duration_, simulate_ahead_time_;
178+
bool rotate_to_goal_heading_;
171179

172180
// Dynamic parameters handler
173181
std::mutex mutex_;
Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2+
// Copyright (c) 2023 Open Navigation LLC
3+
//
4+
// Licensed under the Apache License, Version 2.0 (the "License");
5+
// you may not use this file except in compliance with the License.
6+
// You may obtain a copy of the License at
7+
//
8+
// http://www.apache.org/licenses/LICENSE-2.0
9+
//
10+
// Unless required by applicable law or agreed to in writing, software
11+
// distributed under the License is distributed on an "AS IS" BASIS,
12+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
// See the License for the specific language governing permissions and
14+
// limitations under the License.
15+
16+
#ifndef NAV2_ROTATION_SHIM_CONTROLLER__TOOLS__UTILS_HPP_
17+
#define NAV2_ROTATION_SHIM_CONTROLLER__TOOLS__UTILS_HPP_
18+
19+
#include "nav2_core/goal_checker.hpp"
20+
#include "geometry_msgs/msg/pose_stamped.hpp"
21+
#include "rclcpp/rclcpp.hpp"
22+
23+
namespace nav2_rotation_shim_controller::utils
24+
{
25+
26+
/**
27+
* @brief get the current pose of the robot
28+
* @param goal_checker goal checker to get tolerances
29+
* @param robot robot pose
30+
* @param goal goal pose
31+
* @return bool Whether the robot is in the distance tolerance ignoring rotation and speed
32+
*/
33+
inline bool withinPositionGoalTolerance(
34+
nav2_core::GoalChecker * goal_checker,
35+
const geometry_msgs::msg::Pose & robot,
36+
const geometry_msgs::msg::Pose & goal)
37+
{
38+
if (goal_checker) {
39+
geometry_msgs::msg::Pose pose_tolerance;
40+
geometry_msgs::msg::Twist velocity_tolerance;
41+
goal_checker->getTolerances(pose_tolerance, velocity_tolerance);
42+
43+
const auto pose_tolerance_sq = pose_tolerance.position.x * pose_tolerance.position.x;
44+
45+
auto dx = robot.position.x - goal.position.x;
46+
auto dy = robot.position.y - goal.position.y;
47+
48+
auto dist_sq = dx * dx + dy * dy;
49+
50+
if (dist_sq < pose_tolerance_sq) {
51+
return true;
52+
}
53+
}
54+
55+
return false;
56+
}
57+
58+
} // namespace nav2_rotation_shim_controller::utils
59+
60+
#endif // NAV2_ROTATION_SHIM_CONTROLLER__TOOLS__UTILS_HPP_

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <utility>
2020

2121
#include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp"
22+
#include "nav2_rotation_shim_controller/tools/utils.hpp"
2223

2324
using rcl_interfaces::msg::ParameterType;
2425

@@ -60,6 +61,8 @@ void RotationShimController::configure(
6061
node, plugin_name_ + ".simulate_ahead_time", rclcpp::ParameterValue(1.0));
6162
nav2_util::declare_parameter_if_not_declared(
6263
node, plugin_name_ + ".primary_controller", rclcpp::PARAMETER_STRING);
64+
nav2_util::declare_parameter_if_not_declared(
65+
node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false));
6366

6467
node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
6568
node->get_parameter(plugin_name_ + ".forward_sampling_distance", forward_sampling_distance_);
@@ -73,6 +76,8 @@ void RotationShimController::configure(
7376
node->get_parameter("controller_frequency", control_frequency);
7477
control_duration_ = 1.0 / control_frequency;
7578

79+
node->get_parameter(plugin_name_ + ".rotate_to_goal_heading", rotate_to_goal_heading_);
80+
7681
try {
7782
primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
7883
RCLCPP_INFO(
@@ -139,6 +144,41 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
139144
const geometry_msgs::msg::Twist & velocity,
140145
nav2_core::GoalChecker * goal_checker)
141146
{
147+
// Rotate to goal heading when in goal xy tolerance
148+
if (rotate_to_goal_heading_) {
149+
std::lock_guard<std::mutex> lock_reinit(mutex_);
150+
151+
try {
152+
geometry_msgs::msg::PoseStamped sampled_pt_goal = getSampledPathGoal();
153+
154+
if (!nav2_util::transformPoseInTargetFrame(
155+
sampled_pt_goal, sampled_pt_goal, *tf_,
156+
pose.header.frame_id))
157+
{
158+
throw nav2_core::ControllerTFError("Failed to transform pose to base frame!");
159+
}
160+
161+
if (utils::withinPositionGoalTolerance(
162+
goal_checker,
163+
pose.pose,
164+
sampled_pt_goal.pose))
165+
{
166+
double pose_yaw = tf2::getYaw(pose.pose.orientation);
167+
double goal_yaw = tf2::getYaw(sampled_pt_goal.pose.orientation);
168+
169+
double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw);
170+
171+
return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
172+
}
173+
} catch (const std::runtime_error & e) {
174+
RCLCPP_INFO(
175+
logger_,
176+
"Rotation Shim Controller was unable to find a goal point,"
177+
" a rotational collision was detected, or TF failed to transform"
178+
" into base frame! what(): %s", e.what());
179+
}
180+
}
181+
142182
if (path_updated_) {
143183
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
144184
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
@@ -198,6 +238,17 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
198238
return current_path_.poses.back();
199239
}
200240

241+
geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()
242+
{
243+
if (current_path_.poses.empty()) {
244+
throw nav2_core::InvalidPath("Path is empty - cannot find a goal point");
245+
}
246+
247+
auto goal = current_path_.poses.back();
248+
goal.header.stamp = clock_->now();
249+
return goal;
250+
}
251+
201252
geometry_msgs::msg::Pose
202253
RotationShimController::transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped & pt)
203254
{
@@ -302,6 +353,10 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
302353
} else if (name == plugin_name_ + ".simulate_ahead_time") {
303354
simulate_ahead_time_ = parameter.as_double();
304355
}
356+
} else if (type == ParameterType::PARAMETER_BOOL) {
357+
if (name == plugin_name_ + ".rotate_to_goal_heading") {
358+
rotate_to_goal_heading_ = parameter.as_bool();
359+
}
305360
}
306361
}
307362

nav2_rotation_shim_controller/test/test_shim_controller.cpp

Lines changed: 64 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -309,6 +309,67 @@ TEST(RotationShimControllerTest, computeVelocityTests)
309309
EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error);
310310
}
311311

312+
TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
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+
"PathFollower.rotate_to_goal_heading",
338+
true);
339+
340+
auto controller = std::make_shared<RotationShimShim>();
341+
controller->configure(node, name, tf, costmap);
342+
controller->activate();
343+
344+
// Test state update and path setting
345+
nav_msgs::msg::Path path;
346+
path.header.frame_id = "fake_frame";
347+
path.poses.resize(4);
348+
349+
geometry_msgs::msg::PoseStamped pose;
350+
pose.header.frame_id = "base_link";
351+
geometry_msgs::msg::Twist velocity;
352+
nav2_controller::SimpleGoalChecker checker;
353+
checker.initialize(node, "checker", costmap);
354+
355+
path.header.frame_id = "base_link";
356+
path.poses[0].pose.position.x = 0.0;
357+
path.poses[0].pose.position.y = 0.0;
358+
path.poses[1].pose.position.x = 0.05;
359+
path.poses[1].pose.position.y = 0.05;
360+
path.poses[2].pose.position.x = 0.10;
361+
path.poses[2].pose.position.y = 0.10;
362+
path.poses[3].pose.position.x = 0.20;
363+
path.poses[3].pose.position.y = 0.20;
364+
path.poses[3].header.frame_id = "base_link";
365+
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
369+
controller->setPlan(path);
370+
EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error);
371+
}
372+
312373
TEST(RotationShimControllerTest, testDynamicParameter)
313374
{
314375
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest");
@@ -338,7 +399,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
338399
rclcpp::Parameter("test.rotate_to_heading_angular_vel", 7.0),
339400
rclcpp::Parameter("test.max_angular_accel", 7.0),
340401
rclcpp::Parameter("test.simulate_ahead_time", 7.0),
341-
rclcpp::Parameter("test.primary_controller", std::string("HI"))});
402+
rclcpp::Parameter("test.primary_controller", std::string("HI")),
403+
rclcpp::Parameter("test.rotate_to_goal_heading", true)});
342404

343405
rclcpp::spin_until_future_complete(
344406
node->get_node_base_interface(),
@@ -349,4 +411,5 @@ TEST(RotationShimControllerTest, testDynamicParameter)
349411
EXPECT_EQ(node->get_parameter("test.rotate_to_heading_angular_vel").as_double(), 7.0);
350412
EXPECT_EQ(node->get_parameter("test.max_angular_accel").as_double(), 7.0);
351413
EXPECT_EQ(node->get_parameter("test.simulate_ahead_time").as_double(), 7.0);
414+
EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true);
352415
}

0 commit comments

Comments
 (0)