An action server behavior for waiting a fixed duration.
More...
#include <nav2_behaviors/include/nav2_behaviors/plugins/wait.hpp>
|
| Wait () |
| A constructor for nav2_behaviors::Wait.
|
|
Status | onRun (const std::shared_ptr< const WaitAction::Goal > command) override |
| Initialization to run behavior. More...
|
|
Status | onCycleUpdate () override |
| Loop function to run behavior. More...
|
|
| TimedBehavior () |
| A TimedBehavior constructor.
|
|
virtual Status | onRun (const std::shared_ptr< const typename ActionT::Goal > command)=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.
|
|
virtual | ~Behavior () |
| Virtual destructor.
|
|
|
rclcpp::Time | wait_end_ |
|
WaitAction::Feedback::SharedPtr | feedback_ |
|
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
|
std::string | behavior_name_ |
|
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr | vel_pub_ |
|
std::shared_ptr< ActionServer > | action_server_ |
|
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | collision_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_ |
|
rclcpp::Clock::SharedPtr | clock_ |
|
rclcpp::Logger | logger_ |
|
An action server behavior for waiting a fixed duration.
Definition at line 33 of file wait.hpp.
◆ onCycleUpdate()
Status nav2_behaviors::Wait::onCycleUpdate |
( |
| ) |
|
|
overridevirtual |
◆ onRun()
Status nav2_behaviors::Wait::onRun |
( |
const std::shared_ptr< const WaitAction::Goal > |
command | ) |
|
|
override |
Initialization to run behavior.
- Parameters
-
- Returns
- Status of behavior
Definition at line 31 of file wait.cpp.
The documentation for this class was generated from the following files:
- nav2_behaviors/include/nav2_behaviors/plugins/wait.hpp
- nav2_behaviors/plugins/wait.cpp