Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_constrained_smoother::ConstrainedSmoother Class Reference

Regulated pure pursuit controller plugin. More...

#include <nav2_constrained_smoother/include/nav2_constrained_smoother/constrained_smoother.hpp>

Inheritance diagram for nav2_constrained_smoother::ConstrainedSmoother:
Inheritance graph
[legend]
Collaboration diagram for nav2_constrained_smoother::ConstrainedSmoother:
Collaboration graph
[legend]

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::CostmapSubscribercostmap_sub_
 
rclcpp::Logger logger_ {rclcpp::get_logger("ConstrainedSmoother")}
 
std::unique_ptr< nav2_constrained_smoother::Smoothersmoother_
 
SmootherParams smoother_params_
 
OptimizerParams optimizer_params_
 

Additional Inherited Members

- Public Types inherited from nav2_core::Smoother
using Ptr = std::shared_ptr< nav2_core::Smoother >
 

Detailed Description

Regulated pure pursuit controller plugin.

Definition at line 38 of file constrained_smoother.hpp.

Member Function Documentation

◆ configure()

void nav2_constrained_smoother::ConstrainedSmoother::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 
)
overridevirtual

Configure smoother parameters and member variables.

Parameters
parentWeakPtr to node
nameName of plugin
tfTF buffer
costmap_rosCostmap2DROS object of environment

Implements nav2_core::Smoother.

Definition at line 42 of file constrained_smoother.cpp.

◆ smooth()

bool nav2_constrained_smoother::ConstrainedSmoother::smooth ( nav_msgs::msg::Path &  path,
const rclcpp::Duration &  max_time 
)
overridevirtual

Method to smooth given path.

Parameters
pathIn-out path to be optimized
max_timeMaximum duration smoothing should take
Returns
Smoothed path

Implements nav2_core::Smoother.

Definition at line 91 of file constrained_smoother.cpp.


The documentation for this class was generated from the following files: