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 "pluginlib/class_loader.hpp"
37 #include "pluginlib/class_list_macros.hpp"
39 namespace nav2_controller
42 class ProgressChecker;
51 using ControllerMap = std::unordered_map<std::string, nav2_core::Controller::Ptr>;
52 using GoalCheckerMap = std::unordered_map<std::string, nav2_core::GoalChecker::Ptr>;
58 explicit ControllerServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
75 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
84 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
93 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
102 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
108 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
110 using Action = nav2_msgs::action::FollowPath;
114 std::unique_ptr<ActionServer> action_server_;
163 void publishVelocity(
const geometry_msgs::msg::TwistStamped & velocity);
178 bool getRobotPose(geometry_msgs::msg::PoseStamped & pose);
188 return (std::abs(velocity) > threshold) ? velocity : 0.0;
198 nav_2d_msgs::msg::Twist2D twist_thresh;
209 rcl_interfaces::msg::SetParametersResult
213 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
214 std::mutex dynamic_params_lock_;
217 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
218 std::unique_ptr<nav2_util::NodeThread> costmap_thread_;
221 std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
222 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr vel_publisher_;
223 rclcpp::Subscription<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_sub_;
226 pluginlib::ClassLoader<nav2_core::ProgressChecker> progress_checker_loader_;
227 nav2_core::ProgressChecker::Ptr progress_checker_;
228 std::string default_progress_checker_id_;
229 std::string default_progress_checker_type_;
230 std::string progress_checker_id_;
231 std::string progress_checker_type_;
234 pluginlib::ClassLoader<nav2_core::GoalChecker> goal_checker_loader_;
235 GoalCheckerMap goal_checkers_;
236 std::vector<std::string> default_goal_checker_ids_;
237 std::vector<std::string> default_goal_checker_types_;
238 std::vector<std::string> goal_checker_ids_;
239 std::vector<std::string> goal_checker_types_;
240 std::string goal_checker_ids_concat_, current_goal_checker_;
243 pluginlib::ClassLoader<nav2_core::Controller> lp_loader_;
244 ControllerMap controllers_;
245 std::vector<std::string> default_ids_;
246 std::vector<std::string> default_types_;
247 std::vector<std::string> controller_ids_;
248 std::vector<std::string> controller_types_;
249 std::string controller_ids_concat_, current_controller_;
251 double controller_frequency_;
252 double min_x_velocity_threshold_;
253 double min_y_velocity_threshold_;
254 double min_theta_velocity_threshold_;
256 double failure_tolerance_;
257 bool publish_zero_velocity_;
260 geometry_msgs::msg::PoseStamped end_pose_;
263 rclcpp::Time last_valid_cmd_time_;
266 nav_msgs::msg::Path current_path_;
273 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.
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.