15 #include "nav2_util/geometry_utils.hpp"
16 #include "nav2_graceful_controller/graceful_controller.hpp"
17 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
18 #include "nav2_core/exceptions.hpp"
20 namespace nav2_graceful_controller
24 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
25 std::string name,
const std::shared_ptr<tf2_ros::Buffer> tf,
26 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
28 auto node = parent.lock();
30 throw std::runtime_error(
"Unable to lock node!");
33 costmap_ros_ = costmap_ros;
36 logger_ = node->get_logger();
40 param_handler_ = std::make_unique<ParameterHandler>(
41 node, plugin_name_, logger_,
42 costmap_ros_->getCostmap()->getSizeInMetersX());
43 params_ = param_handler_->getParams();
46 path_handler_ = std::make_unique<PathHandler>(
47 tf2::durationFromSec(params_->transform_tolerance), tf_buffer_, costmap_ros_);
50 control_law_ = std::make_unique<SmoothControlLaw>(
51 params_->k_phi, params_->k_delta, params_->beta, params_->lambda, params_->slowdown_radius,
52 params_->v_linear_min, params_->v_linear_max, params_->v_angular_max);
55 collision_checker_ = std::make_unique<nav2_costmap_2d::
56 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros_->getCostmap());
59 transformed_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"transformed_global_plan", 1);
60 local_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"local_plan", 1);
61 motion_target_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>(
"motion_target", 1);
62 slowdown_pub_ = node->create_publisher<visualization_msgs::msg::Marker>(
"slowdown", 1);
64 RCLCPP_INFO(logger_,
"Configured Graceful Motion Controller: %s", plugin_name_.c_str());
71 "Cleaning up controller: %s of type graceful_controller::GracefulController",
72 plugin_name_.c_str());
73 transformed_plan_pub_.reset();
74 local_plan_pub_.reset();
75 motion_target_pub_.reset();
76 slowdown_pub_.reset();
77 collision_checker_.reset();
78 path_handler_.reset();
79 param_handler_.reset();
87 "Activating controller: %s of type nav2_graceful_controller::GracefulController",
88 plugin_name_.c_str());
89 transformed_plan_pub_->on_activate();
90 local_plan_pub_->on_activate();
91 motion_target_pub_->on_activate();
92 slowdown_pub_->on_activate();
99 "Deactivating controller: %s of type nav2_graceful_controller::GracefulController",
100 plugin_name_.c_str());
101 transformed_plan_pub_->on_deactivate();
102 local_plan_pub_->on_deactivate();
103 motion_target_pub_->on_deactivate();
104 slowdown_pub_->on_deactivate();
108 const geometry_msgs::msg::PoseStamped & pose,
109 const geometry_msgs::msg::Twist & ,
112 std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
115 geometry_msgs::msg::Pose pose_tolerance;
116 geometry_msgs::msg::Twist velocity_tolerance;
117 if (!goal_checker->
getTolerances(pose_tolerance, velocity_tolerance)) {
118 RCLCPP_WARN(logger_,
"Unable to retrieve goal checker's tolerances!");
120 goal_dist_tolerance_ = pose_tolerance.position.x;
124 control_law_->setCurvatureConstants(
125 params_->k_phi, params_->k_delta, params_->beta, params_->lambda);
126 control_law_->setSlowdownRadius(params_->slowdown_radius);
127 control_law_->setSpeedLimit(params_->v_linear_min, params_->v_linear_max, params_->v_angular_max);
130 auto transformed_plan = path_handler_->transformGlobalPlan(
131 pose, params_->max_robot_pose_search_dist);
132 transformed_plan_pub_->publish(transformed_plan);
135 auto motion_target =
getMotionTarget(params_->motion_target_dist, transformed_plan);
136 auto motion_target_point = nav2_graceful_controller::createMotionTargetMsg(motion_target);
137 motion_target_pub_->publish(motion_target_point);
140 auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker(
142 params_->slowdown_radius);
143 slowdown_pub_->publish(slowdown_marker);
146 double dist_to_goal = nav2_util::geometry_utils::calculate_path_length(transformed_plan);
151 double angle_to_target = atan2(motion_target.pose.position.y, motion_target.pose.position.x);
152 if (params_->final_rotation && dist_to_goal < params_->motion_target_dist) {
153 geometry_msgs::msg::PoseStamped stl_pose =
154 transformed_plan.poses[transformed_plan.poses.size() - 2];
155 geometry_msgs::msg::PoseStamped goal_pose = transformed_plan.poses.back();
156 double dx = goal_pose.pose.position.x - stl_pose.pose.position.x;
157 double dy = goal_pose.pose.position.y - stl_pose.pose.position.y;
158 double yaw = std::atan2(dy, dx);
159 motion_target.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
163 bool reversing =
false;
164 if (params_->allow_backward && motion_target.pose.position.x < 0.0) {
166 motion_target.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
167 tf2::getYaw(motion_target.pose.orientation) + M_PI);
174 geometry_msgs::msg::TwistStamped cmd_vel;
175 cmd_vel.header = pose.header;
176 if (params_->final_rotation && (dist_to_goal < goal_dist_tolerance_ || goal_reached_)) {
177 goal_reached_ =
true;
178 double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
180 }
else if (params_->initial_rotation &&
181 fabs(angle_to_target) > params_->initial_rotation_min_angle)
185 cmd_vel.twist = control_law_->calculateRegularVelocity(motion_target.pose, reversing);
189 geometry_msgs::msg::TransformStamped costmap_transform;
191 costmap_transform = tf_buffer_->lookupTransform(
192 costmap_ros_->getGlobalFrameID(), costmap_ros_->getBaseFrameID(),
194 }
catch (tf2::TransformException & ex) {
196 logger_,
"Could not transform %s to %s: %s",
197 costmap_ros_->getBaseFrameID().c_str(), costmap_ros_->getGlobalFrameID().c_str(),
203 nav_msgs::msg::Path local_plan;
204 if (!
simulateTrajectory(pose, motion_target, costmap_transform, local_plan, reversing)) {
207 local_plan.header = transformed_plan.header;
208 local_plan_pub_->publish(local_plan);
215 path_handler_->setPlan(path);
216 goal_reached_ =
false;
220 const double & speed_limit,
const bool & percentage)
222 std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
224 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
225 params_->v_linear_max = params_->v_linear_max_initial;
226 params_->v_angular_max = params_->v_angular_max_initial;
230 params_->v_linear_max = std::max(
231 params_->v_linear_max_initial * speed_limit / 100.0, params_->v_linear_min);
232 params_->v_angular_max = params_->v_angular_max_initial * speed_limit / 100.0;
235 params_->v_linear_max = std::max(speed_limit, params_->v_linear_min);
237 params_->v_angular_max = params_->v_angular_max_initial *
238 speed_limit / params_->v_linear_max_initial;
244 const double & motion_target_dist,
245 const nav_msgs::msg::Path & transformed_plan)
248 auto goal_pose_it = std::find_if(
249 transformed_plan.poses.begin(), transformed_plan.poses.end(), [&](
const auto & ps) {
250 return std::hypot(ps.pose.position.x, ps.pose.position.y) >= motion_target_dist;
254 if (goal_pose_it == transformed_plan.poses.end()) {
255 goal_pose_it = std::prev(transformed_plan.poses.end());
258 return *goal_pose_it;
262 const geometry_msgs::msg::PoseStamped & robot_pose,
263 const geometry_msgs::msg::PoseStamped & motion_target,
264 const geometry_msgs::msg::TransformStamped & costmap_transform,
265 nav_msgs::msg::Path & trajectory,
const bool & backward)
269 robot_pose.pose.position.x, robot_pose.pose.position.y,
270 tf2::getYaw(robot_pose.pose.orientation)))
276 geometry_msgs::msg::PoseStamped next_pose;
277 next_pose.header.frame_id = costmap_ros_->getBaseFrameID();
278 next_pose.pose.orientation.w = 1.0;
279 trajectory.poses.push_back(next_pose);
281 double distance = std::numeric_limits<double>::max();
282 double resolution_ = costmap_ros_->getCostmap()->getResolution();
283 double dt = (params_->v_linear_max > 0.0) ? resolution_ / params_->v_linear_max : 0.0;
286 unsigned int max_iter = 2 * sqrt(
287 motion_target.pose.position.x * motion_target.pose.position.x +
288 motion_target.pose.position.y * motion_target.pose.position.y) / resolution_;
293 next_pose.pose = control_law_->calculateNextPose(
294 dt, motion_target.pose, next_pose.pose, backward);
297 trajectory.poses.push_back(next_pose);
300 geometry_msgs::msg::PoseStamped global_pose;
301 tf2::doTransform(next_pose, global_pose, costmap_transform);
303 global_pose.pose.position.x, global_pose.pose.position.y,
304 tf2::getYaw(global_pose.pose.orientation)))
310 distance = nav2_util::geometry_utils::euclidean_distance(motion_target.pose, next_pose.pose);
311 }
while(distance > resolution_ && trajectory.poses.size() < max_iter);
318 geometry_msgs::msg::Twist vel;
320 vel.angular.z = params_->rotation_scaling_factor * angle_to_target * params_->v_angular_max;
327 if (!costmap_ros_->getCostmap()->worldToMap(x, y, mx, my)) {
329 logger_,
"The path is not in the costmap. Cannot check for collisions. "
330 "Proceed at your own risk, slow the robot, or increase your costmap size.");
336 bool is_tracking_unknown =
337 costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
338 bool consider_footprint = !costmap_ros_->getUseRadius();
340 double footprint_cost;
341 if (consider_footprint) {
342 footprint_cost = collision_checker_->footprintCostAtPose(
343 x, y, theta, costmap_ros_->getRobotFootprint());
345 footprint_cost = collision_checker_->pointCost(mx, my);
348 switch (
static_cast<unsigned char>(footprint_cost)) {
349 case (nav2_costmap_2d::LETHAL_OBSTACLE):
351 case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
352 return consider_footprint ? false :
true;
353 case (nav2_costmap_2d::NO_INFORMATION):
354 return is_tracking_unknown ? false :
true;
363 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.
bool simulateTrajectory(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::PoseStamped &motion_target, const geometry_msgs::msg::TransformStamped &costmap_transform, nav_msgs::msg::Path &trajectory, const bool &backward)
Simulate trajectory calculating in every step the new velocity command based on a new curvature value...
void deactivate() override
Deactivate controller state machine.
geometry_msgs::msg::PoseStamped getMotionTarget(const double &motion_target_dist, const nav_msgs::msg::Path &path)
Get motion target point.
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::Twist rotateToTarget(const double &angle_to_target)
Rotate the robot to face the motion target with maximum angular velocity.
void cleanup() override
Cleanup controller state machine.
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.