17 #ifndef NAV2_CONSTRAINED_SMOOTHER__CONSTRAINED_SMOOTHER_HPP_
18 #define NAV2_CONSTRAINED_SMOOTHER__CONSTRAINED_SMOOTHER_HPP_
25 #include "nav2_core/smoother.hpp"
26 #include "nav2_constrained_smoother/smoother.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "nav2_util/odometry_utils.hpp"
29 #include "nav2_util/geometry_utils.hpp"
31 namespace nav2_constrained_smoother
59 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
60 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
61 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
62 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub)
override;
87 nav_msgs::msg::Path & path,
88 const rclcpp::Duration & max_time)
override;
91 std::shared_ptr<tf2_ros::Buffer> tf_;
92 std::string plugin_name_;
93 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
94 rclcpp::Logger logger_ {rclcpp::get_logger(
"ConstrainedSmoother")};
96 std::unique_ptr<nav2_constrained_smoother::Smoother> smoother_;
Regulated pure pursuit controller plugin.
~ConstrainedSmoother() override=default
Destrructor for nav2_constrained_smoother::ConstrainedSmoother.
void activate() override
Activate controller state machine.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
void cleanup() override
Cleanup controller state machine.
void deactivate() override
Deactivate controller state machine.
ConstrainedSmoother()=default
Constructor for nav2_constrained_smoother::ConstrainedSmoother.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_sub, std::shared_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub) override
Configure smoother parameters and member variables.
smoother interface that acts as a virtual base class for all smoother plugins