Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
graceful_controller.cpp
1 // Copyright (c) 2023 Alberto J. Tudela Roldán
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 <memory>
16 #include <mutex>
17 
18 #include "angles/angles.h"
19 #include "nav2_core/controller_exceptions.hpp"
20 #include "nav2_util/geometry_utils.hpp"
21 #include "nav2_graceful_controller/graceful_controller.hpp"
22 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
23 
24 namespace nav2_graceful_controller
25 {
26 
28  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
29  std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
30  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
31 {
32  auto node = parent.lock();
33  if (!node) {
34  throw nav2_core::ControllerException("Unable to lock node!");
35  }
36 
37  costmap_ros_ = costmap_ros;
38  tf_buffer_ = tf;
39  plugin_name_ = name;
40  logger_ = node->get_logger();
41 
42  // Handles storage and dynamic configuration of parameters.
43  // Returns pointer to data current param settings.
44  param_handler_ = std::make_unique<ParameterHandler>(
45  node, plugin_name_, logger_,
46  costmap_ros_->getCostmap()->getSizeInMetersX());
47  params_ = param_handler_->getParams();
48 
49  // Handles global path transformations
50  path_handler_ = std::make_unique<PathHandler>(
51  tf2::durationFromSec(params_->transform_tolerance), tf_buffer_, costmap_ros_);
52 
53  // Handles the control law to generate the velocity commands
54  control_law_ = std::make_unique<SmoothControlLaw>(
55  params_->k_phi, params_->k_delta, params_->beta, params_->lambda, params_->slowdown_radius,
56  params_->v_linear_min, params_->v_linear_max, params_->v_angular_max);
57 
58  // Initialize footprint collision checker
59  collision_checker_ = std::make_unique<nav2_costmap_2d::
60  FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros_->getCostmap());
61 
62  // Publishers
63  transformed_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>("transformed_global_plan", 1);
64  local_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>("local_plan", 1);
65  motion_target_pub_ = node->create_publisher<geometry_msgs::msg::PoseStamped>("motion_target", 1);
66  slowdown_pub_ = node->create_publisher<visualization_msgs::msg::Marker>("slowdown", 1);
67 
68  RCLCPP_INFO(logger_, "Configured Graceful Motion Controller: %s", plugin_name_.c_str());
69 }
70 
72 {
73  RCLCPP_INFO(
74  logger_,
75  "Cleaning up controller: %s of type graceful_controller::GracefulController",
76  plugin_name_.c_str());
77  transformed_plan_pub_.reset();
78  local_plan_pub_.reset();
79  motion_target_pub_.reset();
80  slowdown_pub_.reset();
81  collision_checker_.reset();
82  path_handler_.reset();
83  param_handler_.reset();
84  control_law_.reset();
85 }
86 
88 {
89  RCLCPP_INFO(
90  logger_,
91  "Activating controller: %s of type nav2_graceful_controller::GracefulController",
92  plugin_name_.c_str());
93  transformed_plan_pub_->on_activate();
94  local_plan_pub_->on_activate();
95  motion_target_pub_->on_activate();
96  slowdown_pub_->on_activate();
97 }
98 
100 {
101  RCLCPP_INFO(
102  logger_,
103  "Deactivating controller: %s of type nav2_graceful_controller::GracefulController",
104  plugin_name_.c_str());
105  transformed_plan_pub_->on_deactivate();
106  local_plan_pub_->on_deactivate();
107  motion_target_pub_->on_deactivate();
108  slowdown_pub_->on_deactivate();
109 }
110 
111 geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands(
112  const geometry_msgs::msg::PoseStamped & pose,
113  const geometry_msgs::msg::Twist & /*velocity*/,
114  nav2_core::GoalChecker * goal_checker)
115 {
116  std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
117 
118  geometry_msgs::msg::TwistStamped cmd_vel;
119  cmd_vel.header = pose.header;
120 
121  // Update for the current goal checker's state
122  geometry_msgs::msg::Pose pose_tolerance;
123  geometry_msgs::msg::Twist velocity_tolerance;
124  if (!goal_checker->getTolerances(pose_tolerance, velocity_tolerance)) {
125  RCLCPP_WARN(logger_, "Unable to retrieve goal checker's tolerances!");
126  } else {
127  goal_dist_tolerance_ = pose_tolerance.position.x;
128  }
129 
130  // Update the smooth control law with the new params
131  control_law_->setCurvatureConstants(
132  params_->k_phi, params_->k_delta, params_->beta, params_->lambda);
133  control_law_->setSlowdownRadius(params_->slowdown_radius);
134  control_law_->setSpeedLimit(params_->v_linear_min, params_->v_linear_max, params_->v_angular_max);
135 
136  // Transform path to robot base frame
137  auto transformed_plan = path_handler_->transformGlobalPlan(
138  pose, params_->max_robot_pose_search_dist);
139 
140  // Add proper orientations to plan, if needed
141  validateOrientations(transformed_plan.poses);
142 
143  // Publish plan for visualization
144  transformed_plan_pub_->publish(transformed_plan);
145 
146  // Transform local frame to global frame to use in collision checking
147  geometry_msgs::msg::TransformStamped costmap_transform;
148  try {
149  costmap_transform = tf_buffer_->lookupTransform(
150  costmap_ros_->getGlobalFrameID(), costmap_ros_->getBaseFrameID(),
151  tf2::TimePointZero);
152  } catch (tf2::TransformException & ex) {
153  RCLCPP_ERROR(
154  logger_, "Could not transform %s to %s: %s",
155  costmap_ros_->getBaseFrameID().c_str(), costmap_ros_->getGlobalFrameID().c_str(),
156  ex.what());
157  throw ex;
158  }
159 
160  // Compute distance to goal as the path's integrated distance to account for path curvatures
161  double dist_to_goal = nav2_util::geometry_utils::calculate_path_length(transformed_plan);
162 
163  // If we've reached the XY goal tolerance, just rotate
164  if (dist_to_goal < goal_dist_tolerance_ || goal_reached_) {
165  goal_reached_ = true;
166  double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
167  // Check for collisions between our current pose and goal pose
168  size_t num_steps = fabs(angle_to_goal) / params_->in_place_collision_resolution;
169  // Need to check at least the end pose
170  num_steps = std::max(static_cast<size_t>(1), num_steps);
171  bool collision_free = true;
172  for (size_t i = 1; i <= num_steps; ++i) {
173  double step = static_cast<double>(i) / static_cast<double>(num_steps);
174  double yaw = step * angle_to_goal;
175  geometry_msgs::msg::PoseStamped next_pose;
176  next_pose.header.frame_id = costmap_ros_->getBaseFrameID();
177  next_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
178  geometry_msgs::msg::PoseStamped costmap_pose;
179  tf2::doTransform(next_pose, costmap_pose, costmap_transform);
180  if (inCollision(
181  costmap_pose.pose.position.x, costmap_pose.pose.position.y,
182  tf2::getYaw(costmap_pose.pose.orientation)))
183  {
184  collision_free = false;
185  break;
186  }
187  }
188  // Compute velocity if rotation is possible
189  if (collision_free) {
190  cmd_vel.twist = rotateToTarget(angle_to_goal);
191  return cmd_vel;
192  }
193  // Else, fall through and see if we should follow control law longer
194  }
195 
196  // Precompute distance to candidate poses
197  std::vector<double> target_distances;
198  computeDistanceAlongPath(transformed_plan.poses, target_distances);
199 
200  // Work back from the end of plan to find valid target pose
201  for (int i = transformed_plan.poses.size() - 1; i >= 0; --i) {
202  // Underlying control law needs a single target pose, which should:
203  // * Be as far away as possible from the robot (for smoothness)
204  // * But no further than the max_lookahed_ distance
205  // * Be feasible to reach in a collision free manner
206  geometry_msgs::msg::PoseStamped target_pose = transformed_plan.poses[i];
207  double dist_to_target = target_distances[i];
208 
209  // Continue if target_pose is too far away from robot
210  if (dist_to_target > params_->max_lookahead) {continue;}
211 
212  if (dist_to_goal < params_->max_lookahead) {
213  if (params_->prefer_final_rotation) {
214  // Avoid unstability and big sweeping turns at the end of paths by
215  // ignoring final heading
216  double yaw = std::atan2(target_pose.pose.position.y, target_pose.pose.position.x);
217  target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
218  }
219  } else if (dist_to_target < params_->min_lookahead) {
220  // Make sure target is far enough away to avoid instability
221  break;
222  }
223 
224  // Flip the orientation of the motion target if the robot is moving backwards
225  bool reversing = false;
226  if (params_->allow_backward && target_pose.pose.position.x < 0.0) {
227  reversing = true;
228  target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
229  tf2::getYaw(target_pose.pose.orientation) + M_PI);
230  }
231 
232  // Actually simulate our path
233  nav_msgs::msg::Path local_plan;
234  if (simulateTrajectory(target_pose, costmap_transform, local_plan, cmd_vel, reversing)) {
235  // Successfully simulated to target_pose - compute velocity at this moment
236  // Publish the selected target_pose
237  motion_target_pub_->publish(target_pose);
238  // Publish marker for slowdown radius around motion target for debugging / visualization
239  auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker(
240  target_pose, params_->slowdown_radius);
241  slowdown_pub_->publish(slowdown_marker);
242  // Publish the local plan
243  local_plan.header = transformed_plan.header;
244  local_plan_pub_->publish(local_plan);
245  // Successfully found velocity command
246  return cmd_vel;
247  }
248  }
249 
250  throw nav2_core::NoValidControl("Collision detected in trajectory");
251 }
252 
253 void GracefulController::setPlan(const nav_msgs::msg::Path & path)
254 {
255  path_handler_->setPlan(path);
256  goal_reached_ = false;
257  do_initial_rotation_ = true;
258 }
259 
261  const double & speed_limit, const bool & percentage)
262 {
263  std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
264 
265  if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
266  params_->v_linear_max = params_->v_linear_max_initial;
267  params_->v_angular_max = params_->v_angular_max_initial;
268  } else {
269  if (percentage) {
270  // Speed limit is expressed in % from maximum speed of robot
271  params_->v_linear_max = std::max(
272  params_->v_linear_max_initial * speed_limit / 100.0, params_->v_linear_min);
273  params_->v_angular_max = params_->v_angular_max_initial * speed_limit / 100.0;
274  } else {
275  // Speed limit is expressed in m/s
276  params_->v_linear_max = std::max(speed_limit, params_->v_linear_min);
277  // Limit the angular velocity to be proportional to the linear velocity
278  params_->v_angular_max = params_->v_angular_max_initial *
279  speed_limit / params_->v_linear_max_initial;
280  }
281  }
282 }
283 
285  const geometry_msgs::msg::PoseStamped & motion_target,
286  const geometry_msgs::msg::TransformStamped & costmap_transform,
287  nav_msgs::msg::Path & trajectory,
288  geometry_msgs::msg::TwistStamped & cmd_vel,
289  bool backward)
290 {
291  trajectory.poses.clear();
292 
293  // First pose is robot current pose
294  geometry_msgs::msg::PoseStamped next_pose;
295  next_pose.header.frame_id = costmap_ros_->getBaseFrameID();
296  next_pose.pose.orientation.w = 1.0;
297 
298  // Should we simulate rotation initially?
299  bool sim_initial_rotation = do_initial_rotation_ && params_->initial_rotation;
300  double angle_to_target =
301  std::atan2(motion_target.pose.position.y, motion_target.pose.position.x);
302  if (fabs(angle_to_target) < params_->initial_rotation_tolerance) {
303  sim_initial_rotation = false;
304  do_initial_rotation_ = false;
305  }
306 
307  double distance = std::numeric_limits<double>::max();
308  double resolution_ = costmap_ros_->getCostmap()->getResolution();
309  double dt = (params_->v_linear_max > 0.0) ? resolution_ / params_->v_linear_max : 0.0;
310 
311  // Set max iter to avoid infinite loop
312  unsigned int max_iter = 3 *
313  std::hypot(motion_target.pose.position.x, motion_target.pose.position.y) / resolution_;
314 
315  // Generate path
316  do{
317  if (sim_initial_rotation) {
318  // Compute rotation velocity
319  double next_pose_yaw = tf2::getYaw(next_pose.pose.orientation);
320  auto cmd = rotateToTarget(angle_to_target - next_pose_yaw);
321 
322  // If this is first iteration, this is our current target velocity
323  if (trajectory.poses.empty()) {cmd_vel.twist = cmd;}
324 
325  // Are we done simulating initial rotation?
326  if (fabs(angle_to_target - next_pose_yaw) < params_->initial_rotation_tolerance) {
327  sim_initial_rotation = false;
328  }
329 
330  // Forward simulate rotation command
331  next_pose_yaw += cmd_vel.twist.angular.z * dt;
332  next_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(next_pose_yaw);
333  } else {
334  // If this is first iteration, this is our current target velocity
335  if (trajectory.poses.empty()) {
336  cmd_vel.twist = control_law_->calculateRegularVelocity(
337  motion_target.pose, next_pose.pose, backward);
338  }
339 
340  // Apply velocities to calculate next pose
341  next_pose.pose = control_law_->calculateNextPose(
342  dt, motion_target.pose, next_pose.pose, backward);
343  }
344 
345  // Add the pose to the trajectory for visualization
346  trajectory.poses.push_back(next_pose);
347 
348  // Check for collision
349  geometry_msgs::msg::PoseStamped global_pose;
350  tf2::doTransform(next_pose, global_pose, costmap_transform);
351  if (inCollision(
352  global_pose.pose.position.x, global_pose.pose.position.y,
353  tf2::getYaw(global_pose.pose.orientation)))
354  {
355  return false;
356  }
357 
358  // Check if we reach the goal
359  distance = nav2_util::geometry_utils::euclidean_distance(motion_target.pose, next_pose.pose);
360  }while(distance > resolution_ && trajectory.poses.size() < max_iter);
361 
362  return true;
363 }
364 
365 geometry_msgs::msg::Twist GracefulController::rotateToTarget(double angle_to_target)
366 {
367  geometry_msgs::msg::Twist vel;
368  vel.linear.x = 0.0;
369  vel.angular.z = params_->rotation_scaling_factor * angle_to_target * params_->v_angular_max;
370  vel.angular.z = std::copysign(1.0, vel.angular.z) * std::max(abs(vel.angular.z),
371  params_->v_angular_min_in_place);
372  return vel;
373 }
374 
375 bool GracefulController::inCollision(const double & x, const double & y, const double & theta)
376 {
377  unsigned int mx, my;
378  if (!costmap_ros_->getCostmap()->worldToMap(x, y, mx, my)) {
379  RCLCPP_WARN(
380  logger_, "The path is not in the costmap. Cannot check for collisions. "
381  "Proceed at your own risk, slow the robot, or increase your costmap size.");
382  return false;
383  }
384 
385  // Calculate the cost of the footprint at the robot's current position depending
386  // on the shape of the footprint
387  bool is_tracking_unknown =
388  costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
389  bool consider_footprint = !costmap_ros_->getUseRadius();
390 
391  double footprint_cost;
392  if (consider_footprint) {
393  footprint_cost = collision_checker_->footprintCostAtPose(
394  x, y, theta, costmap_ros_->getRobotFootprint());
395  } else {
396  footprint_cost = collision_checker_->pointCost(mx, my);
397  }
398 
399  switch (static_cast<unsigned char>(footprint_cost)) {
400  case (nav2_costmap_2d::LETHAL_OBSTACLE):
401  return true;
402  case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
403  return consider_footprint ? false : true;
404  case (nav2_costmap_2d::NO_INFORMATION):
405  return is_tracking_unknown ? false : true;
406  }
407 
408  return false;
409 }
410 
412  const std::vector<geometry_msgs::msg::PoseStamped> & poses,
413  std::vector<double> & distances)
414 {
415  distances.resize(poses.size());
416  // Do the first pose from robot
417  double d = std::hypot(poses[0].pose.position.x, poses[0].pose.position.y);
418  distances[0] = d;
419  // Compute remaining poses
420  for (size_t i = 1; i < poses.size(); ++i) {
421  d += nav2_util::geometry_utils::euclidean_distance(poses[i - 1].pose, poses[i].pose);
422  distances[i] = d;
423  }
424 }
425 
427  std::vector<geometry_msgs::msg::PoseStamped> & path)
428 {
429  // We never change the orientation of the first & last pose
430  // So we need at least three poses to do anything here
431  if (path.size() < 3) {return;}
432 
433  // Check if we actually need to add orientations
434  double initial_yaw = tf2::getYaw(path[1].pose.orientation);
435  for (size_t i = 2; i < path.size() - 1; ++i) {
436  double this_yaw = tf2::getYaw(path[i].pose.orientation);
437  if (angles::shortest_angular_distance(this_yaw, initial_yaw) > 1e-6) {return;}
438  }
439 
440  // For each pose, point at the next one
441  // NOTE: control loop will handle reversing logic
442  for (size_t i = 0; i < path.size() - 1; ++i) {
443  // Get relative yaw angle
444  double dx = path[i + 1].pose.position.x - path[i].pose.position.x;
445  double dy = path[i + 1].pose.position.y - path[i].pose.position.y;
446  double yaw = std::atan2(dy, dx);
447  path[i].pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
448  }
449 }
450 
451 } // namespace nav2_graceful_controller
452 
453 // Register this controller as a nav2_core plugin
454 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...
void activate() override
Activate controller state machine.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan.
void computeDistanceAlongPath(const std::vector< geometry_msgs::msg::PoseStamped > &poses, std::vector< double > &distances)
Compute the distance to each pose in a path.
void deactivate() override
Deactivate controller state machine.
bool simulateTrajectory(const geometry_msgs::msg::PoseStamped &motion_target, const geometry_msgs::msg::TransformStamped &costmap_transform, nav_msgs::msg::Path &trajectory, geometry_msgs::msg::TwistStamped &cmd_vel, bool backward)
Simulate trajectory calculating in every step the new velocity command based on a new curvature value...
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.
void cleanup() override
Cleanup controller state machine.
geometry_msgs::msg::Twist rotateToTarget(double angle_to_target)
Rotate the robot to face the motion target with maximum angular velocity.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override
Compute the best command given the current pose and velocity.
bool inCollision(const double &x, const double &y, const double &theta)
Checks if the robot is in collision.
void validateOrientations(std::vector< geometry_msgs::msg::PoseStamped > &path)
Control law requires proper orientations, not all planners provide them.