15 #ifndef NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
16 #define NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
26 #include "rclcpp/rclcpp.hpp"
27 #include "tf2_ros/transform_listener.h"
28 #include "tf2_ros/create_timer_ros.h"
29 #include "geometry_msgs/msg/twist.hpp"
30 #include "nav2_util/simple_action_server.hpp"
31 #include "nav2_util/robot_utils.hpp"
32 #include "nav2_core/behavior.hpp"
33 #pragma GCC diagnostic push
34 #pragma GCC diagnostic ignored "-Wpedantic"
35 #include "tf2/utils.h"
36 #pragma GCC diagnostic pop
38 namespace nav2_behaviors
41 enum class Status : int8_t
48 using namespace std::chrono_literals;
54 template<
typename ActionT>
64 : action_server_(nullptr),
65 cycle_frequency_(10.0),
67 transform_tolerance_(0.0)
76 virtual Status onRun(
const std::shared_ptr<const typename ActionT::Goal> command) = 0;
84 virtual Status onCycleUpdate() = 0;
88 virtual void onConfigure()
94 virtual void onCleanup()
99 virtual void onActionCompletion()
105 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
106 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf,
107 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker)
override
110 auto node = node_.lock();
111 logger_ = node->get_logger();
112 clock_ = node->get_clock();
114 RCLCPP_INFO(logger_,
"Configuring %s", name.c_str());
116 behavior_name_ = name;
119 node->get_parameter(
"cycle_frequency", cycle_frequency_);
120 node->get_parameter(
"global_frame", global_frame_);
121 node->get_parameter(
"robot_base_frame", robot_base_frame_);
122 node->get_parameter(
"transform_tolerance", transform_tolerance_);
124 action_server_ = std::make_shared<ActionServer>(
125 node, behavior_name_,
126 std::bind(&TimedBehavior::execute,
this));
128 collision_checker_ = collision_checker;
130 vel_pub_ = node->template create_publisher<geometry_msgs::msg::Twist>(
"cmd_vel", 1);
138 action_server_.reset();
146 RCLCPP_INFO(logger_,
"Activating %s", behavior_name_.c_str());
148 vel_pub_->on_activate();
149 action_server_->activate();
156 vel_pub_->on_deactivate();
157 action_server_->deactivate();
162 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
164 std::string behavior_name_;
165 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr vel_pub_;
166 std::shared_ptr<ActionServer> action_server_;
167 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
168 std::shared_ptr<tf2_ros::Buffer> tf_;
170 double cycle_frequency_;
172 std::string global_frame_;
173 std::string robot_base_frame_;
174 double transform_tolerance_;
175 rclcpp::Duration elasped_time_{0, 0};
178 rclcpp::Clock::SharedPtr clock_;
181 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_behaviors")};
187 RCLCPP_INFO(logger_,
"Running %s", behavior_name_.c_str());
192 "Called while inactive, ignoring request.");
196 if (onRun(action_server_->get_current_goal()) != Status::SUCCEEDED) {
199 "Initial checks failed for %s", behavior_name_.c_str());
200 action_server_->terminate_current();
204 auto start_time = clock_->now();
207 auto result = std::make_shared<typename ActionT::Result>();
209 rclcpp::WallRate loop_rate(cycle_frequency_);
211 while (rclcpp::ok()) {
212 elasped_time_ = clock_->now() - start_time;
213 if (action_server_->is_cancel_requested()) {
214 RCLCPP_INFO(logger_,
"Canceling %s", behavior_name_.c_str());
216 result->total_elapsed_time = elasped_time_;
217 action_server_->terminate_all(result);
218 onActionCompletion();
223 if (action_server_->is_preempt_requested()) {
225 logger_,
"Received a preemption request for %s,"
226 " however feature is currently not implemented. Aborting and stopping.",
227 behavior_name_.c_str());
229 result->total_elapsed_time = clock_->now() - start_time;
230 action_server_->terminate_current(result);
231 onActionCompletion();
235 switch (onCycleUpdate()) {
236 case Status::SUCCEEDED:
239 "%s completed successfully", behavior_name_.c_str());
240 result->total_elapsed_time = clock_->now() - start_time;
241 action_server_->succeeded_current(result);
242 onActionCompletion();
246 RCLCPP_WARN(logger_,
"%s failed", behavior_name_.c_str());
247 result->total_elapsed_time = clock_->now() - start_time;
248 action_server_->terminate_current(result);
249 onActionCompletion();
252 case Status::RUNNING:
264 auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
265 cmd_vel->linear.x = 0.0;
266 cmd_vel->linear.y = 0.0;
267 cmd_vel->angular.z = 0.0;
269 vel_pub_->publish(std::move(cmd_vel));
TimedBehavior()
A TimedBehavior constructor.
void deactivate() override
Method to deactive Behavior and any threads involved in execution.
void activate() override
Method to active Behavior and any threads involved in execution.
void cleanup() override
Method to cleanup resources used on shutdown.
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
Abstract interface for behaviors to adhere to with pluginlib.
An action server wrapper to make applications simpler using Actions.