16 #ifndef NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_
17 #define NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_
22 #include <unordered_map>
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_util/lifecycle_node.hpp"
32 #include "nav2_util/robot_utils.hpp"
33 #include "nav2_util/simple_action_server.hpp"
34 #include "pluginlib/class_list_macros.hpp"
35 #include "pluginlib/class_loader.hpp"
37 namespace nav2_smoother
48 using SmootherMap = std::unordered_map<std::string, nav2_core::Smoother::Ptr>;
54 explicit SmootherServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
71 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
87 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
97 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
107 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
114 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
116 using Action = nav2_msgs::action::SmoothPath;
136 bool findSmootherId(
const std::string & c_name, std::string & name);
139 std::unique_ptr<ActionServer> action_server_;
142 std::shared_ptr<tf2_ros::Buffer> tf_;
143 std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
146 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
149 pluginlib::ClassLoader<nav2_core::Smoother> lp_loader_;
150 SmootherMap smoothers_;
151 std::vector<std::string> default_ids_;
152 std::vector<std::string> default_types_;
153 std::vector<std::string> smoother_ids_;
154 std::vector<std::string> smoother_types_;
155 std::string smoother_ids_concat_, current_smoother_;
158 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
159 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
160 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
This class hosts variety of plugins of different algorithms to smooth or refine a path from the expos...
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
~SmootherServer()
Destructor for nav2_smoother::SmootherServer.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
bool loadSmootherPlugins()
Loads smoother plugins from parameter file.
SmootherServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_smoother::SmootherServer.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures smoother parameters and member variables.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
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...
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.