22 #include "lifecycle_msgs/msg/state.hpp"
23 #include "nav2_core/controller_exceptions.hpp"
24 #include "nav_2d_utils/conversions.hpp"
25 #include "nav_2d_utils/tf_help.hpp"
26 #include "nav2_util/node_utils.hpp"
27 #include "nav2_util/geometry_utils.hpp"
28 #include "nav2_controller/controller_server.hpp"
30 using namespace std::chrono_literals;
31 using rcl_interfaces::msg::ParameterType;
32 using std::placeholders::_1;
34 namespace nav2_controller
37 ControllerServer::ControllerServer(
const rclcpp::NodeOptions & options)
38 : nav2_util::LifecycleNode(
"controller_server",
"", options),
39 progress_checker_loader_(
"nav2_core",
"nav2_core::ProgressChecker"),
40 default_progress_checker_ids_{
"progress_checker"},
41 default_progress_checker_types_{
"nav2_controller::SimpleProgressChecker"},
42 goal_checker_loader_(
"nav2_core",
"nav2_core::GoalChecker"),
43 default_goal_checker_ids_{
"goal_checker"},
44 default_goal_checker_types_{
"nav2_controller::SimpleGoalChecker"},
45 lp_loader_(
"nav2_core",
"nav2_core::Controller"),
46 default_ids_{
"FollowPath"},
47 default_types_{
"dwb_core::DWBLocalPlanner"},
48 costmap_update_timeout_(300ms)
50 RCLCPP_INFO(get_logger(),
"Creating controller server");
52 declare_parameter(
"controller_frequency", 20.0);
54 declare_parameter(
"action_server_result_timeout", 10.0);
56 declare_parameter(
"progress_checker_plugins", default_progress_checker_ids_);
57 declare_parameter(
"goal_checker_plugins", default_goal_checker_ids_);
58 declare_parameter(
"controller_plugins", default_ids_);
59 declare_parameter(
"min_x_velocity_threshold", rclcpp::ParameterValue(0.0001));
60 declare_parameter(
"min_y_velocity_threshold", rclcpp::ParameterValue(0.0001));
61 declare_parameter(
"min_theta_velocity_threshold", rclcpp::ParameterValue(0.0001));
63 declare_parameter(
"speed_limit_topic", rclcpp::ParameterValue(
"speed_limit"));
65 declare_parameter(
"failure_tolerance", rclcpp::ParameterValue(0.0));
66 declare_parameter(
"use_realtime_priority", rclcpp::ParameterValue(
false));
67 declare_parameter(
"publish_zero_velocity", rclcpp::ParameterValue(
true));
68 declare_parameter(
"costmap_update_timeout", 0.30);
71 costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
72 "local_costmap", std::string{get_namespace()},
"local_costmap",
73 get_parameter(
"use_sim_time").as_bool());
78 progress_checkers_.clear();
79 goal_checkers_.clear();
81 costmap_thread_.reset();
84 nav2_util::CallbackReturn
89 RCLCPP_INFO(get_logger(),
"Configuring controller interface");
91 RCLCPP_INFO(get_logger(),
"getting progress checker plugins..");
92 get_parameter(
"progress_checker_plugins", progress_checker_ids_);
93 if (progress_checker_ids_ == default_progress_checker_ids_) {
94 for (
size_t i = 0; i < default_progress_checker_ids_.size(); ++i) {
95 nav2_util::declare_parameter_if_not_declared(
96 node, default_progress_checker_ids_[i] +
".plugin",
97 rclcpp::ParameterValue(default_progress_checker_types_[i]));
101 RCLCPP_INFO(get_logger(),
"getting goal checker plugins..");
102 get_parameter(
"goal_checker_plugins", goal_checker_ids_);
103 if (goal_checker_ids_ == default_goal_checker_ids_) {
104 for (
size_t i = 0; i < default_goal_checker_ids_.size(); ++i) {
105 nav2_util::declare_parameter_if_not_declared(
106 node, default_goal_checker_ids_[i] +
".plugin",
107 rclcpp::ParameterValue(default_goal_checker_types_[i]));
111 get_parameter(
"controller_plugins", controller_ids_);
112 if (controller_ids_ == default_ids_) {
113 for (
size_t i = 0; i < default_ids_.size(); ++i) {
114 nav2_util::declare_parameter_if_not_declared(
115 node, default_ids_[i] +
".plugin",
116 rclcpp::ParameterValue(default_types_[i]));
120 controller_types_.resize(controller_ids_.size());
121 goal_checker_types_.resize(goal_checker_ids_.size());
122 progress_checker_types_.resize(progress_checker_ids_.size());
124 get_parameter(
"controller_frequency", controller_frequency_);
125 get_parameter(
"min_x_velocity_threshold", min_x_velocity_threshold_);
126 get_parameter(
"min_y_velocity_threshold", min_y_velocity_threshold_);
127 get_parameter(
"min_theta_velocity_threshold", min_theta_velocity_threshold_);
128 RCLCPP_INFO(get_logger(),
"Controller frequency set to %.4fHz", controller_frequency_);
130 std::string speed_limit_topic;
131 get_parameter(
"speed_limit_topic", speed_limit_topic);
132 get_parameter(
"failure_tolerance", failure_tolerance_);
133 get_parameter(
"use_realtime_priority", use_realtime_priority_);
135 costmap_ros_->configure();
137 costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
139 for (
size_t i = 0; i != progress_checker_ids_.size(); i++) {
141 progress_checker_types_[i] = nav2_util::get_plugin_type_param(
142 node, progress_checker_ids_[i]);
143 nav2_core::ProgressChecker::Ptr progress_checker =
144 progress_checker_loader_.createUniqueInstance(progress_checker_types_[i]);
146 get_logger(),
"Created progress_checker : %s of type %s",
147 progress_checker_ids_[i].c_str(), progress_checker_types_[i].c_str());
148 progress_checker->initialize(node, progress_checker_ids_[i]);
149 progress_checkers_.insert({progress_checker_ids_[i], progress_checker});
150 }
catch (
const std::exception & ex) {
153 "Failed to create progress_checker. Exception: %s", ex.what());
155 return nav2_util::CallbackReturn::FAILURE;
159 for (
size_t i = 0; i != progress_checker_ids_.size(); i++) {
160 progress_checker_ids_concat_ += progress_checker_ids_[i] + std::string(
" ");
165 "Controller Server has %s progress checkers available.", progress_checker_ids_concat_.c_str());
167 for (
size_t i = 0; i != goal_checker_ids_.size(); i++) {
169 goal_checker_types_[i] = nav2_util::get_plugin_type_param(node, goal_checker_ids_[i]);
170 nav2_core::GoalChecker::Ptr goal_checker =
171 goal_checker_loader_.createUniqueInstance(goal_checker_types_[i]);
173 get_logger(),
"Created goal checker : %s of type %s",
174 goal_checker_ids_[i].c_str(), goal_checker_types_[i].c_str());
175 goal_checker->initialize(node, goal_checker_ids_[i], costmap_ros_);
176 goal_checkers_.insert({goal_checker_ids_[i], goal_checker});
177 }
catch (
const pluginlib::PluginlibException & ex) {
180 "Failed to create goal checker. Exception: %s", ex.what());
182 return nav2_util::CallbackReturn::FAILURE;
186 for (
size_t i = 0; i != goal_checker_ids_.size(); i++) {
187 goal_checker_ids_concat_ += goal_checker_ids_[i] + std::string(
" ");
192 "Controller Server has %s goal checkers available.", goal_checker_ids_concat_.c_str());
194 for (
size_t i = 0; i != controller_ids_.size(); i++) {
196 controller_types_[i] = nav2_util::get_plugin_type_param(node, controller_ids_[i]);
197 nav2_core::Controller::Ptr controller =
198 lp_loader_.createUniqueInstance(controller_types_[i]);
200 get_logger(),
"Created controller : %s of type %s",
201 controller_ids_[i].c_str(), controller_types_[i].c_str());
202 controller->configure(
203 node, controller_ids_[i],
204 costmap_ros_->getTfBuffer(), costmap_ros_);
205 controllers_.insert({controller_ids_[i], controller});
206 }
catch (
const pluginlib::PluginlibException & ex) {
209 "Failed to create controller. Exception: %s", ex.what());
211 return nav2_util::CallbackReturn::FAILURE;
215 for (
size_t i = 0; i != controller_ids_.size(); i++) {
216 controller_ids_concat_ += controller_ids_[i] + std::string(
" ");
221 "Controller Server has %s controllers available.", controller_ids_concat_.c_str());
223 odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
224 vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node,
"cmd_vel", 1);
226 double action_server_result_timeout;
227 get_parameter(
"action_server_result_timeout", action_server_result_timeout);
228 rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
229 server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
231 double costmap_update_timeout_dbl;
232 get_parameter(
"costmap_update_timeout", costmap_update_timeout_dbl);
233 costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
238 action_server_ = std::make_unique<ActionServer>(
243 std::chrono::milliseconds(500),
244 true , server_options, use_realtime_priority_ );
245 }
catch (
const std::runtime_error & e) {
246 RCLCPP_ERROR(get_logger(),
"Error creating action server! %s", e.what());
248 return nav2_util::CallbackReturn::FAILURE;
252 speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(
253 speed_limit_topic, rclcpp::QoS(10),
254 std::bind(&ControllerServer::speedLimitCallback,
this, std::placeholders::_1));
256 return nav2_util::CallbackReturn::SUCCESS;
259 nav2_util::CallbackReturn
262 RCLCPP_INFO(get_logger(),
"Activating");
264 const auto costmap_ros_state = costmap_ros_->activate();
265 if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
266 return nav2_util::CallbackReturn::FAILURE;
268 ControllerMap::iterator it;
269 for (it = controllers_.begin(); it != controllers_.end(); ++it) {
270 it->second->activate();
272 vel_publisher_->on_activate();
273 action_server_->activate();
277 dyn_params_handler_ = node->add_on_set_parameters_callback(
283 return nav2_util::CallbackReturn::SUCCESS;
286 nav2_util::CallbackReturn
289 RCLCPP_INFO(get_logger(),
"Deactivating");
291 action_server_->deactivate();
292 ControllerMap::iterator it;
293 for (it = controllers_.begin(); it != controllers_.end(); ++it) {
294 it->second->deactivate();
304 costmap_ros_->deactivate();
307 geometry_msgs::msg::TwistStamped velocity;
308 velocity.twist.angular.x = 0;
309 velocity.twist.angular.y = 0;
310 velocity.twist.angular.z = 0;
311 velocity.twist.linear.x = 0;
312 velocity.twist.linear.y = 0;
313 velocity.twist.linear.z = 0;
314 velocity.header.frame_id = costmap_ros_->getBaseFrameID();
315 velocity.header.stamp = now();
318 vel_publisher_->on_deactivate();
320 remove_on_set_parameters_callback(dyn_params_handler_.get());
321 dyn_params_handler_.reset();
326 return nav2_util::CallbackReturn::SUCCESS;
329 nav2_util::CallbackReturn
332 RCLCPP_INFO(get_logger(),
"Cleaning up");
335 ControllerMap::iterator it;
336 for (it = controllers_.begin(); it != controllers_.end(); ++it) {
337 it->second->cleanup();
339 controllers_.clear();
341 goal_checkers_.clear();
342 progress_checkers_.clear();
344 costmap_ros_->cleanup();
348 action_server_.reset();
350 costmap_thread_.reset();
351 vel_publisher_.reset();
352 speed_limit_sub_.reset();
354 return nav2_util::CallbackReturn::SUCCESS;
357 nav2_util::CallbackReturn
360 RCLCPP_INFO(get_logger(),
"Shutting down");
361 return nav2_util::CallbackReturn::SUCCESS;
365 const std::string & c_name,
366 std::string & current_controller)
368 if (controllers_.find(c_name) == controllers_.end()) {
369 if (controllers_.size() == 1 && c_name.empty()) {
371 get_logger(),
"No controller was specified in action call."
372 " Server will use only plugin loaded %s. "
373 "This warning will appear once.", controller_ids_concat_.c_str());
374 current_controller = controllers_.begin()->first;
377 get_logger(),
"FollowPath called with controller name %s, "
378 "which does not exist. Available controllers are: %s.",
379 c_name.c_str(), controller_ids_concat_.c_str());
383 RCLCPP_DEBUG(get_logger(),
"Selected controller: %s.", c_name.c_str());
384 current_controller = c_name;
391 const std::string & c_name,
392 std::string & current_goal_checker)
394 if (goal_checkers_.find(c_name) == goal_checkers_.end()) {
395 if (goal_checkers_.size() == 1 && c_name.empty()) {
397 get_logger(),
"No goal checker was specified in parameter 'current_goal_checker'."
398 " Server will use only plugin loaded %s. "
399 "This warning will appear once.", goal_checker_ids_concat_.c_str());
400 current_goal_checker = goal_checkers_.begin()->first;
403 get_logger(),
"FollowPath called with goal_checker name %s in parameter"
404 " 'current_goal_checker', which does not exist. Available goal checkers are: %s.",
405 c_name.c_str(), goal_checker_ids_concat_.c_str());
409 RCLCPP_DEBUG(get_logger(),
"Selected goal checker: %s.", c_name.c_str());
410 current_goal_checker = c_name;
417 const std::string & c_name,
418 std::string & current_progress_checker)
420 if (progress_checkers_.find(c_name) == progress_checkers_.end()) {
421 if (progress_checkers_.size() == 1 && c_name.empty()) {
423 get_logger(),
"No progress checker was specified in parameter 'current_progress_checker'."
424 " Server will use only plugin loaded %s. "
425 "This warning will appear once.", progress_checker_ids_concat_.c_str());
426 current_progress_checker = progress_checkers_.begin()->first;
429 get_logger(),
"FollowPath called with progress_checker name %s in parameter"
430 " 'current_progress_checker', which does not exist. Available progress checkers are: %s.",
431 c_name.c_str(), progress_checker_ids_concat_.c_str());
435 RCLCPP_DEBUG(get_logger(),
"Selected progress checker: %s.", c_name.c_str());
436 current_progress_checker = c_name;
444 std::lock_guard<std::mutex> lock(dynamic_params_lock_);
446 RCLCPP_INFO(get_logger(),
"Received a goal, begin computing control effort.");
449 auto goal = action_server_->get_current_goal();
454 std::string c_name = goal->controller_id;
455 std::string current_controller;
457 current_controller_ = current_controller;
462 std::string gc_name = goal->goal_checker_id;
463 std::string current_goal_checker;
465 current_goal_checker_ = current_goal_checker;
470 std::string pc_name = goal->progress_checker_id;
471 std::string current_progress_checker;
473 current_progress_checker_ = current_progress_checker;
479 progress_checkers_[current_progress_checker_]->reset();
481 last_valid_cmd_time_ = now();
482 rclcpp::WallRate loop_rate(controller_frequency_);
483 while (rclcpp::ok()) {
484 auto start_time = this->now();
486 if (action_server_ ==
nullptr || !action_server_->is_server_active()) {
487 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
491 if (action_server_->is_cancel_requested()) {
492 if (controllers_[current_controller_]->cancel()) {
493 RCLCPP_INFO(get_logger(),
"Cancellation was successful. Stopping the robot.");
494 action_server_->terminate_all();
498 RCLCPP_INFO_THROTTLE(
499 get_logger(), *get_clock(), 1000,
"Waiting for the controller to finish cancellation");
505 auto waiting_start = now();
506 while (!costmap_ros_->isCurrent()) {
507 if (now() - waiting_start > costmap_update_timeout_) {
518 RCLCPP_INFO(get_logger(),
"Reached the goal!");
522 auto cycle_duration = this->now() - start_time;
523 if (!loop_rate.sleep()) {
526 "Control loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz.",
527 controller_frequency_, 1 / cycle_duration.seconds());
531 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
533 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
534 result->error_code = Action::Result::INVALID_CONTROLLER;
535 action_server_->terminate_current(result);
538 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
540 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
541 result->error_code = Action::Result::TF_ERROR;
542 action_server_->terminate_current(result);
545 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
547 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
548 result->error_code = Action::Result::NO_VALID_CONTROL;
549 action_server_->terminate_current(result);
552 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
554 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
555 result->error_code = Action::Result::FAILED_TO_MAKE_PROGRESS;
556 action_server_->terminate_current(result);
559 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
561 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
562 result->error_code = Action::Result::PATIENCE_EXCEEDED;
563 action_server_->terminate_current(result);
566 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
568 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
569 result->error_code = Action::Result::INVALID_PATH;
570 action_server_->terminate_current(result);
573 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
575 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
576 result->error_code = Action::Result::CONTROLLER_TIMED_OUT;
577 action_server_->terminate_current(result);
580 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
582 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
583 result->error_code = Action::Result::UNKNOWN;
584 action_server_->terminate_current(result);
586 }
catch (std::exception & e) {
587 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
589 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
590 result->error_code = Action::Result::UNKNOWN;
591 action_server_->terminate_current(result);
595 RCLCPP_DEBUG(get_logger(),
"Controller succeeded, setting result");
600 action_server_->succeeded_current();
607 "Providing path to the controller %s", current_controller_.c_str());
608 if (path.poses.empty()) {
611 controllers_[current_controller_]->setPlan(path);
613 end_pose_ = path.poses.back();
614 end_pose_.header.frame_id = path.header.frame_id;
615 goal_checkers_[current_goal_checker_]->reset();
618 get_logger(),
"Path end point is (%.2f, %.2f)",
619 end_pose_.pose.position.x, end_pose_.pose.position.y);
621 current_path_ = path;
626 geometry_msgs::msg::PoseStamped pose;
632 if (!progress_checkers_[current_progress_checker_]->check(pose)) {
638 geometry_msgs::msg::TwistStamped cmd_vel_2d;
642 controllers_[current_controller_]->computeVelocityCommands(
644 nav_2d_utils::twist2Dto3D(twist),
645 goal_checkers_[current_goal_checker_].get());
646 last_valid_cmd_time_ = now();
647 cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
648 cmd_vel_2d.header.stamp = last_valid_cmd_time_;
652 if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) {
653 RCLCPP_WARN(this->get_logger(),
"%s", e.what());
654 cmd_vel_2d.twist.angular.x = 0;
655 cmd_vel_2d.twist.angular.y = 0;
656 cmd_vel_2d.twist.angular.z = 0;
657 cmd_vel_2d.twist.linear.x = 0;
658 cmd_vel_2d.twist.linear.y = 0;
659 cmd_vel_2d.twist.linear.z = 0;
660 cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
661 cmd_vel_2d.header.stamp = now();
662 if ((now() - last_valid_cmd_time_).seconds() > failure_tolerance_ &&
663 failure_tolerance_ != -1.0)
672 std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
673 feedback->speed = std::hypot(cmd_vel_2d.twist.linear.x, cmd_vel_2d.twist.linear.y);
676 nav_msgs::msg::Path & current_path = current_path_;
677 auto find_closest_pose_idx =
678 [&pose, ¤t_path]() {
679 size_t closest_pose_idx = 0;
680 double curr_min_dist = std::numeric_limits<double>::max();
681 for (
size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
682 double curr_dist = nav2_util::geometry_utils::euclidean_distance(
683 pose, current_path.poses[curr_idx]);
684 if (curr_dist < curr_min_dist) {
685 curr_min_dist = curr_dist;
686 closest_pose_idx = curr_idx;
689 return closest_pose_idx;
692 feedback->distance_to_goal =
693 nav2_util::geometry_utils::calculate_path_length(current_path_, find_closest_pose_idx());
694 action_server_->publish_feedback(feedback);
696 RCLCPP_DEBUG(get_logger(),
"Publishing velocity at time %.2f", now().seconds());
702 if (action_server_->is_preempt_requested()) {
703 RCLCPP_INFO(get_logger(),
"Passing new path to controller.");
704 auto goal = action_server_->accept_pending_goal();
705 std::string current_controller;
707 current_controller_ = current_controller;
710 get_logger(),
"Terminating action, invalid controller %s requested.",
711 goal->controller_id.c_str());
712 action_server_->terminate_current();
715 std::string current_goal_checker;
717 current_goal_checker_ = current_goal_checker;
720 get_logger(),
"Terminating action, invalid goal checker %s requested.",
721 goal->goal_checker_id.c_str());
722 action_server_->terminate_current();
725 std::string current_progress_checker;
727 if (current_progress_checker_ != current_progress_checker) {
729 get_logger(),
"Change of progress checker %s requested, resetting it",
730 goal->progress_checker_id.c_str());
731 current_progress_checker_ = current_progress_checker;
732 progress_checkers_[current_progress_checker_]->reset();
736 get_logger(),
"Terminating action, invalid progress checker %s requested.",
737 goal->progress_checker_id.c_str());
738 action_server_->terminate_current();
747 auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>(velocity);
748 if (vel_publisher_->is_activated() && vel_publisher_->get_subscription_count() > 0) {
749 vel_publisher_->publish(std::move(cmd_vel));
755 if (get_parameter(
"publish_zero_velocity").as_bool()) {
756 geometry_msgs::msg::TwistStamped velocity;
757 velocity.twist.angular.x = 0;
758 velocity.twist.angular.y = 0;
759 velocity.twist.angular.z = 0;
760 velocity.twist.linear.x = 0;
761 velocity.twist.linear.y = 0;
762 velocity.twist.linear.z = 0;
763 velocity.header.frame_id = costmap_ros_->getBaseFrameID();
764 velocity.header.stamp = now();
769 ControllerMap::iterator it;
770 for (it = controllers_.begin(); it != controllers_.end(); ++it) {
777 geometry_msgs::msg::PoseStamped pose;
784 geometry_msgs::msg::Twist velocity = nav_2d_utils::twist2Dto3D(twist);
786 geometry_msgs::msg::PoseStamped transformed_end_pose;
787 rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance()));
788 nav_2d_utils::transformPose(
789 costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
790 end_pose_, transformed_end_pose, tolerance);
792 return goal_checkers_[current_goal_checker_]->isGoalReached(
793 pose.pose, transformed_end_pose.pose,
799 geometry_msgs::msg::PoseStamped current_pose;
800 if (!costmap_ros_->getRobotPose(current_pose)) {
807 void ControllerServer::speedLimitCallback(
const nav2_msgs::msg::SpeedLimit::SharedPtr msg)
809 ControllerMap::iterator it;
810 for (it = controllers_.begin(); it != controllers_.end(); ++it) {
811 it->second->setSpeedLimit(msg->speed_limit, msg->percentage);
815 rcl_interfaces::msg::SetParametersResult
818 rcl_interfaces::msg::SetParametersResult result;
820 for (
auto parameter : parameters) {
821 const auto & type = parameter.get_type();
822 const auto & name = parameter.get_name();
826 if (name.find(
'.') != std::string::npos) {
830 if (!dynamic_params_lock_.try_lock()) {
833 "Unable to dynamically change Parameters while the controller is currently running");
834 result.successful =
false;
836 "Unable to dynamically change Parameters while the controller is currently running";
840 if (type == ParameterType::PARAMETER_DOUBLE) {
841 if (name ==
"controller_frequency") {
842 controller_frequency_ = parameter.as_double();
843 }
else if (name ==
"min_x_velocity_threshold") {
844 min_x_velocity_threshold_ = parameter.as_double();
845 }
else if (name ==
"min_y_velocity_threshold") {
846 min_y_velocity_threshold_ = parameter.as_double();
847 }
else if (name ==
"min_theta_velocity_threshold") {
848 min_theta_velocity_threshold_ = parameter.as_double();
849 }
else if (name ==
"failure_tolerance") {
850 failure_tolerance_ = parameter.as_double();
854 dynamic_params_lock_.unlock();
857 result.successful =
true;
863 #include "rclcpp_components/register_node_macro.hpp"
This class hosts variety of plugins of different algorithms to complete control tasks from the expose...
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void publishVelocity(const geometry_msgs::msg::TwistStamped &velocity)
Calls velocity publisher to publish the velocity on "cmd_vel" topic.
bool getRobotPose(geometry_msgs::msg::PoseStamped &pose)
Obtain current pose of the robot.
nav_2d_msgs::msg::Twist2D getThresholdedTwist(const nav_2d_msgs::msg::Twist2D &twist)
get the thresholded Twist
void computeControl()
FollowPath action server callback. Handles action server updates and spins server until goal is reach...
bool isGoalReached()
Checks if goal is reached.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
~ControllerServer()
Destructor for nav2_controller::ControllerServer.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
bool findGoalCheckerId(const std::string &c_name, std::string &name)
Find the valid goal checker ID name for the specified parameter.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
void updateGlobalPath()
Calls setPlannerPath method with an updated path received from action server.
void setPlannerPath(const nav_msgs::msg::Path &path)
Assigns path to controller.
void publishZeroVelocity()
Calls velocity publisher to publish zero velocity.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures controller parameters and member variables.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
bool findControllerId(const std::string &c_name, std::string &name)
Find the valid controller ID name for the given request.
bool findProgressCheckerId(const std::string &c_name, std::string &name)
Find the valid progress checker ID name for the specified parameter.
void computeAndPublishVelocity()
Calculates velocity and publishes to "cmd_vel" topic.
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.