Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_behaviors::TimedBehavior< ActionT > Class Template Referenceabstract
Inheritance diagram for nav2_behaviors::TimedBehavior< ActionT >:
Inheritance graph
[legend]
Collaboration diagram for nav2_behaviors::TimedBehavior< ActionT >:
Collaboration graph
[legend]

Public Types

using ActionServer = nav2_util::SimpleActionServer< ActionT >
 
- Public Types inherited from nav2_core::Behavior
using Ptr = std::shared_ptr< Behavior >
 

Public Member Functions

 TimedBehavior ()
 A TimedBehavior constructor.
 
virtual Status onRun (const std::shared_ptr< const typename ActionT::Goal > command)=0
 
virtual Status onCycleUpdate ()=0
 
virtual void onConfigure ()
 
virtual void onCleanup ()
 
virtual void onActionCompletion ()
 
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 > collision_checker) override
 
void cleanup () override
 Method to cleanup resources used on shutdown.
 
void activate () override
 Method to active Behavior and any threads involved in execution.
 
void deactivate () override
 Method to deactive Behavior and any threads involved in execution.
 
- Public Member Functions inherited from nav2_core::Behavior
virtual ~Behavior ()
 Virtual destructor.
 

Protected Member Functions

void execute ()
 
void stopRobot ()
 

Protected Attributes

rclcpp_lifecycle::LifecycleNode::WeakPtr node_
 
std::string behavior_name_
 
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr vel_pub_
 
std::shared_ptr< ActionServeraction_server_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckercollision_checker_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
double cycle_frequency_
 
double enabled_
 
std::string global_frame_
 
std::string robot_base_frame_
 
double transform_tolerance_
 
rclcpp::Duration elasped_time_ {0, 0}
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_ {rclcpp::get_logger("nav2_behaviors")}
 

Detailed Description

template<typename ActionT>
class nav2_behaviors::TimedBehavior< ActionT >

Definition at line 55 of file timed_behavior.hpp.

Member Function Documentation

◆ configure()

template<typename ActionT >
void nav2_behaviors::TimedBehavior< ActionT >::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 collision_checker 
)
inlineoverridevirtual
Parameters
parentpointer to user's node
nameThe name of this planner
tfA pointer to a TF buffer
costmap_rosA pointer to the costmap

Implements nav2_core::Behavior.

Definition at line 104 of file timed_behavior.hpp.


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