15 #ifndef NAV2_BEHAVIORS__PLUGINS__WAIT_HPP_
16 #define NAV2_BEHAVIORS__PLUGINS__WAIT_HPP_
22 #include "nav2_behaviors/timed_behavior.hpp"
23 #include "nav2_msgs/action/wait.hpp"
25 namespace nav2_behaviors
27 using WaitAction = nav2_msgs::action::Wait;
47 Status
onRun(
const std::shared_ptr<const WaitAction::Goal> command)
override;
56 rclcpp::Time wait_end_;
57 WaitAction::Feedback::SharedPtr feedback_;
An action server behavior for waiting a fixed duration.
Status onRun(const std::shared_ptr< const WaitAction::Goal > command) override
Initialization to run behavior.
Wait()
A constructor for nav2_behaviors::Wait.
Status onCycleUpdate() override
Loop function to run behavior.