Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
nav2_smoother.hpp
1 // Copyright (c) 2021 RoboTech Vision
2 // Copyright (c) 2019 Intel Corporation
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_
17 #define NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_
18 
19 #include <memory>
20 #include <string>
21 #include <thread>
22 #include <unordered_map>
23 #include <vector>
24 
25 #include "nav2_core/smoother.hpp"
26 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
27 #include "nav2_costmap_2d/costmap_subscriber.hpp"
28 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
29 #include "nav2_costmap_2d/footprint_subscriber.hpp"
30 #include "nav2_msgs/action/smooth_path.hpp"
31 #include "nav2_ros_common/lifecycle_node.hpp"
32 #include "nav2_util/robot_utils.hpp"
33 #include "nav2_ros_common/simple_action_server.hpp"
34 #include "pluginlib/class_list_macros.hpp"
35 #include "pluginlib/class_loader.hpp"
36 
37 namespace nav2_smoother
38 {
39 
46 {
47 public:
48  using SmootherMap = std::unordered_map<std::string, nav2_core::Smoother::Ptr>;
49 
54  explicit SmootherServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
59 
60 protected:
71  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
72 
77  bool loadSmootherPlugins();
78 
87  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
88 
97  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
98 
107  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
108 
114  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
115 
116  using Action = nav2_msgs::action::SmoothPath;
117  using ActionResult = Action::Result;
119 
128  void smoothPlan();
129 
137  bool findSmootherId(const std::string & c_name, std::string & name);
138 
144  bool validate(const nav_msgs::msg::Path & path);
145 
146  // Our action server implements the SmoothPath action
147  typename ActionServer::SharedPtr action_server_;
148 
149  // Transforms
150  std::shared_ptr<tf2_ros::Buffer> tf_;
151  std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
152 
153  // Publishers and subscribers
154  nav2::Publisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
155 
156  // Smoother Plugins
157  pluginlib::ClassLoader<nav2_core::Smoother> lp_loader_;
158  SmootherMap smoothers_;
159  std::vector<std::string> default_ids_;
160  std::vector<std::string> default_types_;
161  std::vector<std::string> smoother_ids_;
162  std::vector<std::string> smoother_types_;
163  std::string smoother_ids_concat_, current_smoother_;
164 
165  // Utilities
166  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
167  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
168  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
169 };
170 
171 } // namespace nav2_smoother
172 
173 #endif // NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_
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 smooth or refine a path from the expos...
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
~SmootherServer()
Destructor for nav2_smoother::SmootherServer.
bool loadSmootherPlugins()
Loads smoother plugins from parameter file.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
bool validate(const nav_msgs::msg::Path &path)
Validate that the path contains a meaningful path for smoothing.
SmootherServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_smoother::SmootherServer.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures smoother parameters and member variables.
bool findSmootherId(const std::string &c_name, std::string &name)
Find the valid smoother ID name for the given request.
void smoothPlan()
SmoothPath action server callback. Handles action server updates and spins server until goal is reach...