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.hpp"
30 #include "nav2_msgs/action/follow_path.hpp"
31 #include "nav2_msgs/msg/speed_limit.hpp"
32 #include "nav2_ros_common/lifecycle_node.hpp"
33 #include "nav2_ros_common/simple_action_server.hpp"
34 #include "nav2_util/robot_utils.hpp"
35 #include "nav2_util/odometry_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::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
86 nav2::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
95 nav2::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
104 nav2::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
110 nav2::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
112 using Action = nav2_msgs::action::FollowPath;
116 typename ActionServer::SharedPtr action_server_;
174 void publishVelocity(
const geometry_msgs::msg::TwistStamped & velocity);
193 bool getRobotPose(geometry_msgs::msg::PoseStamped & pose);
203 return (std::abs(velocity) > threshold) ? velocity : 0.0;
213 geometry_msgs::msg::Twist twist_thresh;
224 rcl_interfaces::msg::SetParametersResult
228 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
229 std::mutex dynamic_params_lock_;
232 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
233 std::unique_ptr<nav2::NodeThread> costmap_thread_;
236 std::unique_ptr<nav2_util::OdomSmoother> odom_sub_;
237 std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
238 nav2::Subscription<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_sub_;
241 pluginlib::ClassLoader<nav2_core::ProgressChecker> progress_checker_loader_;
242 ProgressCheckerMap progress_checkers_;
243 std::vector<std::string> default_progress_checker_ids_;
244 std::vector<std::string> default_progress_checker_types_;
245 std::vector<std::string> progress_checker_ids_;
246 std::vector<std::string> progress_checker_types_;
247 std::string progress_checker_ids_concat_, current_progress_checker_;
250 pluginlib::ClassLoader<nav2_core::GoalChecker> goal_checker_loader_;
251 GoalCheckerMap goal_checkers_;
252 std::vector<std::string> default_goal_checker_ids_;
253 std::vector<std::string> default_goal_checker_types_;
254 std::vector<std::string> goal_checker_ids_;
255 std::vector<std::string> goal_checker_types_;
256 std::string goal_checker_ids_concat_, current_goal_checker_;
259 pluginlib::ClassLoader<nav2_core::Controller> lp_loader_;
260 ControllerMap controllers_;
261 std::vector<std::string> default_ids_;
262 std::vector<std::string> default_types_;
263 std::vector<std::string> controller_ids_;
264 std::vector<std::string> controller_types_;
265 std::string controller_ids_concat_, current_controller_;
267 double controller_frequency_;
268 double min_x_velocity_threshold_;
269 double min_y_velocity_threshold_;
270 double min_theta_velocity_threshold_;
272 double failure_tolerance_;
273 bool use_realtime_priority_;
274 bool publish_zero_velocity_;
275 rclcpp::Duration costmap_update_timeout_;
278 geometry_msgs::msg::PoseStamped end_pose_;
281 rclcpp::Time last_valid_cmd_time_;
284 nav_msgs::msg::Path current_path_;
291 void speedLimitCallback(
const nav2_msgs::msg::SpeedLimit::SharedPtr msg);
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.
This class hosts variety of plugins of different algorithms to complete control tasks from the expose...
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
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 in costmap's frame.
double getThresholdedVelocity(double velocity, double threshold)
get the thresholded velocity
void onGoalExit(bool force_stop)
Called on goal exit.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures controller parameters and member variables.
void computeControl()
FollowPath action server callback. Handles action server updates and spins server until goal is reach...
bool isGoalReached()
Checks if goal is reached.
geometry_msgs::msg::Twist getThresholdedTwist(const geometry_msgs::msg::Twist &twist)
get the thresholded Twist
~ControllerServer()
Destructor for nav2_controller::ControllerServer.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
bool findGoalCheckerId(const std::string &c_name, std::string &name)
Find the valid goal checker ID name for the specified parameter.
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.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
void publishZeroVelocity()
Calls velocity publisher to publish zero velocity.
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.