15 #ifndef NAV2_CORE__BEHAVIOR_HPP_
16 #define NAV2_CORE__BEHAVIOR_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_util/lifecycle_node.hpp"
23 #include "tf2_ros/buffer.h"
24 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
29 enum class CostmapInfoType
44 using Ptr = std::shared_ptr<Behavior>;
58 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
59 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf,
60 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker,
61 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker) = 0;
Abstract interface for behaviors to adhere to with pluginlib.
virtual void cleanup()=0
Method to cleanup resources used on shutdown.
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 activate()=0
Method to active Behavior and any threads involved in execution.
virtual CostmapInfoType getResourceInfo()=0
Method to determine the required costmap info.
virtual void deactivate()=0
Method to deactive Behavior and any threads involved in execution.