Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
nav2_rotation_shim_controller.cpp
1 // Copyright (c) 2021 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <algorithm>
16 #include <string>
17 #include <memory>
18 #include <vector>
19 #include <utility>
20 
21 #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp"
22 
23 using rcl_interfaces::msg::ParameterType;
24 
25 namespace nav2_rotation_shim_controller
26 {
27 
29 : lp_loader_("nav2_core", "nav2_core::Controller"),
30  primary_controller_(nullptr),
31  path_updated_(false),
32  in_rotation_(false)
33 {
34 }
35 
37  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
38  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
39  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
40 {
41  position_goal_checker_ = std::make_unique<nav2_controller::PositionGoalChecker>();
42  position_goal_checker_->initialize(parent, plugin_name_ + ".position_checker", costmap_ros);
43  plugin_name_ = name;
44  node_ = parent;
45  auto node = parent.lock();
46 
47  tf_ = tf;
48  costmap_ros_ = costmap_ros;
49  logger_ = node->get_logger();
50  clock_ = node->get_clock();
51 
52  std::string primary_controller;
53  double control_frequency;
54  nav2_util::declare_parameter_if_not_declared(
55  node, plugin_name_ + ".angular_dist_threshold", rclcpp::ParameterValue(0.785)); // 45 deg
56  nav2_util::declare_parameter_if_not_declared(
57  node, plugin_name_ + ".angular_disengage_threshold", rclcpp::ParameterValue(0.785 / 2.0));
58  nav2_util::declare_parameter_if_not_declared(
59  node, plugin_name_ + ".forward_sampling_distance", rclcpp::ParameterValue(0.5));
60  nav2_util::declare_parameter_if_not_declared(
61  node, plugin_name_ + ".rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.8));
62  nav2_util::declare_parameter_if_not_declared(
63  node, plugin_name_ + ".max_angular_accel", rclcpp::ParameterValue(3.2));
64  nav2_util::declare_parameter_if_not_declared(
65  node, plugin_name_ + ".simulate_ahead_time", rclcpp::ParameterValue(1.0));
66  nav2_util::declare_parameter_if_not_declared(
67  node, plugin_name_ + ".primary_controller", rclcpp::PARAMETER_STRING);
68  nav2_util::declare_parameter_if_not_declared(
69  node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false));
70  nav2_util::declare_parameter_if_not_declared(
71  node, plugin_name_ + ".rotate_to_heading_once", rclcpp::ParameterValue(false));
72  nav2_util::declare_parameter_if_not_declared(
73  node, plugin_name_ + ".closed_loop", rclcpp::ParameterValue(true));
74  nav2_util::declare_parameter_if_not_declared(
75  node, plugin_name_ + ".use_path_orientations", rclcpp::ParameterValue(false));
76 
77  node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
78  node->get_parameter(plugin_name_ + ".angular_disengage_threshold", angular_disengage_threshold_);
79  node->get_parameter(plugin_name_ + ".forward_sampling_distance", forward_sampling_distance_);
80  node->get_parameter(
81  plugin_name_ + ".rotate_to_heading_angular_vel",
82  rotate_to_heading_angular_vel_);
83  node->get_parameter(plugin_name_ + ".max_angular_accel", max_angular_accel_);
84  node->get_parameter(plugin_name_ + ".simulate_ahead_time", simulate_ahead_time_);
85 
86  primary_controller = node->get_parameter(plugin_name_ + ".primary_controller").as_string();
87  node->get_parameter("controller_frequency", control_frequency);
88  control_duration_ = 1.0 / control_frequency;
89 
90  node->get_parameter(plugin_name_ + ".rotate_to_goal_heading", rotate_to_goal_heading_);
91  node->get_parameter(plugin_name_ + ".rotate_to_heading_once", rotate_to_heading_once_);
92  node->get_parameter(plugin_name_ + ".closed_loop", closed_loop_);
93  node->get_parameter(plugin_name_ + ".use_path_orientations", use_path_orientations_);
94 
95  try {
96  primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
97  RCLCPP_INFO(
98  logger_, "Created internal controller for rotation shimming: %s of type %s",
99  plugin_name_.c_str(), primary_controller.c_str());
100  } catch (const pluginlib::PluginlibException & ex) {
101  RCLCPP_FATAL(
102  logger_,
103  "Failed to create internal controller for rotation shimming. Exception: %s", ex.what());
104  return;
105  }
106 
107  primary_controller_->configure(parent, name, tf, costmap_ros);
108 
109  // initialize collision checker and set costmap
110  collision_checker_ = std::make_unique<nav2_costmap_2d::
111  FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros->getCostmap());
112 }
113 
115 {
116  RCLCPP_INFO(
117  logger_,
118  "Activating controller: %s of type "
119  "nav2_rotation_shim_controller::RotationShimController",
120  plugin_name_.c_str());
121 
122  primary_controller_->activate();
123  in_rotation_ = false;
124  last_angular_vel_ = std::numeric_limits<double>::max();
125 
126  auto node = node_.lock();
127  dyn_params_handler_ = node->add_on_set_parameters_callback(
128  std::bind(
130  this, std::placeholders::_1));
131  position_goal_checker_->reset();
132 }
133 
135 {
136  RCLCPP_INFO(
137  logger_,
138  "Deactivating controller: %s of type "
139  "nav2_rotation_shim_controller::RotationShimController",
140  plugin_name_.c_str());
141 
142  primary_controller_->deactivate();
143 
144  if (auto node = node_.lock()) {
145  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
146  }
147  dyn_params_handler_.reset();
148 }
149 
151 {
152  RCLCPP_INFO(
153  logger_,
154  "Cleaning up controller: %s of type "
155  "nav2_rotation_shim_controller::RotationShimController",
156  plugin_name_.c_str());
157 
158  primary_controller_->cleanup();
159  primary_controller_.reset();
160  position_goal_checker_.reset();
161 }
162 
163 geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands(
164  const geometry_msgs::msg::PoseStamped & pose,
165  const geometry_msgs::msg::Twist & velocity,
166  nav2_core::GoalChecker * goal_checker)
167 {
168  // Rotate to goal heading when in goal xy tolerance
169  if (rotate_to_goal_heading_) {
170  std::lock_guard<std::mutex> lock_reinit(mutex_);
171 
172  try {
173  geometry_msgs::msg::PoseStamped sampled_pt_goal = getSampledPathGoal();
174 
175  if (!nav2_util::transformPoseInTargetFrame(
176  sampled_pt_goal, sampled_pt_goal, *tf_,
177  pose.header.frame_id))
178  {
179  throw nav2_core::ControllerTFError("Failed to transform pose to base frame!");
180  }
181 
182  geometry_msgs::msg::Pose pose_tolerance;
183  geometry_msgs::msg::Twist vel_tolerance;
184  goal_checker->getTolerances(pose_tolerance, vel_tolerance);
185  position_goal_checker_->setXYGoalTolerance(pose_tolerance.position.x);
186 
187  if (position_goal_checker_->isGoalReached(pose.pose, sampled_pt_goal.pose, velocity)) {
188  double pose_yaw = tf2::getYaw(pose.pose.orientation);
189  double goal_yaw = tf2::getYaw(sampled_pt_goal.pose.orientation);
190 
191  double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw);
192 
193  auto cmd_vel = computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
194  last_angular_vel_ = cmd_vel.twist.angular.z;
195  return cmd_vel;
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 
206  if (path_updated_) {
207  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
208  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
209 
210  std::lock_guard<std::mutex> lock_reinit(mutex_);
211  try {
212  auto sampled_pt = getSampledPathPt();
213  double angular_distance_to_heading;
214  if (use_path_orientations_) {
215  angular_distance_to_heading = angles::shortest_angular_distance(
216  tf2::getYaw(pose.pose.orientation),
217  tf2::getYaw(sampled_pt.pose.orientation));
218  } else {
219  geometry_msgs::msg::Pose sampled_pt_base = transformPoseToBaseFrame(sampled_pt);
220  angular_distance_to_heading = std::atan2(
221  sampled_pt_base.position.y,
222  sampled_pt_base.position.x);
223  }
224 
225  double angular_thresh =
226  in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
227  if (abs(angular_distance_to_heading) > angular_thresh) {
228  RCLCPP_DEBUG(
229  logger_,
230  "Robot is not within the new path's rough heading, rotating to heading...");
231  in_rotation_ = true;
232  auto cmd_vel = computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
233  last_angular_vel_ = cmd_vel.twist.angular.z;
234  return cmd_vel;
235  } else {
236  RCLCPP_DEBUG(
237  logger_,
238  "Robot is at the new path's rough heading, passing to controller");
239  path_updated_ = false;
240  }
241  } catch (const std::runtime_error & e) {
242  RCLCPP_DEBUG(
243  logger_,
244  "Rotation Shim Controller was unable to find a sampling point,"
245  " a rotational collision was detected, or TF failed to transform"
246  " into base frame! what(): %s", e.what());
247  path_updated_ = false;
248  }
249  }
250 
251  // If at this point, use the primary controller to path track
252  in_rotation_ = false;
253  auto cmd_vel = primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
254  last_angular_vel_ = cmd_vel.twist.angular.z;
255  return cmd_vel;
256 }
257 
258 geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
259 {
260  if (current_path_.poses.size() < 2) {
262  "Path is too short to find a valid sampled path point for rotation.");
263  }
264 
265  geometry_msgs::msg::Pose start = current_path_.poses.front().pose;
266  double dx, dy;
267 
268  // Find the first point at least sampling distance away
269  for (unsigned int i = 1; i != current_path_.poses.size(); i++) {
270  dx = current_path_.poses[i].pose.position.x - start.position.x;
271  dy = current_path_.poses[i].pose.position.y - start.position.y;
272  if (hypot(dx, dy) >= forward_sampling_distance_) {
273  current_path_.poses[i].header.frame_id = current_path_.header.frame_id;
274  current_path_.poses[i].header.stamp = clock_->now(); // Get current time transformation
275  return current_path_.poses[i];
276  }
277  }
278 
279  auto goal = current_path_.poses.back();
280  goal.header.frame_id = current_path_.header.frame_id;
281  goal.header.stamp = clock_->now();
282  return goal;
283 }
284 
285 geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()
286 {
287  if (current_path_.poses.empty()) {
288  throw nav2_core::InvalidPath("Path is empty - cannot find a goal point");
289  }
290 
291  auto goal = current_path_.poses.back();
292  goal.header.frame_id = current_path_.header.frame_id;
293  goal.header.stamp = clock_->now();
294  return goal;
295 }
296 
297 geometry_msgs::msg::Pose
298 RotationShimController::transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped & pt)
299 {
300  geometry_msgs::msg::PoseStamped pt_base;
301  if (!nav2_util::transformPoseInTargetFrame(pt, pt_base, *tf_, costmap_ros_->getBaseFrameID())) {
302  throw nav2_core::ControllerTFError("Failed to transform pose to base frame!");
303  }
304  return pt_base.pose;
305 }
306 
307 geometry_msgs::msg::TwistStamped
309  const double & angular_distance_to_heading,
310  const geometry_msgs::msg::PoseStamped & pose,
311  const geometry_msgs::msg::Twist & velocity)
312 {
313  auto current = closed_loop_ ? velocity.angular.z : last_angular_vel_;
314  if (current == std::numeric_limits<double>::max()) {
315  current = 0.0;
316  }
317 
318  geometry_msgs::msg::TwistStamped cmd_vel;
319  cmd_vel.header = pose.header;
320  const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0;
321  const double angular_vel = sign * rotate_to_heading_angular_vel_;
322  const double & dt = control_duration_;
323  const double min_feasible_angular_speed = current - max_angular_accel_ * dt;
324  const double max_feasible_angular_speed = current + max_angular_accel_ * dt;
325  cmd_vel.twist.angular.z =
326  std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
327 
328  // Check if we need to slow down to avoid overshooting
329  double max_vel_to_stop = std::sqrt(2 * max_angular_accel_ * fabs(angular_distance_to_heading));
330  if (fabs(cmd_vel.twist.angular.z) > max_vel_to_stop) {
331  cmd_vel.twist.angular.z = sign * max_vel_to_stop;
332  }
333 
334  isCollisionFree(cmd_vel, angular_distance_to_heading, pose);
335  return cmd_vel;
336 }
337 
339  const geometry_msgs::msg::TwistStamped & cmd_vel,
340  const double & angular_distance_to_heading,
341  const geometry_msgs::msg::PoseStamped & pose)
342 {
343  // Simulate rotation ahead by time in control frequency increments
344  double simulated_time = 0.0;
345  double initial_yaw = tf2::getYaw(pose.pose.orientation);
346  double yaw = 0.0;
347  double footprint_cost = 0.0;
348  double remaining_rotation_before_thresh =
349  fabs(angular_distance_to_heading) - angular_dist_threshold_;
350 
351  while (simulated_time < simulate_ahead_time_) {
352  simulated_time += control_duration_;
353  yaw = initial_yaw + cmd_vel.twist.angular.z * simulated_time;
354 
355  // Stop simulating past the point it would be passed onto the primary controller
356  if (angles::shortest_angular_distance(yaw, initial_yaw) >= remaining_rotation_before_thresh) {
357  break;
358  }
359 
360  using namespace nav2_costmap_2d; // NOLINT
361  footprint_cost = collision_checker_->footprintCostAtPose(
362  pose.pose.position.x, pose.pose.position.y,
363  yaw, costmap_ros_->getRobotFootprint());
364 
365  if (footprint_cost == static_cast<double>(NO_INFORMATION) &&
366  costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
367  {
369  "RotationShimController detected a potential collision ahead!");
370  }
371 
372  if (footprint_cost >= static_cast<double>(LETHAL_OBSTACLE)) {
373  throw nav2_core::NoValidControl("RotationShimController detected collision ahead!");
374  }
375  }
376 }
377 
378 bool RotationShimController::isGoalChanged(const nav_msgs::msg::Path & path)
379 {
380  // Return true if rotating or if the current path is empty
381  if (in_rotation_ || current_path_.poses.empty()) {
382  return true;
383  }
384 
385  // Check if the last pose of the current and new paths differ
386  return current_path_.poses.back().pose != path.poses.back().pose;
387 }
388 
389 void RotationShimController::setPlan(const nav_msgs::msg::Path & path)
390 {
391  path_updated_ = rotate_to_heading_once_ ? isGoalChanged(path) : true;
392  current_path_ = path;
393  primary_controller_->setPlan(path);
394  position_goal_checker_->reset();
395 }
396 
397 void RotationShimController::setSpeedLimit(const double & speed_limit, const bool & percentage)
398 {
399  primary_controller_->setSpeedLimit(speed_limit, percentage);
400 }
401 
403 {
404  last_angular_vel_ = std::numeric_limits<double>::max();
405  primary_controller_->reset();
406  position_goal_checker_->reset();
407 }
408 
409 rcl_interfaces::msg::SetParametersResult
410 RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
411 {
412  rcl_interfaces::msg::SetParametersResult result;
413  std::lock_guard<std::mutex> lock_reinit(mutex_);
414 
415  for (auto parameter : parameters) {
416  const auto & type = parameter.get_type();
417  const auto & name = parameter.get_name();
418 
419  if (type == ParameterType::PARAMETER_DOUBLE) {
420  if (name == plugin_name_ + ".angular_dist_threshold") {
421  angular_dist_threshold_ = parameter.as_double();
422  } else if (name == plugin_name_ + ".forward_sampling_distance") {
423  forward_sampling_distance_ = parameter.as_double();
424  } else if (name == plugin_name_ + ".rotate_to_heading_angular_vel") {
425  rotate_to_heading_angular_vel_ = parameter.as_double();
426  } else if (name == plugin_name_ + ".max_angular_accel") {
427  max_angular_accel_ = parameter.as_double();
428  } else if (name == plugin_name_ + ".simulate_ahead_time") {
429  simulate_ahead_time_ = parameter.as_double();
430  }
431  } else if (type == ParameterType::PARAMETER_BOOL) {
432  if (name == plugin_name_ + ".rotate_to_goal_heading") {
433  rotate_to_goal_heading_ = parameter.as_bool();
434  } else if (name == plugin_name_ + ".rotate_to_heading_once") {
435  rotate_to_heading_once_ = parameter.as_bool();
436  } else if (name == plugin_name_ + ".closed_loop") {
437  closed_loop_ = parameter.as_bool();
438  } else if (name == plugin_name_ + ".use_path_orientations") {
439  use_path_orientations_ = parameter.as_bool();
440  }
441  }
442  }
443 
444  result.successful = true;
445  return result;
446 }
447 
448 } // namespace nav2_rotation_shim_controller
449 
450 // Register this controller as a nav2_core plugin
451 PLUGINLIB_EXPORT_CLASS(
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
Function-object for checking whether a goal has been reached.
virtual bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance)=0
Get the maximum possible tolerances used for goal checking in the major types. Any field without a va...
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
Rotate to rough path heading controller shim plugin.
void deactivate() override
Deactivate controller state machine.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configure controller state machine.
geometry_msgs::msg::PoseStamped getSampledPathPt()
Finds the point on the path that is roughly the sampling point distance away from the robot for use....
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
Compute the best command given the current pose and velocity.
geometry_msgs::msg::Pose transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped &pt)
Uses TF to find the location of the sampled path point in base frame.
void cleanup() override
Cleanup controller state machine.
geometry_msgs::msg::PoseStamped getSampledPathGoal()
Find the goal point in path May throw exception if the path is empty.
bool isGoalChanged(const nav_msgs::msg::Path &path)
Checks if the goal has changed based on the given path.
geometry_msgs::msg::TwistStamped computeRotateToHeadingCommand(const double &angular_distance, const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity)
Rotates the robot to the rough heading.
void activate() override
Activate controller state machine.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
RotationShimController()
Constructor for nav2_rotation_shim_controller::RotationShimController.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void isCollisionFree(const geometry_msgs::msg::TwistStamped &cmd_vel, const double &angular_distance_to_heading, const geometry_msgs::msg::PoseStamped &pose)
Checks if rotation is safe.
void reset() override
Reset the state of the controller.