15 #ifndef NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
16 #define NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
28 #include "rclcpp/rclcpp.hpp"
29 #include "tf2_ros/transform_listener.h"
30 #include "tf2_ros/create_timer_ros.h"
31 #include "geometry_msgs/msg/twist.hpp"
32 #include "nav2_util/robot_utils.hpp"
33 #include "nav2_util/twist_publisher.hpp"
34 #include "nav2_util/simple_action_server.hpp"
35 #include "nav2_core/behavior.hpp"
36 #pragma GCC diagnostic push
37 #pragma GCC diagnostic ignored "-Wpedantic"
38 #include "tf2/utils.h"
39 #pragma GCC diagnostic pop
42 namespace nav2_behaviors
45 enum class Status : int8_t
55 uint16_t error_code{0};
58 using namespace std::chrono_literals;
64 template<
typename ActionT>
74 : action_server_(nullptr),
75 cycle_frequency_(10.0),
77 transform_tolerance_(0.0)
86 virtual ResultStatus onRun(
const std::shared_ptr<const typename ActionT::Goal> command) = 0;
98 virtual void onConfigure()
104 virtual void onCleanup()
109 virtual void onActionCompletion(std::shared_ptr<typename ActionT::Result>)
115 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
116 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf,
117 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker,
118 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker)
122 auto node = node_.lock();
123 logger_ = node->get_logger();
124 clock_ = node->get_clock();
126 RCLCPP_INFO(logger_,
"Configuring %s", name.c_str());
128 behavior_name_ = name;
131 node->get_parameter(
"cycle_frequency", cycle_frequency_);
132 node->get_parameter(
"local_frame", local_frame_);
133 node->get_parameter(
"global_frame", global_frame_);
134 node->get_parameter(
"robot_base_frame", robot_base_frame_);
135 node->get_parameter(
"transform_tolerance", transform_tolerance_);
137 if (!node->has_parameter(
"action_server_result_timeout")) {
138 node->declare_parameter(
"action_server_result_timeout", 10.0);
141 double action_server_result_timeout;
142 node->get_parameter(
"action_server_result_timeout", action_server_result_timeout);
143 rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
144 server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
146 action_server_ = std::make_shared<ActionServer>(
147 node, behavior_name_,
148 std::bind(&TimedBehavior::execute,
this),
nullptr, std::chrono::milliseconds(
149 500),
false, server_options);
151 local_collision_checker_ = local_collision_checker;
152 global_collision_checker_ = global_collision_checker;
154 vel_pub_ = std::make_unique<nav2_util::TwistPublisher>(node,
"cmd_vel", 1);
162 action_server_.reset();
170 RCLCPP_INFO(logger_,
"Activating %s", behavior_name_.c_str());
172 vel_pub_->on_activate();
173 action_server_->activate();
180 vel_pub_->on_deactivate();
181 action_server_->deactivate();
186 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
188 std::string behavior_name_;
189 std::unique_ptr<nav2_util::TwistPublisher> vel_pub_;
190 std::shared_ptr<ActionServer> action_server_;
191 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker_;
192 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker_;
193 std::shared_ptr<tf2_ros::Buffer> tf_;
195 double cycle_frequency_;
197 std::string local_frame_;
198 std::string global_frame_;
199 std::string robot_base_frame_;
200 double transform_tolerance_;
201 rclcpp::Duration elasped_time_{0, 0};
204 rclcpp::Clock::SharedPtr clock_;
207 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_behaviors")};
213 RCLCPP_INFO(logger_,
"Running %s", behavior_name_.c_str());
218 "Called while inactive, ignoring request.");
223 auto result = std::make_shared<typename ActionT::Result>();
225 ResultStatus on_run_result = onRun(action_server_->get_current_goal());
226 if (on_run_result.status != Status::SUCCEEDED) {
229 "Initial checks failed for %s", behavior_name_.c_str());
230 result->error_code = on_run_result.error_code;
231 action_server_->terminate_current(result);
235 auto start_time = clock_->now();
236 rclcpp::WallRate loop_rate(cycle_frequency_);
238 while (rclcpp::ok()) {
239 elasped_time_ = clock_->now() - start_time;
241 if (action_server_->is_preempt_requested()) {
243 logger_,
"Received a preemption request for %s,"
244 " however feature is currently not implemented. Aborting and stopping.",
245 behavior_name_.c_str());
247 result->total_elapsed_time = clock_->now() - start_time;
248 onActionCompletion(result);
249 action_server_->terminate_current(result);
253 if (action_server_->is_cancel_requested()) {
254 RCLCPP_INFO(logger_,
"Canceling %s", behavior_name_.c_str());
256 result->total_elapsed_time = elasped_time_;
257 onActionCompletion(result);
258 action_server_->terminate_all(result);
262 ResultStatus on_cycle_update_result = onCycleUpdate();
263 switch (on_cycle_update_result.status) {
264 case Status::SUCCEEDED:
267 "%s completed successfully", behavior_name_.c_str());
268 result->total_elapsed_time = clock_->now() - start_time;
269 onActionCompletion(result);
270 action_server_->succeeded_current(result);
274 RCLCPP_WARN(logger_,
"%s failed", behavior_name_.c_str());
275 result->total_elapsed_time = clock_->now() - start_time;
276 result->error_code = on_cycle_update_result.error_code;
277 onActionCompletion(result);
278 action_server_->terminate_current(result);
281 case Status::RUNNING:
293 auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
294 cmd_vel->header.frame_id = robot_base_frame_;
295 cmd_vel->header.stamp = clock_->now();
296 cmd_vel->twist.linear.x = 0.0;
297 cmd_vel->twist.linear.y = 0.0;
298 cmd_vel->twist.angular.z = 0.0;
300 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 > local_collision_checker, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > global_collision_checker) override
Abstract interface for behaviors to adhere to with pluginlib.
An action server wrapper to make applications simpler using Actions.