21 #include "angles/angles.h"
22 #include "nav2_util/geometry_utils.hpp"
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp"
28 using rcl_interfaces::msg::ParameterType;
30 namespace nav2_rotation_shim_controller
34 : lp_loader_(
"nav2_core",
"nav2_core::Controller"),
35 primary_controller_(nullptr),
42 const nav2::LifecycleNode::WeakPtr & parent,
43 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
44 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
46 position_goal_checker_ = std::make_unique<nav2_controller::PositionGoalChecker>();
47 position_goal_checker_->initialize(parent, plugin_name_ +
".position_checker", costmap_ros);
50 auto node = parent.lock();
53 costmap_ros_ = costmap_ros;
54 logger_ = node->get_logger();
55 clock_ = node->get_clock();
57 std::string primary_controller;
58 double control_frequency;
59 nav2::declare_parameter_if_not_declared(
60 node, plugin_name_ +
".angular_dist_threshold", rclcpp::ParameterValue(0.785));
61 nav2::declare_parameter_if_not_declared(
62 node, plugin_name_ +
".angular_disengage_threshold", rclcpp::ParameterValue(0.785 / 2.0));
63 nav2::declare_parameter_if_not_declared(
64 node, plugin_name_ +
".forward_sampling_distance", rclcpp::ParameterValue(0.5));
65 nav2::declare_parameter_if_not_declared(
66 node, plugin_name_ +
".rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.8));
67 nav2::declare_parameter_if_not_declared(
68 node, plugin_name_ +
".max_angular_accel", rclcpp::ParameterValue(3.2));
69 nav2::declare_parameter_if_not_declared(
70 node, plugin_name_ +
".simulate_ahead_time", rclcpp::ParameterValue(1.0));
71 nav2::declare_parameter_if_not_declared(
72 node, plugin_name_ +
".primary_controller", rclcpp::PARAMETER_STRING);
73 nav2::declare_parameter_if_not_declared(
74 node, plugin_name_ +
".rotate_to_goal_heading", rclcpp::ParameterValue(
false));
75 nav2::declare_parameter_if_not_declared(
76 node, plugin_name_ +
".rotate_to_heading_once", rclcpp::ParameterValue(
false));
77 nav2::declare_parameter_if_not_declared(
78 node, plugin_name_ +
".closed_loop", rclcpp::ParameterValue(
true));
79 nav2::declare_parameter_if_not_declared(
80 node, plugin_name_ +
".use_path_orientations", rclcpp::ParameterValue(
false));
82 node->get_parameter(plugin_name_ +
".angular_dist_threshold", angular_dist_threshold_);
83 node->get_parameter(plugin_name_ +
".angular_disengage_threshold", angular_disengage_threshold_);
84 node->get_parameter(plugin_name_ +
".forward_sampling_distance", forward_sampling_distance_);
86 plugin_name_ +
".rotate_to_heading_angular_vel",
87 rotate_to_heading_angular_vel_);
88 node->get_parameter(plugin_name_ +
".max_angular_accel", max_angular_accel_);
89 node->get_parameter(plugin_name_ +
".simulate_ahead_time", simulate_ahead_time_);
91 primary_controller = node->get_parameter(plugin_name_ +
".primary_controller").as_string();
92 node->get_parameter(
"controller_frequency", control_frequency);
93 control_duration_ = 1.0 / control_frequency;
95 node->get_parameter(plugin_name_ +
".rotate_to_goal_heading", rotate_to_goal_heading_);
96 node->get_parameter(plugin_name_ +
".rotate_to_heading_once", rotate_to_heading_once_);
97 node->get_parameter(plugin_name_ +
".closed_loop", closed_loop_);
98 node->get_parameter(plugin_name_ +
".use_path_orientations", use_path_orientations_);
101 primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
103 logger_,
"Created internal controller for rotation shimming: %s of type %s",
104 plugin_name_.c_str(), primary_controller.c_str());
105 }
catch (
const pluginlib::PluginlibException & ex) {
108 "Failed to create internal controller for rotation shimming. Exception: %s", ex.what());
112 primary_controller_->configure(parent, name, tf, costmap_ros);
115 collision_checker_ = std::make_unique<nav2_costmap_2d::
116 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros->getCostmap());
123 "Activating controller: %s of type "
124 "nav2_rotation_shim_controller::RotationShimController",
125 plugin_name_.c_str());
127 primary_controller_->activate();
128 in_rotation_ =
false;
129 last_angular_vel_ = std::numeric_limits<double>::max();
131 auto node = node_.lock();
132 dyn_params_handler_ = node->add_on_set_parameters_callback(
135 this, std::placeholders::_1));
136 position_goal_checker_->reset();
143 "Deactivating controller: %s of type "
144 "nav2_rotation_shim_controller::RotationShimController",
145 plugin_name_.c_str());
147 primary_controller_->deactivate();
149 if (
auto node = node_.lock()) {
150 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
152 dyn_params_handler_.reset();
159 "Cleaning up controller: %s of type "
160 "nav2_rotation_shim_controller::RotationShimController",
161 plugin_name_.c_str());
163 primary_controller_->cleanup();
164 primary_controller_.reset();
165 position_goal_checker_.reset();
169 const geometry_msgs::msg::PoseStamped & pose,
170 const geometry_msgs::msg::Twist & velocity,
174 if (rotate_to_goal_heading_) {
175 std::lock_guard<std::mutex> lock_reinit(mutex_);
180 if (!nav2_util::transformPoseInTargetFrame(
181 sampled_pt_goal, sampled_pt_goal, *tf_,
182 pose.header.frame_id))
187 geometry_msgs::msg::Pose pose_tolerance;
188 geometry_msgs::msg::Twist vel_tolerance;
190 position_goal_checker_->setXYGoalTolerance(pose_tolerance.position.x);
192 if (position_goal_checker_->isGoalReached(pose.pose, sampled_pt_goal.pose, velocity)) {
193 double pose_yaw = tf2::getYaw(pose.pose.orientation);
194 double goal_yaw = tf2::getYaw(sampled_pt_goal.pose.orientation);
196 double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw);
199 last_angular_vel_ = cmd_vel.twist.angular.z;
202 }
catch (
const std::runtime_error & e) {
205 "Rotation Shim Controller was unable to find a goal point,"
206 " a rotational collision was detected, or TF failed to transform"
207 " into base frame! what(): %s", e.what());
213 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
215 std::lock_guard<std::mutex> lock_reinit(mutex_);
218 double angular_distance_to_heading;
219 if (use_path_orientations_) {
220 angular_distance_to_heading = angles::shortest_angular_distance(
221 tf2::getYaw(pose.pose.orientation),
222 tf2::getYaw(sampled_pt.pose.orientation));
225 angular_distance_to_heading = std::atan2(
226 sampled_pt_base.position.y,
227 sampled_pt_base.position.x);
230 double angular_thresh =
231 in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
232 if (abs(angular_distance_to_heading) > angular_thresh) {
235 "Robot is not within the new path's rough heading, rotating to heading...");
238 last_angular_vel_ = cmd_vel.twist.angular.z;
243 "Robot is at the new path's rough heading, passing to controller");
244 path_updated_ =
false;
246 }
catch (
const std::runtime_error & e) {
249 "Rotation Shim Controller was unable to find a sampling point,"
250 " a rotational collision was detected, or TF failed to transform"
251 " into base frame! what(): %s", e.what());
252 path_updated_ =
false;
257 in_rotation_ =
false;
258 auto cmd_vel = primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
259 last_angular_vel_ = cmd_vel.twist.angular.z;
265 if (current_path_.poses.size() < 2) {
267 "Path is too short to find a valid sampled path point for rotation.");
270 geometry_msgs::msg::Pose start = current_path_.poses.front().pose;
274 for (
unsigned int i = 1; i != current_path_.poses.size(); i++) {
275 dx = current_path_.poses[i].pose.position.x - start.position.x;
276 dy = current_path_.poses[i].pose.position.y - start.position.y;
277 if (hypot(dx, dy) >= forward_sampling_distance_) {
278 current_path_.poses[i].header.frame_id = current_path_.header.frame_id;
279 current_path_.poses[i].header.stamp = clock_->now();
280 return current_path_.poses[i];
284 auto goal = current_path_.poses.back();
285 goal.header.frame_id = current_path_.header.frame_id;
286 goal.header.stamp = clock_->now();
292 if (current_path_.poses.empty()) {
296 auto goal = current_path_.poses.back();
297 goal.header.frame_id = current_path_.header.frame_id;
298 goal.header.stamp = clock_->now();
302 geometry_msgs::msg::Pose
305 geometry_msgs::msg::PoseStamped pt_base;
306 if (!nav2_util::transformPoseInTargetFrame(pt, pt_base, *tf_, costmap_ros_->getBaseFrameID())) {
312 geometry_msgs::msg::TwistStamped
314 const double & angular_distance_to_heading,
315 const geometry_msgs::msg::PoseStamped & pose,
316 const geometry_msgs::msg::Twist & velocity)
318 auto current = closed_loop_ ? velocity.angular.z : last_angular_vel_;
319 if (current == std::numeric_limits<double>::max()) {
323 geometry_msgs::msg::TwistStamped cmd_vel;
324 cmd_vel.header = pose.header;
325 const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0;
326 const double angular_vel = sign * rotate_to_heading_angular_vel_;
327 const double & dt = control_duration_;
328 const double min_feasible_angular_speed = current - max_angular_accel_ * dt;
329 const double max_feasible_angular_speed = current + max_angular_accel_ * dt;
330 cmd_vel.twist.angular.z =
331 std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
334 double max_vel_to_stop = std::sqrt(2 * max_angular_accel_ * fabs(angular_distance_to_heading));
335 if (fabs(cmd_vel.twist.angular.z) > max_vel_to_stop) {
336 cmd_vel.twist.angular.z = sign * max_vel_to_stop;
344 const geometry_msgs::msg::TwistStamped & cmd_vel,
345 const double & angular_distance_to_heading,
346 const geometry_msgs::msg::PoseStamped & pose)
349 double simulated_time = 0.0;
350 double initial_yaw = tf2::getYaw(pose.pose.orientation);
352 double footprint_cost = 0.0;
353 double remaining_rotation_before_thresh =
354 fabs(angular_distance_to_heading) - angular_dist_threshold_;
356 while (simulated_time < simulate_ahead_time_) {
357 simulated_time += control_duration_;
358 yaw = initial_yaw + cmd_vel.twist.angular.z * simulated_time;
361 if (angles::shortest_angular_distance(yaw, initial_yaw) >= remaining_rotation_before_thresh) {
366 footprint_cost = collision_checker_->footprintCostAtPose(
367 pose.pose.position.x, pose.pose.position.y,
368 yaw, costmap_ros_->getRobotFootprint());
370 if (footprint_cost ==
static_cast<double>(NO_INFORMATION) &&
371 costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
374 "RotationShimController detected a potential collision ahead!");
377 if (footprint_cost >=
static_cast<double>(LETHAL_OBSTACLE)) {
386 if (in_rotation_ || current_path_.poses.empty()) {
391 return current_path_.poses.back().pose != path.poses.back().pose;
396 path_updated_ = rotate_to_heading_once_ ?
isGoalChanged(path) :
true;
397 current_path_ = path;
398 primary_controller_->setPlan(path);
399 position_goal_checker_->reset();
404 primary_controller_->setSpeedLimit(speed_limit, percentage);
409 last_angular_vel_ = std::numeric_limits<double>::max();
410 primary_controller_->reset();
411 position_goal_checker_->reset();
414 rcl_interfaces::msg::SetParametersResult
417 rcl_interfaces::msg::SetParametersResult result;
418 std::lock_guard<std::mutex> lock_reinit(mutex_);
420 for (
auto parameter : parameters) {
421 const auto & param_type = parameter.get_type();
422 const auto & param_name = parameter.get_name();
423 if (param_name.find(plugin_name_ +
".") != 0) {
427 if (param_type == ParameterType::PARAMETER_DOUBLE) {
428 if (param_name == plugin_name_ +
".angular_dist_threshold") {
429 angular_dist_threshold_ = parameter.as_double();
430 }
else if (param_name == plugin_name_ +
".forward_sampling_distance") {
431 forward_sampling_distance_ = parameter.as_double();
432 }
else if (param_name == plugin_name_ +
".rotate_to_heading_angular_vel") {
433 rotate_to_heading_angular_vel_ = parameter.as_double();
434 }
else if (param_name == plugin_name_ +
".max_angular_accel") {
435 max_angular_accel_ = parameter.as_double();
436 }
else if (param_name == plugin_name_ +
".simulate_ahead_time") {
437 simulate_ahead_time_ = parameter.as_double();
439 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
440 if (param_name == plugin_name_ +
".rotate_to_goal_heading") {
441 rotate_to_goal_heading_ = parameter.as_bool();
442 }
else if (param_name == plugin_name_ +
".rotate_to_heading_once") {
443 rotate_to_heading_once_ = parameter.as_bool();
444 }
else if (param_name == plugin_name_ +
".closed_loop") {
445 closed_loop_ = parameter.as_bool();
446 }
else if (param_name == plugin_name_ +
".use_path_orientations") {
447 use_path_orientations_ = parameter.as_bool();
452 result.successful =
true;
459 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...
A 2D costmap provides a mapping between points in the world and their associated "costs".
Rotate to rough path heading controller shim plugin.
void deactivate() override
Deactivate 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.
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.
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.