|
Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Regulated pure pursuit controller plugin. More...
#include <nav2_constrained_smoother/include/nav2_constrained_smoother/constrained_smoother.hpp>


Public Member Functions | |
| ConstrainedSmoother ()=default | |
| Constructor for nav2_constrained_smoother::ConstrainedSmoother. | |
| ~ConstrainedSmoother () override=default | |
| Destrructor 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. More... | |
| void | cleanup () override |
| Cleanup controller state machine. | |
| void | activate () override |
| Activate controller state machine. | |
| void | deactivate () override |
| Deactivate controller state machine. | |
| bool | smooth (nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override |
| Method to smooth given path. More... | |
Public Member Functions inherited from nav2_core::Smoother | |
| virtual | ~Smoother () |
| Virtual destructor. | |
Protected Attributes | |
| std::shared_ptr< tf2_ros::Buffer > | tf_ |
| std::string | plugin_name_ |
| std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > | costmap_sub_ |
| rclcpp::Logger | logger_ {rclcpp::get_logger("ConstrainedSmoother")} |
| std::unique_ptr< nav2_constrained_smoother::Smoother > | smoother_ |
| SmootherParams | smoother_params_ |
| OptimizerParams | optimizer_params_ |
Additional Inherited Members | |
Public Types inherited from nav2_core::Smoother | |
| using | Ptr = std::shared_ptr< nav2_core::Smoother > |
Regulated pure pursuit controller plugin.
Definition at line 38 of file constrained_smoother.hpp.
|
overridevirtual |
Configure smoother parameters and member variables.
| parent | WeakPtr to node |
| name | Name of plugin |
| tf | TF buffer |
| costmap_ros | Costmap2DROS object of environment |
Implements nav2_core::Smoother.
Definition at line 42 of file constrained_smoother.cpp.
|
overridevirtual |
Method to smooth given path.
| path | In-out path to be optimized |
| max_time | Maximum duration smoothing should take |
Implements nav2_core::Smoother.
Definition at line 91 of file constrained_smoother.cpp.