21 #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp"
23 using rcl_interfaces::msg::ParameterType;
25 namespace nav2_rotation_shim_controller
29 : lp_loader_(
"nav2_core",
"nav2_core::Controller"),
30 primary_controller_(nullptr),
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)
41 position_goal_checker_ = std::make_unique<nav2_controller::PositionGoalChecker>();
42 position_goal_checker_->initialize(parent, plugin_name_ +
".position_checker", costmap_ros);
45 auto node = parent.lock();
48 costmap_ros_ = costmap_ros;
49 logger_ = node->get_logger();
50 clock_ = node->get_clock();
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));
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));
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_);
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_);
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;
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_);
96 primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
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) {
103 "Failed to create internal controller for rotation shimming. Exception: %s", ex.what());
107 primary_controller_->configure(parent, name, tf, costmap_ros);
110 collision_checker_ = std::make_unique<nav2_costmap_2d::
111 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros->getCostmap());
118 "Activating controller: %s of type "
119 "nav2_rotation_shim_controller::RotationShimController",
120 plugin_name_.c_str());
122 primary_controller_->activate();
123 in_rotation_ =
false;
124 last_angular_vel_ = std::numeric_limits<double>::max();
126 auto node = node_.lock();
127 dyn_params_handler_ = node->add_on_set_parameters_callback(
130 this, std::placeholders::_1));
131 position_goal_checker_->reset();
138 "Deactivating controller: %s of type "
139 "nav2_rotation_shim_controller::RotationShimController",
140 plugin_name_.c_str());
142 primary_controller_->deactivate();
144 if (
auto node = node_.lock()) {
145 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
147 dyn_params_handler_.reset();
154 "Cleaning up controller: %s of type "
155 "nav2_rotation_shim_controller::RotationShimController",
156 plugin_name_.c_str());
158 primary_controller_->cleanup();
159 primary_controller_.reset();
160 position_goal_checker_.reset();
164 const geometry_msgs::msg::PoseStamped & pose,
165 const geometry_msgs::msg::Twist & velocity,
169 if (rotate_to_goal_heading_) {
170 std::lock_guard<std::mutex> lock_reinit(mutex_);
175 if (!nav2_util::transformPoseInTargetFrame(
176 sampled_pt_goal, sampled_pt_goal, *tf_,
177 pose.header.frame_id))
182 geometry_msgs::msg::Pose pose_tolerance;
183 geometry_msgs::msg::Twist vel_tolerance;
185 position_goal_checker_->setXYGoalTolerance(pose_tolerance.position.x);
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);
191 double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw);
194 last_angular_vel_ = cmd_vel.twist.angular.z;
197 }
catch (
const std::runtime_error & e) {
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());
208 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
210 std::lock_guard<std::mutex> lock_reinit(mutex_);
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));
220 angular_distance_to_heading = std::atan2(
221 sampled_pt_base.position.y,
222 sampled_pt_base.position.x);
225 double angular_thresh =
226 in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
227 if (abs(angular_distance_to_heading) > angular_thresh) {
230 "Robot is not within the new path's rough heading, rotating to heading...");
233 last_angular_vel_ = cmd_vel.twist.angular.z;
238 "Robot is at the new path's rough heading, passing to controller");
239 path_updated_ =
false;
241 }
catch (
const std::runtime_error & e) {
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;
252 in_rotation_ =
false;
253 auto cmd_vel = primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
254 last_angular_vel_ = cmd_vel.twist.angular.z;
260 if (current_path_.poses.size() < 2) {
262 "Path is too short to find a valid sampled path point for rotation.");
265 geometry_msgs::msg::Pose start = current_path_.poses.front().pose;
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();
275 return current_path_.poses[i];
279 auto goal = current_path_.poses.back();
280 goal.header.frame_id = current_path_.header.frame_id;
281 goal.header.stamp = clock_->now();
287 if (current_path_.poses.empty()) {
291 auto goal = current_path_.poses.back();
292 goal.header.frame_id = current_path_.header.frame_id;
293 goal.header.stamp = clock_->now();
297 geometry_msgs::msg::Pose
300 geometry_msgs::msg::PoseStamped pt_base;
301 if (!nav2_util::transformPoseInTargetFrame(pt, pt_base, *tf_, costmap_ros_->getBaseFrameID())) {
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)
313 auto current = closed_loop_ ? velocity.angular.z : last_angular_vel_;
314 if (current == std::numeric_limits<double>::max()) {
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);
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;
339 const geometry_msgs::msg::TwistStamped & cmd_vel,
340 const double & angular_distance_to_heading,
341 const geometry_msgs::msg::PoseStamped & pose)
344 double simulated_time = 0.0;
345 double initial_yaw = tf2::getYaw(pose.pose.orientation);
347 double footprint_cost = 0.0;
348 double remaining_rotation_before_thresh =
349 fabs(angular_distance_to_heading) - angular_dist_threshold_;
351 while (simulated_time < simulate_ahead_time_) {
352 simulated_time += control_duration_;
353 yaw = initial_yaw + cmd_vel.twist.angular.z * simulated_time;
356 if (angles::shortest_angular_distance(yaw, initial_yaw) >= remaining_rotation_before_thresh) {
361 footprint_cost = collision_checker_->footprintCostAtPose(
362 pose.pose.position.x, pose.pose.position.y,
363 yaw, costmap_ros_->getRobotFootprint());
365 if (footprint_cost ==
static_cast<double>(NO_INFORMATION) &&
366 costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
369 "RotationShimController detected a potential collision ahead!");
372 if (footprint_cost >=
static_cast<double>(LETHAL_OBSTACLE)) {
381 if (in_rotation_ || current_path_.poses.empty()) {
386 return current_path_.poses.back().pose != path.poses.back().pose;
391 path_updated_ = rotate_to_heading_once_ ?
isGoalChanged(path) :
true;
392 current_path_ = path;
393 primary_controller_->setPlan(path);
394 position_goal_checker_->reset();
399 primary_controller_->setSpeedLimit(speed_limit, percentage);
404 last_angular_vel_ = std::numeric_limits<double>::max();
405 primary_controller_->reset();
406 position_goal_checker_->reset();
409 rcl_interfaces::msg::SetParametersResult
412 rcl_interfaces::msg::SetParametersResult result;
413 std::lock_guard<std::mutex> lock_reinit(mutex_);
415 for (
auto parameter : parameters) {
416 const auto & type = parameter.get_type();
417 const auto & name = parameter.get_name();
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();
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();
444 result.successful =
true;
451 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.
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.