Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Abstract interface for behaviors to adhere to with pluginlib. More...
#include <nav2_core/include/nav2_core/behavior.hpp>
Public Types | |
using | Ptr = std::shared_ptr< Behavior > |
Public Member Functions | |
virtual | ~Behavior () |
Virtual destructor. | |
virtual void | configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > local_collision_checker, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > global_collision_checker)=0 |
virtual void | cleanup ()=0 |
Method to cleanup resources used on shutdown. | |
virtual void | activate ()=0 |
Method to active Behavior and any threads involved in execution. | |
virtual void | deactivate ()=0 |
Method to deactive Behavior and any threads involved in execution. | |
virtual CostmapInfoType | getResourceInfo ()=0 |
Method to determine the required costmap info. More... | |
Abstract interface for behaviors to adhere to with pluginlib.
Definition at line 41 of file behavior.hpp.
|
pure virtual |
parent | pointer to user's node |
name | The name of this planner |
tf | A pointer to a TF buffer |
costmap_ros | A pointer to the costmap |
Implemented in nav2_behaviors::TimedBehavior< ActionT >, nav2_behaviors::TimedBehavior< AssistedTeleopAction >, nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >, nav2_behaviors::TimedBehavior< SpinAction >, and nav2_behaviors::TimedBehavior< WaitAction >.
|
pure virtual |
Method to determine the required costmap info.
Implemented in nav2_behaviors::Wait, nav2_behaviors::Spin, nav2_behaviors::DriveOnHeading< ActionT >, nav2_behaviors::DriveOnHeading< nav2_msgs::action::BackUp >, and nav2_behaviors::AssistedTeleop.