Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
timed_behavior.hpp
1 // Copyright (c) 2018 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
16 #define NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
17 
18 
19 #include <cstdint>
20 #include <memory>
21 #include <string>
22 #include <cmath>
23 #include <chrono>
24 #include <ctime>
25 #include <thread>
26 #include <utility>
27 
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
40 
41 
42 namespace nav2_behaviors
43 {
44 
45 enum class Status : int8_t
46 {
47  SUCCEEDED = 1,
48  FAILED = 2,
49  RUNNING = 3,
50 };
51 
53 {
54  Status status;
55  uint16_t error_code{0};
56 };
57 
58 using namespace std::chrono_literals; //NOLINT
59 
64 template<typename ActionT>
66 {
67 public:
69 
74  : action_server_(nullptr),
75  cycle_frequency_(10.0),
76  enabled_(false),
77  transform_tolerance_(0.0)
78  {
79  }
80 
81  virtual ~TimedBehavior() = default;
82 
83  // Derived classes can override this method to catch the command and perform some checks
84  // before getting into the main loop. The method will only be called
85  // once and should return SUCCEEDED otherwise behavior will return FAILED.
86  virtual ResultStatus onRun(const std::shared_ptr<const typename ActionT::Goal> command) = 0;
87 
88 
89  // This is the method derived classes should mainly implement
90  // and will be called cyclically while it returns RUNNING.
91  // Implement the behavior such that it runs some unit of work on each call
92  // and provides a status. The Behavior will finish once SUCCEEDED is returned
93  // It's up to the derived class to define the final commanded velocity.
94  virtual ResultStatus onCycleUpdate() = 0;
95 
96  // an opportunity for derived classes to do something on configuration
97  // if they chose
98  virtual void onConfigure()
99  {
100  }
101 
102  // an opportunity for derived classes to do something on cleanup
103  // if they chose
104  virtual void onCleanup()
105  {
106  }
107 
108  // an opportunity for a derived class to do something on action completion
109  virtual void onActionCompletion(std::shared_ptr<typename ActionT::Result>/*result*/)
110  {
111  }
112 
113  // configure the server on lifecycle setup
114  void configure(
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)
119  override
120  {
121  node_ = parent;
122  auto node = node_.lock();
123  logger_ = node->get_logger();
124  clock_ = node->get_clock();
125 
126  RCLCPP_INFO(logger_, "Configuring %s", name.c_str());
127 
128  behavior_name_ = name;
129  tf_ = tf;
130 
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_);
136 
137  if (!node->has_parameter("action_server_result_timeout")) {
138  node->declare_parameter("action_server_result_timeout", 10.0);
139  }
140 
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);
145 
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);
150 
151  local_collision_checker_ = local_collision_checker;
152  global_collision_checker_ = global_collision_checker;
153 
154  vel_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel", 1);
155 
156  onConfigure();
157  }
158 
159  // Cleanup server on lifecycle transition
160  void cleanup() override
161  {
162  action_server_.reset();
163  vel_pub_.reset();
164  onCleanup();
165  }
166 
167  // Activate server on lifecycle transition
168  void activate() override
169  {
170  RCLCPP_INFO(logger_, "Activating %s", behavior_name_.c_str());
171 
172  vel_pub_->on_activate();
173  action_server_->activate();
174  enabled_ = true;
175  }
176 
177  // Deactivate server on lifecycle transition
178  void deactivate() override
179  {
180  vel_pub_->on_deactivate();
181  action_server_->deactivate();
182  enabled_ = false;
183  }
184 
185 protected:
186  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
187 
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_;
194 
195  double cycle_frequency_;
196  double enabled_;
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};
202 
203  // Clock
204  rclcpp::Clock::SharedPtr clock_;
205 
206  // Logger
207  rclcpp::Logger logger_{rclcpp::get_logger("nav2_behaviors")};
208 
209  // Main execution callbacks for the action server implementation calling the Behavior's
210  // onRun and cycle functions to execute a specific behavior
211  void execute()
212  {
213  RCLCPP_INFO(logger_, "Running %s", behavior_name_.c_str());
214 
215  if (!enabled_) {
216  RCLCPP_WARN(
217  logger_,
218  "Called while inactive, ignoring request.");
219  return;
220  }
221 
222  // Initialize the ActionT result
223  auto result = std::make_shared<typename ActionT::Result>();
224 
225  ResultStatus on_run_result = onRun(action_server_->get_current_goal());
226  if (on_run_result.status != Status::SUCCEEDED) {
227  RCLCPP_INFO(
228  logger_,
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);
232  return;
233  }
234 
235  auto start_time = clock_->now();
236  rclcpp::WallRate loop_rate(cycle_frequency_);
237 
238  while (rclcpp::ok()) {
239  elasped_time_ = clock_->now() - start_time;
240  // TODO(orduno) #868 Enable preempting a Behavior on-the-fly without stopping
241  if (action_server_->is_preempt_requested()) {
242  RCLCPP_ERROR(
243  logger_, "Received a preemption request for %s,"
244  " however feature is currently not implemented. Aborting and stopping.",
245  behavior_name_.c_str());
246  stopRobot();
247  result->total_elapsed_time = clock_->now() - start_time;
248  onActionCompletion(result);
249  action_server_->terminate_current(result);
250  return;
251  }
252 
253  if (action_server_->is_cancel_requested()) {
254  RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
255  stopRobot();
256  result->total_elapsed_time = elasped_time_;
257  onActionCompletion(result);
258  action_server_->terminate_all(result);
259  return;
260  }
261 
262  ResultStatus on_cycle_update_result = onCycleUpdate();
263  switch (on_cycle_update_result.status) {
264  case Status::SUCCEEDED:
265  RCLCPP_INFO(
266  logger_,
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);
271  return;
272 
273  case Status::FAILED:
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);
279  return;
280 
281  case Status::RUNNING:
282 
283  default:
284  loop_rate.sleep();
285  break;
286  }
287  }
288  }
289 
290  // Stop the robot with a commanded velocity
291  void stopRobot()
292  {
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;
299 
300  vel_pub_->publish(std::move(cmd_vel));
301  }
302 };
303 
304 } // namespace nav2_behaviors
305 
306 #endif // NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
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.
Definition: behavior.hpp:42
An action server wrapper to make applications simpler using Actions.