Skip to content

Commit 94d3a9d

Browse files
committed
[RotationShimController] Rotate to goal heading
When arriving in the goal xy tolerance, the rotation shim controller takes back the control and perform the necessary rotation to be in the correct goal orientation. This can be useful when the final orientaion of the robot matters. It can also simplify the configuration of the primary controller since it would not have to be configured to be able to reach the target orientation.
1 parent 1f980a1 commit 94d3a9d

File tree

3 files changed

+147
-1
lines changed

3 files changed

+147
-1
lines changed

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_;

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ void RotationShimController::configure(
6060
node, plugin_name_ + ".simulate_ahead_time", rclcpp::ParameterValue(1.0));
6161
nav2_util::declare_parameter_if_not_declared(
6262
node, plugin_name_ + ".primary_controller", rclcpp::PARAMETER_STRING);
63+
nav2_util::declare_parameter_if_not_declared(
64+
node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false));
6365

6466
node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
6567
node->get_parameter(plugin_name_ + ".forward_sampling_distance", forward_sampling_distance_);
@@ -73,6 +75,8 @@ void RotationShimController::configure(
7375
node->get_parameter("controller_frequency", control_frequency);
7476
control_duration_ = 1.0 / control_frequency;
7577

78+
node->get_parameter("rotate_to_goal_heading", rotate_to_goal_heading_);
79+
7680
try {
7781
primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
7882
RCLCPP_INFO(
@@ -134,11 +138,71 @@ void RotationShimController::cleanup()
134138
primary_controller_.reset();
135139
}
136140

141+
/**
142+
* @brief Check if the robot pose is within the Goal Checker's tolerances to goal
143+
* @param global_checker Pointer to the goal checker
144+
* @param robot Pose of robot
145+
* @param path Path to retreive goal pose from
146+
* @return bool If robot is within goal checker tolerances to the goal
147+
*/
148+
static bool withinPositionGoalTolerance(
149+
nav2_core::GoalChecker * goal_checker,
150+
const geometry_msgs::msg::Pose & robot,
151+
const geometry_msgs::msg::Pose & goal)
152+
{
153+
if (goal_checker) {
154+
geometry_msgs::msg::Pose pose_tolerance;
155+
geometry_msgs::msg::Twist velocity_tolerance;
156+
goal_checker->getTolerances(pose_tolerance, velocity_tolerance);
157+
158+
const auto pose_tolerance_sq = pose_tolerance.position.x * pose_tolerance.position.x;
159+
160+
auto dx = robot.position.x - goal.position.x;
161+
auto dy = robot.position.y - goal.position.y;
162+
163+
auto dist_sq = dx * dx + dy * dy;
164+
165+
if (dist_sq < pose_tolerance_sq) {
166+
return true;
167+
}
168+
}
169+
170+
return false;
171+
}
172+
137173
geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands(
138174
const geometry_msgs::msg::PoseStamped & pose,
139175
const geometry_msgs::msg::Twist & velocity,
140176
nav2_core::GoalChecker * goal_checker)
141177
{
178+
// Rotate to goal heading when in goal xy tolerance
179+
if (rotate_to_goal_heading_) {
180+
std::lock_guard<std::mutex> lock_reinit(mutex_);
181+
182+
try {
183+
geometry_msgs::msg::Pose sampled_pt_goal = transformPoseToBaseFrame(getSampledPathGoal());
184+
if (withinPositionGoalTolerance(goal_checker, pose.pose, sampled_pt_goal)) {
185+
double pose_yaw, pose_pitch, pose_roll;
186+
double goal_yaw, goal_pitch, goal_roll;
187+
tf2::getEulerYPR(pose.pose.orientation, pose_yaw, pose_pitch, pose_roll);
188+
tf2::getEulerYPR(sampled_pt_goal.orientation, goal_yaw, goal_pitch, goal_roll);
189+
190+
double angular_distance_to_heading = std::abs(goal_yaw - pose_yaw);
191+
if (angular_distance_to_heading > M_PI) {
192+
angular_distance_to_heading -= M_PI;
193+
}
194+
195+
return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
196+
}
197+
} catch (const std::runtime_error & e) {
198+
RCLCPP_INFO(
199+
logger_,
200+
"Rotation Shim Controller was unable to find a goal point,"
201+
" a rotational collision was detected, or TF failed to transform"
202+
" into base frame! what(): %s", e.what());
203+
}
204+
}
205+
142206
if (path_updated_) {
143207
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
144208
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
@@ -201,6 +265,16 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
201265
"passing off to primary controller plugin.", forward_sampling_distance_));
202266
}
203267

268+
geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()
269+
{
270+
if (current_path_.poses.size() == 0) {
271+
throw nav2_core::ControllerException(
272+
"Path is empty - cannot find a goal point");
273+
}
274+
275+
return current_path_.poses[current_path_.poses.size() - 1];
276+
}
277+
204278
geometry_msgs::msg::Pose
205279
RotationShimController::transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped & pt)
206280
{
@@ -306,6 +380,9 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
306380
simulate_ahead_time_ = parameter.as_double();
307381
}
308382
}
383+
if (name == plugin_name_ + ".rotate_to_goal_heading") {
384+
rotate_to_goal_heading_ = parameter.as_bool();
385+
}
309386
}
310387

311388
result.successful = true;

nav2_rotation_shim_controller/test/test_shim_controller.cpp

Lines changed: 62 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -309,6 +309,65 @@ 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[1].pose.position.x = 0.05;
357+
path.poses[1].pose.position.y = 0.05;
358+
path.poses[2].pose.position.x = 0.10;
359+
path.poses[2].pose.position.y = 0.10;
360+
path.poses[3].pose.position.x = 0.20;
361+
path.poses[3].pose.position.y = 0.20;
362+
path.poses[3].header.frame_id = "base_link";
363+
364+
// this should make the goal checker to validated the fact that the robot is in range
365+
// of the goal. The rotation shim controller should rotate toward the goal heading
366+
// then it will throw an exception because the costmap is bogus
367+
controller->setPlan(path);
368+
controller->computeVelocityCommands(pose, velocity, &checker);
369+
}
370+
312371
TEST(RotationShimControllerTest, testDynamicParameter)
313372
{
314373
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest");
@@ -338,7 +397,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
338397
rclcpp::Parameter("test.rotate_to_heading_angular_vel", 7.0),
339398
rclcpp::Parameter("test.max_angular_accel", 7.0),
340399
rclcpp::Parameter("test.simulate_ahead_time", 7.0),
341-
rclcpp::Parameter("test.primary_controller", std::string("HI"))});
400+
rclcpp::Parameter("test.primary_controller", std::string("HI")),
401+
rclcpp::Parameter("test.rotate_to_goal_heading", true)});
342402

343403
rclcpp::spin_until_future_complete(
344404
node->get_node_base_interface(),
@@ -349,4 +409,5 @@ TEST(RotationShimControllerTest, testDynamicParameter)
349409
EXPECT_EQ(node->get_parameter("test.rotate_to_heading_angular_vel").as_double(), 7.0);
350410
EXPECT_EQ(node->get_parameter("test.max_angular_accel").as_double(), 7.0);
351411
EXPECT_EQ(node->get_parameter("test.simulate_ahead_time").as_double(), 7.0);
412+
EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true);
352413
}

0 commit comments

Comments
 (0)