22 #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp"
24 using rcl_interfaces::msg::ParameterType;
26 namespace nav2_rotation_shim_controller
30 : lp_loader_(
"nav2_core",
"nav2_core::Controller"),
31 primary_controller_(nullptr),
38 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
39 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
40 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
42 position_goal_checker_ = std::make_unique<nav2_controller::PositionGoalChecker>();
43 position_goal_checker_->initialize(parent, plugin_name_ +
".position_checker", costmap_ros);
46 auto node = parent.lock();
49 costmap_ros_ = costmap_ros;
50 logger_ = node->get_logger();
51 clock_ = node->get_clock();
53 std::string primary_controller;
54 double control_frequency;
55 nav2_util::declare_parameter_if_not_declared(
56 node, plugin_name_ +
".angular_dist_threshold", rclcpp::ParameterValue(0.785));
57 nav2_util::declare_parameter_if_not_declared(
58 node, plugin_name_ +
".angular_disengage_threshold", rclcpp::ParameterValue(0.785));
59 nav2_util::declare_parameter_if_not_declared(
60 node, plugin_name_ +
".forward_sampling_distance", rclcpp::ParameterValue(0.5));
61 nav2_util::declare_parameter_if_not_declared(
62 node, plugin_name_ +
".rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.8));
63 nav2_util::declare_parameter_if_not_declared(
64 node, plugin_name_ +
".max_angular_accel", rclcpp::ParameterValue(3.2));
65 nav2_util::declare_parameter_if_not_declared(
66 node, plugin_name_ +
".simulate_ahead_time", rclcpp::ParameterValue(1.0));
67 nav2_util::declare_parameter_if_not_declared(
68 node, plugin_name_ +
".primary_controller", rclcpp::PARAMETER_STRING);
69 nav2_util::declare_parameter_if_not_declared(
70 node, plugin_name_ +
".rotate_to_goal_heading", rclcpp::ParameterValue(
false));
71 nav2_util::declare_parameter_if_not_declared(
72 node, plugin_name_ +
".closed_loop", rclcpp::ParameterValue(
true));
74 node->get_parameter(plugin_name_ +
".angular_dist_threshold", angular_dist_threshold_);
75 node->get_parameter(plugin_name_ +
".angular_disengage_threshold", angular_disengage_threshold_);
76 node->get_parameter(plugin_name_ +
".forward_sampling_distance", forward_sampling_distance_);
78 plugin_name_ +
".rotate_to_heading_angular_vel",
79 rotate_to_heading_angular_vel_);
80 node->get_parameter(plugin_name_ +
".max_angular_accel", max_angular_accel_);
81 node->get_parameter(plugin_name_ +
".simulate_ahead_time", simulate_ahead_time_);
83 primary_controller = node->get_parameter(plugin_name_ +
".primary_controller").as_string();
84 node->get_parameter(
"controller_frequency", control_frequency);
85 control_duration_ = 1.0 / control_frequency;
87 node->get_parameter(plugin_name_ +
".rotate_to_goal_heading", rotate_to_goal_heading_);
88 node->get_parameter(plugin_name_ +
".closed_loop", closed_loop_);
91 primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
93 logger_,
"Created internal controller for rotation shimming: %s of type %s",
94 plugin_name_.c_str(), primary_controller.c_str());
95 }
catch (
const pluginlib::PluginlibException & ex) {
98 "Failed to create internal controller for rotation shimming. Exception: %s", ex.what());
102 primary_controller_->configure(parent, name, tf, costmap_ros);
105 collision_checker_ = std::make_unique<nav2_costmap_2d::
106 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_ros->getCostmap());
113 "Activating controller: %s of type "
114 "nav2_rotation_shim_controller::RotationShimController",
115 plugin_name_.c_str());
117 primary_controller_->activate();
118 in_rotation_ =
false;
119 last_angular_vel_ = std::numeric_limits<double>::max();
121 auto node = node_.lock();
122 dyn_params_handler_ = node->add_on_set_parameters_callback(
125 this, std::placeholders::_1));
126 position_goal_checker_->reset();
133 "Deactivating controller: %s of type "
134 "nav2_rotation_shim_controller::RotationShimController",
135 plugin_name_.c_str());
137 primary_controller_->deactivate();
139 dyn_params_handler_.reset();
146 "Cleaning up controller: %s of type "
147 "nav2_rotation_shim_controller::RotationShimController",
148 plugin_name_.c_str());
150 primary_controller_->cleanup();
151 primary_controller_.reset();
152 position_goal_checker_.reset();
156 const geometry_msgs::msg::PoseStamped & pose,
157 const geometry_msgs::msg::Twist & velocity,
161 if (rotate_to_goal_heading_) {
162 std::lock_guard<std::mutex> lock_reinit(mutex_);
167 if (!nav2_util::transformPoseInTargetFrame(
168 sampled_pt_goal, sampled_pt_goal, *tf_,
169 pose.header.frame_id))
171 throw std::runtime_error(
"Failed to transform pose to base frame!");
174 geometry_msgs::msg::Pose pose_tolerance;
175 geometry_msgs::msg::Twist vel_tolerance;
177 position_goal_checker_->setXYGoalTolerance(pose_tolerance.position.x);
179 if (position_goal_checker_->isGoalReached(pose.pose, sampled_pt_goal.pose, velocity)) {
180 double pose_yaw = tf2::getYaw(pose.pose.orientation);
181 double goal_yaw = tf2::getYaw(sampled_pt_goal.pose.orientation);
183 double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw);
186 last_angular_vel_ = cmd_vel.twist.angular.z;
189 }
catch (
const std::runtime_error & e) {
192 "Rotation Shim Controller was unable to find a goal point,"
193 " a rotational collision was detected, or TF failed to transform"
194 " into base frame! what(): %s", e.what());
200 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
202 std::lock_guard<std::mutex> lock_reinit(mutex_);
206 double angular_distance_to_heading =
207 std::atan2(sampled_pt_base.position.y, sampled_pt_base.position.x);
209 double angular_thresh =
210 in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
211 if (abs(angular_distance_to_heading) > angular_thresh) {
214 "Robot is not within the new path's rough heading, rotating to heading...");
217 last_angular_vel_ = cmd_vel.twist.angular.z;
222 "Robot is at the new path's rough heading, passing to controller");
223 path_updated_ =
false;
225 }
catch (
const std::runtime_error & e) {
228 "Rotation Shim Controller was unable to find a sampling point,"
229 " a rotational collision was detected, or TF failed to transform"
230 " into base frame! what(): %s", e.what());
231 path_updated_ =
false;
236 in_rotation_ =
false;
237 auto cmd_vel = primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
238 last_angular_vel_ = cmd_vel.twist.angular.z;
244 if (current_path_.poses.size() < 2) {
246 "Path is too short to find a valid sampled path point for rotation.");
249 geometry_msgs::msg::Pose start = current_path_.poses.front().pose;
253 for (
unsigned int i = 1; i != current_path_.poses.size(); i++) {
254 dx = current_path_.poses[i].pose.position.x - start.position.x;
255 dy = current_path_.poses[i].pose.position.y - start.position.y;
256 if (hypot(dx, dy) >= forward_sampling_distance_) {
257 current_path_.poses[i].header.frame_id = current_path_.header.frame_id;
258 current_path_.poses[i].header.stamp = clock_->now();
259 return current_path_.poses[i];
265 "Unable to find a sampling point at least %0.2f from the robot,"
266 "passing off to primary controller plugin.", forward_sampling_distance_));
271 if (current_path_.poses.empty()) {
272 throw std::runtime_error(
"Path is empty - cannot find a goal point");
275 auto goal = current_path_.poses.back();
276 goal.header.frame_id = current_path_.header.frame_id;
277 goal.header.stamp = clock_->now();
281 geometry_msgs::msg::Pose
284 geometry_msgs::msg::PoseStamped pt_base;
285 if (!nav2_util::transformPoseInTargetFrame(pt, pt_base, *tf_, costmap_ros_->getBaseFrameID())) {
291 geometry_msgs::msg::TwistStamped
293 const double & angular_distance_to_heading,
294 const geometry_msgs::msg::PoseStamped & pose,
295 const geometry_msgs::msg::Twist & velocity)
297 auto current = closed_loop_ ? velocity.angular.z : last_angular_vel_;
298 if (current == std::numeric_limits<double>::max()) {
302 geometry_msgs::msg::TwistStamped cmd_vel;
303 cmd_vel.header = pose.header;
304 const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0;
305 const double angular_vel = sign * rotate_to_heading_angular_vel_;
306 const double & dt = control_duration_;
307 const double min_feasible_angular_speed = current - max_angular_accel_ * dt;
308 const double max_feasible_angular_speed = current + max_angular_accel_ * dt;
309 cmd_vel.twist.angular.z =
310 std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
317 const geometry_msgs::msg::TwistStamped & cmd_vel,
318 const double & angular_distance_to_heading,
319 const geometry_msgs::msg::PoseStamped & pose)
322 double simulated_time = 0.0;
323 double initial_yaw = tf2::getYaw(pose.pose.orientation);
325 double footprint_cost = 0.0;
326 double remaining_rotation_before_thresh =
327 fabs(angular_distance_to_heading) - angular_dist_threshold_;
329 while (simulated_time < simulate_ahead_time_) {
330 simulated_time += control_duration_;
331 yaw = initial_yaw + cmd_vel.twist.angular.z * simulated_time;
334 if (angles::shortest_angular_distance(yaw, initial_yaw) >= remaining_rotation_before_thresh) {
339 footprint_cost = collision_checker_->footprintCostAtPose(
340 pose.pose.position.x, pose.pose.position.y,
341 yaw, costmap_ros_->getRobotFootprint());
343 if (footprint_cost ==
static_cast<double>(NO_INFORMATION) &&
344 costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
346 throw std::runtime_error(
"RotationShimController detected a potential collision ahead!");
349 if (footprint_cost >=
static_cast<double>(LETHAL_OBSTACLE)) {
350 throw std::runtime_error(
"RotationShimController detected collision ahead!");
357 path_updated_ =
true;
358 current_path_ = path;
359 primary_controller_->setPlan(path);
360 position_goal_checker_->reset();
365 primary_controller_->setSpeedLimit(speed_limit, percentage);
368 rcl_interfaces::msg::SetParametersResult
371 rcl_interfaces::msg::SetParametersResult result;
372 std::lock_guard<std::mutex> lock_reinit(mutex_);
374 for (
auto parameter : parameters) {
375 const auto & type = parameter.get_type();
376 const auto & name = parameter.get_name();
378 if (type == ParameterType::PARAMETER_DOUBLE) {
379 if (name == plugin_name_ +
".angular_dist_threshold") {
380 angular_dist_threshold_ = parameter.as_double();
381 }
else if (name == plugin_name_ +
".forward_sampling_distance") {
382 forward_sampling_distance_ = parameter.as_double();
383 }
else if (name == plugin_name_ +
".rotate_to_heading_angular_vel") {
384 rotate_to_heading_angular_vel_ = parameter.as_double();
385 }
else if (name == plugin_name_ +
".max_angular_accel") {
386 max_angular_accel_ = parameter.as_double();
387 }
else if (name == plugin_name_ +
".simulate_ahead_time") {
388 simulate_ahead_time_ = parameter.as_double();
390 }
else if (type == ParameterType::PARAMETER_BOOL) {
391 if (name == plugin_name_ +
".rotate_to_goal_heading") {
392 rotate_to_goal_heading_ = parameter.as_bool();
393 }
else if (name == plugin_name_ +
".closed_loop") {
394 closed_loop_ = parameter.as_bool();
399 result.successful =
true;
406 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.
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.