Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
controller_server.hpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_CONTROLLER__CONTROLLER_SERVER_HPP_
16 #define NAV2_CONTROLLER__CONTROLLER_SERVER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <thread>
21 #include <unordered_map>
22 #include <vector>
23 #include <mutex>
24 
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"
39 
40 namespace nav2_controller
41 {
42 
43 class ProgressChecker;
50 {
51 public:
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>;
55 
60  explicit ControllerServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
65 
66 protected:
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;
111 
112  using Action = nav2_msgs::action::FollowPath;
114 
115  // Our action server implements the FollowPath action
116  std::unique_ptr<ActionServer> action_server_;
117 
127  void computeControl();
128 
136  bool findControllerId(const std::string & c_name, std::string & name);
137 
145  bool findGoalCheckerId(const std::string & c_name, std::string & name);
146 
154  bool findProgressCheckerId(const std::string & c_name, std::string & name);
155 
160  void setPlannerPath(const nav_msgs::msg::Path & path);
169  void updateGlobalPath();
174  void publishVelocity(const geometry_msgs::msg::TwistStamped & velocity);
178  void publishZeroVelocity();
182  void onGoalExit(bool force_stop);
187  bool isGoalReached();
193  bool getRobotPose(geometry_msgs::msg::PoseStamped & pose);
194 
201  double getThresholdedVelocity(double velocity, double threshold)
202  {
203  return (std::abs(velocity) > threshold) ? velocity : 0.0;
204  }
205 
211  nav_2d_msgs::msg::Twist2D getThresholdedTwist(const nav_2d_msgs::msg::Twist2D & twist)
212  {
213  nav_2d_msgs::msg::Twist2D twist_thresh;
214  twist_thresh.x = getThresholdedVelocity(twist.x, min_x_velocity_threshold_);
215  twist_thresh.y = getThresholdedVelocity(twist.y, min_y_velocity_threshold_);
216  twist_thresh.theta = getThresholdedVelocity(twist.theta, min_theta_velocity_threshold_);
217  return twist_thresh;
218  }
219 
224  rcl_interfaces::msg::SetParametersResult
225  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
226 
227  // Dynamic parameters handler
228  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
229  std::mutex dynamic_params_lock_;
230 
231  // The controller needs a costmap node
232  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
233  std::unique_ptr<nav2_util::NodeThread> costmap_thread_;
234 
235  // Publishers and subscribers
236  std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
237  std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
238  rclcpp::Subscription<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_sub_;
239 
240  // Progress Checker Plugin
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_;
248 
249  // Goal Checker Plugin
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_;
257 
258  // Controller Plugins
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_;
266 
267  double controller_frequency_;
268  double min_x_velocity_threshold_;
269  double min_y_velocity_threshold_;
270  double min_theta_velocity_threshold_;
271 
272  double failure_tolerance_;
273  bool use_realtime_priority_;
274  bool publish_zero_velocity_;
275  rclcpp::Duration costmap_update_timeout_;
276 
277  // Whether we've published the single controller warning yet
278  geometry_msgs::msg::PoseStamped end_pose_;
279 
280  // Last time the controller generated a valid command
281  rclcpp::Time last_valid_cmd_time_;
282 
283  // Current path container
284  nav_msgs::msg::Path current_path_;
285 
286 private:
291  void speedLimitCallback(const nav2_msgs::msg::SpeedLimit::SharedPtr msg);
292 };
293 
294 } // namespace nav2_controller
295 
296 #endif // NAV2_CONTROLLER__CONTROLLER_SERVER_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.
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.
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 onGoalExit(bool force_stop)
Called on goal exit.
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.