Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_core::Behavior Class Referenceabstract

Abstract interface for behaviors to adhere to with pluginlib. More...

#include <nav2_core/include/nav2_core/behavior.hpp>

Inheritance diagram for nav2_core::Behavior:
Inheritance graph
[legend]

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...
 

Detailed Description

Abstract interface for behaviors to adhere to with pluginlib.

Definition at line 41 of file behavior.hpp.

Member Function Documentation

◆ configure()

virtual void nav2_core::Behavior::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 
)
pure virtual

◆ getResourceInfo()

virtual CostmapInfoType nav2_core::Behavior::getResourceInfo ( )
pure virtual

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