15 #ifndef NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
16 #define NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
26 #include "nav2_core/smoother.hpp"
27 #include "nav2_smoother/smoother_utils.hpp"
28 #include "nav2_costmap_2d/costmap_2d.hpp"
29 #include "nav2_costmap_2d/cost_values.hpp"
30 #include "nav2_util/geometry_utils.hpp"
31 #include "nav2_util/node_utils.hpp"
32 #include "nav_msgs/msg/path.hpp"
33 #include "angles/angles.h"
34 #include "tf2/utils.h"
36 namespace nav2_smoother
57 const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
58 std::string name, std::shared_ptr<tf2_ros::Buffer>,
59 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
60 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
override;
65 void cleanup()
override {costmap_sub_.reset();}
85 nav_msgs::msg::Path & path,
86 const rclcpp::Duration & max_time)
override;
98 nav_msgs::msg::Path & path,
99 bool & reversing_segment,
101 const double & max_time);
110 const geometry_msgs::msg::PoseStamped & msg,
111 const unsigned int & dim);
120 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
121 const double & value);
123 double tolerance_, data_w_, smooth_w_;
124 int max_its_, refinement_ctr_;
126 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
127 rclcpp::Logger logger_{rclcpp::get_logger(
"SimpleSmoother")};
smoother interface that acts as a virtual base class for all smoother plugins
A 2D costmap provides a mapping between points in the world and their associated "costs".
A path smoother implementation.
~SimpleSmoother() override=default
A destructor for nav2_smoother::SimpleSmoother.
bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
void deactivate() override
Method to deactivate smoother and any threads involved in execution.
void activate() override
Method to activate smoother and any threads involved in execution.
SimpleSmoother()=default
A constructor for nav2_smoother::SimpleSmoother.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
void cleanup() override
Method to cleanup resources.