15 #ifndef NAV2_CONTROLLER__CONTROLLER_SERVER_HPP_
16 #define NAV2_CONTROLLER__CONTROLLER_SERVER_HPP_
21 #include <unordered_map>
25 #include "nav2_core/controller.hpp"
26 #include "nav2_core/progress_checker.hpp"
27 #include "nav2_core/goal_checker.hpp"
28 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
29 #include "tf2_ros/transform_listener.h"
30 #include "nav2_msgs/action/follow_path.hpp"
31 #include "nav2_msgs/msg/speed_limit.hpp"
32 #include "nav_2d_utils/odom_subscriber.hpp"
33 #include "nav2_util/lifecycle_node.hpp"
34 #include "nav2_util/simple_action_server.hpp"
35 #include "nav2_util/robot_utils.hpp"
36 #include "nav2_util/twist_publisher.hpp"
37 #include "pluginlib/class_loader.hpp"
38 #include "pluginlib/class_list_macros.hpp"
40 namespace nav2_controller
43 class ProgressChecker;
52 using ControllerMap = std::unordered_map<std::string, nav2_core::Controller::Ptr>;
53 using GoalCheckerMap = std::unordered_map<std::string, nav2_core::GoalChecker::Ptr>;
54 using ProgressCheckerMap = std::unordered_map<std::string, nav2_core::ProgressChecker::Ptr>;
60 explicit ControllerServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
77 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
86 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
95 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
104 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
110 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
112 using Action = nav2_msgs::action::FollowPath;
116 std::unique_ptr<ActionServer> action_server_;
174 void publishVelocity(
const geometry_msgs::msg::TwistStamped & velocity);
189 bool getRobotPose(geometry_msgs::msg::PoseStamped & pose);
199 return (std::abs(velocity) > threshold) ? velocity : 0.0;
209 nav_2d_msgs::msg::Twist2D twist_thresh;
220 rcl_interfaces::msg::SetParametersResult
224 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
225 std::mutex dynamic_params_lock_;
228 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
229 std::unique_ptr<nav2_util::NodeThread> costmap_thread_;
232 std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
233 std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
234 rclcpp::Subscription<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_sub_;
237 pluginlib::ClassLoader<nav2_core::ProgressChecker> progress_checker_loader_;
238 ProgressCheckerMap progress_checkers_;
239 std::vector<std::string> default_progress_checker_ids_;
240 std::vector<std::string> default_progress_checker_types_;
241 std::vector<std::string> progress_checker_ids_;
242 std::vector<std::string> progress_checker_types_;
243 std::string progress_checker_ids_concat_, current_progress_checker_;
246 pluginlib::ClassLoader<nav2_core::GoalChecker> goal_checker_loader_;
247 GoalCheckerMap goal_checkers_;
248 std::vector<std::string> default_goal_checker_ids_;
249 std::vector<std::string> default_goal_checker_types_;
250 std::vector<std::string> goal_checker_ids_;
251 std::vector<std::string> goal_checker_types_;
252 std::string goal_checker_ids_concat_, current_goal_checker_;
255 pluginlib::ClassLoader<nav2_core::Controller> lp_loader_;
256 ControllerMap controllers_;
257 std::vector<std::string> default_ids_;
258 std::vector<std::string> default_types_;
259 std::vector<std::string> controller_ids_;
260 std::vector<std::string> controller_types_;
261 std::string controller_ids_concat_, current_controller_;
263 double controller_frequency_;
264 double min_x_velocity_threshold_;
265 double min_y_velocity_threshold_;
266 double min_theta_velocity_threshold_;
268 double failure_tolerance_;
269 bool use_realtime_priority_;
270 rclcpp::Duration costmap_update_timeout_;
273 geometry_msgs::msg::PoseStamped end_pose_;
276 rclcpp::Time last_valid_cmd_time_;
279 nav_msgs::msg::Path current_path_;
286 void speedLimitCallback(
const nav2_msgs::msg::SpeedLimit::SharedPtr msg);
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.
ControllerServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for nav2_controller::ControllerServer.
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
double getThresholdedVelocity(double velocity, double threshold)
get the thresholded velocity
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.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.