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"
24 namespace nav2_graceful_controller
28 const nav2::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)
32 nav2::LifecycleNode::SharedPtr node = parent.lock();
37 costmap_ros_ = costmap_ros;
40 logger_ = node->get_logger();
44 param_handler_ = std::make_unique<ParameterHandler>(
45 node, plugin_name_, logger_,
46 costmap_ros_->getCostmap()->getSizeInMetersX());
47 params_ = param_handler_->getParams();
50 path_handler_ = std::make_unique<PathHandler>(
51 params_->transform_tolerance, tf_buffer_, costmap_ros_);
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);
59 if(params_->use_collision_detection) {
60 collision_checker_ = std::make_unique<nav2_costmap_2d::
61 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros_->getCostmap());
65 transformed_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"transformed_global_plan");
66 local_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"local_plan");
67 motion_target_pub_ = node->create_publisher<geometry_msgs::msg::PoseStamped>(
"motion_target");
68 slowdown_pub_ = node->create_publisher<visualization_msgs::msg::Marker>(
"slowdown");
70 RCLCPP_INFO(logger_,
"Configured Graceful Motion Controller: %s", plugin_name_.c_str());
77 "Cleaning up controller: %s of type graceful_controller::GracefulController",
78 plugin_name_.c_str());
79 transformed_plan_pub_.reset();
80 local_plan_pub_.reset();
81 motion_target_pub_.reset();
82 slowdown_pub_.reset();
83 collision_checker_.reset();
84 path_handler_.reset();
85 param_handler_.reset();
93 "Activating controller: %s of type nav2_graceful_controller::GracefulController",
94 plugin_name_.c_str());
95 transformed_plan_pub_->on_activate();
96 local_plan_pub_->on_activate();
97 motion_target_pub_->on_activate();
98 slowdown_pub_->on_activate();
105 "Deactivating controller: %s of type nav2_graceful_controller::GracefulController",
106 plugin_name_.c_str());
107 transformed_plan_pub_->on_deactivate();
108 local_plan_pub_->on_deactivate();
109 motion_target_pub_->on_deactivate();
110 slowdown_pub_->on_deactivate();
114 const geometry_msgs::msg::PoseStamped & pose,
115 const geometry_msgs::msg::Twist & ,
118 std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
120 geometry_msgs::msg::TwistStamped cmd_vel;
121 cmd_vel.header = pose.header;
124 geometry_msgs::msg::Pose pose_tolerance;
125 geometry_msgs::msg::Twist velocity_tolerance;
126 if (!goal_checker->
getTolerances(pose_tolerance, velocity_tolerance)) {
127 RCLCPP_WARN(logger_,
"Unable to retrieve goal checker's tolerances!");
129 goal_dist_tolerance_ = pose_tolerance.position.x;
133 control_law_->setCurvatureConstants(
134 params_->k_phi, params_->k_delta, params_->beta, params_->lambda);
135 control_law_->setSlowdownRadius(params_->slowdown_radius);
136 control_law_->setSpeedLimit(params_->v_linear_min, params_->v_linear_max, params_->v_angular_max);
139 auto transformed_plan = path_handler_->transformGlobalPlan(
140 pose, params_->max_robot_pose_search_dist);
146 transformed_plan_pub_->publish(transformed_plan);
149 geometry_msgs::msg::TransformStamped costmap_transform;
151 costmap_transform = tf_buffer_->lookupTransform(
152 costmap_ros_->getGlobalFrameID(), costmap_ros_->getBaseFrameID(),
154 }
catch (tf2::TransformException & ex) {
156 logger_,
"Could not transform %s to %s: %s",
157 costmap_ros_->getBaseFrameID().c_str(), costmap_ros_->getGlobalFrameID().c_str(),
163 double dist_to_goal = nav2_util::geometry_utils::calculate_path_length(transformed_plan);
166 if (dist_to_goal < goal_dist_tolerance_ || goal_reached_) {
167 goal_reached_ =
true;
168 double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
170 size_t num_steps = fabs(angle_to_goal) / params_->in_place_collision_resolution;
172 num_steps = std::max(
static_cast<size_t>(1), num_steps);
173 bool collision_free =
true;
174 for (
size_t i = 1; i <= num_steps; ++i) {
175 double step =
static_cast<double>(i) /
static_cast<double>(num_steps);
176 double yaw = step * angle_to_goal;
177 geometry_msgs::msg::PoseStamped next_pose;
178 next_pose.header.frame_id = costmap_ros_->getBaseFrameID();
179 next_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
180 geometry_msgs::msg::PoseStamped costmap_pose;
181 tf2::doTransform(next_pose, costmap_pose, costmap_transform);
182 if (params_->use_collision_detection &&
inCollision(
183 costmap_pose.pose.position.x, costmap_pose.pose.position.y,
184 tf2::getYaw(costmap_pose.pose.orientation)))
186 collision_free =
false;
191 if (collision_free) {
199 std::vector<double> target_distances;
203 for (
int i = transformed_plan.poses.size() - 1; i >= 0; --i) {
208 geometry_msgs::msg::PoseStamped target_pose = transformed_plan.poses[i];
209 double dist_to_target = target_distances[i];
212 if (dist_to_target > params_->max_lookahead) {
continue;}
214 if (dist_to_goal < params_->max_lookahead) {
215 if (params_->prefer_final_rotation) {
218 double yaw = std::atan2(target_pose.pose.position.y, target_pose.pose.position.x);
219 target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
221 }
else if (dist_to_target < params_->min_lookahead) {
227 bool reversing =
false;
228 if (params_->allow_backward && target_pose.pose.position.x < 0.0) {
230 target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
231 tf2::getYaw(target_pose.pose.orientation) + M_PI);
235 nav_msgs::msg::Path local_plan;
236 if (
simulateTrajectory(target_pose, costmap_transform, local_plan, cmd_vel, reversing)) {
239 motion_target_pub_->publish(target_pose);
241 auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker(
242 target_pose, params_->slowdown_radius);
243 slowdown_pub_->publish(slowdown_marker);
245 local_plan.header = transformed_plan.header;
246 local_plan_pub_->publish(local_plan);
257 path_handler_->setPlan(path);
258 goal_reached_ =
false;
259 do_initial_rotation_ =
true;
263 const double & speed_limit,
const bool & percentage)
265 std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
267 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
268 params_->v_linear_max = params_->v_linear_max_initial;
269 params_->v_angular_max = params_->v_angular_max_initial;
273 params_->v_linear_max = std::max(
274 params_->v_linear_max_initial * speed_limit / 100.0, params_->v_linear_min);
275 params_->v_angular_max = params_->v_angular_max_initial * speed_limit / 100.0;
278 params_->v_linear_max = std::max(speed_limit, params_->v_linear_min);
280 params_->v_angular_max = params_->v_angular_max_initial *
281 speed_limit / params_->v_linear_max_initial;
287 const geometry_msgs::msg::PoseStamped & motion_target,
288 const geometry_msgs::msg::TransformStamped & costmap_transform,
289 nav_msgs::msg::Path & trajectory,
290 geometry_msgs::msg::TwistStamped & cmd_vel,
293 trajectory.poses.clear();
296 geometry_msgs::msg::PoseStamped next_pose;
297 next_pose.header.frame_id = costmap_ros_->getBaseFrameID();
298 next_pose.pose.orientation.w = 1.0;
301 bool sim_initial_rotation = do_initial_rotation_ && params_->initial_rotation;
302 double angle_to_target =
303 std::atan2(motion_target.pose.position.y, motion_target.pose.position.x);
304 if (fabs(angle_to_target) < params_->initial_rotation_tolerance) {
305 sim_initial_rotation =
false;
306 do_initial_rotation_ =
false;
309 double distance = std::numeric_limits<double>::max();
310 double resolution_ = costmap_ros_->getCostmap()->getResolution();
311 double dt = (params_->v_linear_max > 0.0) ? resolution_ / params_->v_linear_max : 0.0;
314 unsigned int max_iter = 3 *
315 std::hypot(motion_target.pose.position.x, motion_target.pose.position.y) / resolution_;
319 if (sim_initial_rotation) {
321 double next_pose_yaw = tf2::getYaw(next_pose.pose.orientation);
325 if (trajectory.poses.empty()) {cmd_vel.twist = cmd;}
328 if (fabs(angle_to_target - next_pose_yaw) < params_->initial_rotation_tolerance) {
329 sim_initial_rotation =
false;
333 next_pose_yaw += cmd_vel.twist.angular.z * dt;
334 next_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(next_pose_yaw);
337 if (trajectory.poses.empty()) {
338 cmd_vel.twist = control_law_->calculateRegularVelocity(
339 motion_target.pose, next_pose.pose, backward);
343 next_pose.pose = control_law_->calculateNextPose(
344 dt, motion_target.pose, next_pose.pose, backward);
348 trajectory.poses.push_back(next_pose);
351 geometry_msgs::msg::PoseStamped global_pose;
352 tf2::doTransform(next_pose, global_pose, costmap_transform);
353 if (params_->use_collision_detection &&
inCollision(
354 global_pose.pose.position.x, global_pose.pose.position.y,
355 tf2::getYaw(global_pose.pose.orientation)))
361 distance = nav2_util::geometry_utils::euclidean_distance(motion_target.pose, next_pose.pose);
362 }
while(distance > resolution_ && trajectory.poses.size() < max_iter);
369 geometry_msgs::msg::Twist vel;
371 vel.angular.z = params_->rotation_scaling_factor * angle_to_target * params_->v_angular_max;
372 vel.angular.z = std::copysign(1.0, vel.angular.z) * std::max(abs(vel.angular.z),
373 params_->v_angular_min_in_place);
380 if (!costmap_ros_->getCostmap()->worldToMap(x, y, mx, my)) {
382 logger_,
"The path is not in the costmap. Cannot check for collisions. "
383 "Proceed at your own risk, slow the robot, or increase your costmap size.");
389 bool is_tracking_unknown =
390 costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
391 bool consider_footprint = !costmap_ros_->getUseRadius();
393 double footprint_cost;
394 if (consider_footprint) {
395 footprint_cost = collision_checker_->footprintCostAtPose(
396 x, y, theta, costmap_ros_->getRobotFootprint());
398 footprint_cost = collision_checker_->pointCost(mx, my);
401 switch (
static_cast<unsigned char>(footprint_cost)) {
402 case (nav2_costmap_2d::LETHAL_OBSTACLE):
404 case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
405 return consider_footprint ? false :
true;
406 case (nav2_costmap_2d::NO_INFORMATION):
407 return is_tracking_unknown ? false :
true;
414 const std::vector<geometry_msgs::msg::PoseStamped> & poses,
415 std::vector<double> & distances)
417 distances.resize(poses.size());
419 double d = std::hypot(poses[0].pose.position.x, poses[0].pose.position.y);
422 for (
size_t i = 1; i < poses.size(); ++i) {
423 d += nav2_util::geometry_utils::euclidean_distance(poses[i - 1].pose, poses[i].pose);
429 std::vector<geometry_msgs::msg::PoseStamped> & path)
433 if (path.size() < 3) {
return;}
436 double initial_yaw = tf2::getYaw(path[1].pose.orientation);
437 for (
size_t i = 2; i < path.size() - 1; ++i) {
438 double this_yaw = tf2::getYaw(path[i].pose.orientation);
439 if (angles::shortest_angular_distance(this_yaw, initial_yaw) > 1e-6) {
return;}
444 for (
size_t i = 0; i < path.size() - 1; ++i) {
446 double dx = path[i + 1].pose.position.x - path[i].pose.position.x;
447 double dy = path[i + 1].pose.position.y - path[i].pose.position.y;
448 double yaw = std::atan2(dy, dx);
449 path[i].pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
456 PLUGINLIB_EXPORT_CLASS(
controller interface that acts as a virtual base class for all controller plugins
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...
Graceful controller plugin.
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 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.
void configure(const nav2::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::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.