Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Public Types | |
using | ActionServer = nav2_util::SimpleActionServer< ActionT > |
![]() | |
using | Ptr = std::shared_ptr< Behavior > |
Public Member Functions | |
TimedBehavior () | |
A TimedBehavior constructor. | |
virtual ResultStatus | onRun (const std::shared_ptr< const typename ActionT::Goal > command)=0 |
virtual ResultStatus | onCycleUpdate ()=0 |
virtual void | onConfigure () |
virtual void | onCleanup () |
virtual void | onActionCompletion (std::shared_ptr< typename ActionT::Result >) |
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) 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 deactivate Behavior and any threads involved in execution. | |
![]() | |
virtual | ~Behavior () |
Virtual destructor. | |
virtual CostmapInfoType | getResourceInfo ()=0 |
Method to determine the required costmap info. More... | |
Protected Member Functions | |
void | execute () |
void | stopRobot () |
Protected Attributes | |
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
std::string | behavior_name_ |
std::unique_ptr< nav2_util::TwistPublisher > | vel_pub_ |
std::shared_ptr< ActionServer > | action_server_ |
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | local_collision_checker_ |
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | global_collision_checker_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
double | cycle_frequency_ |
double | enabled_ |
std::string | local_frame_ |
std::string | global_frame_ |
std::string | robot_base_frame_ |
double | transform_tolerance_ |
rclcpp::Duration | elapsed_time_ {0, 0} |
rclcpp::Clock::SharedPtr | clock_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("nav2_behaviors")} |
Definition at line 66 of file timed_behavior.hpp.
|
inlineoverridevirtual |
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 |
Implements nav2_core::Behavior.
Definition at line 115 of file timed_behavior.hpp.