Nav2 Navigation Stack - humble  humble
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 #include <memory>
19 #include <string>
20 #include <cmath>
21 #include <chrono>
22 #include <ctime>
23 #include <thread>
24 #include <utility>
25 
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
37 
38 namespace nav2_behaviors
39 {
40 
41 enum class Status : int8_t
42 {
43  SUCCEEDED = 1,
44  FAILED = 2,
45  RUNNING = 3,
46 };
47 
48 using namespace std::chrono_literals; //NOLINT
49 
54 template<typename ActionT>
56 {
57 public:
59 
64  : action_server_(nullptr),
65  cycle_frequency_(10.0),
66  enabled_(false),
67  transform_tolerance_(0.0)
68  {
69  }
70 
71  virtual ~TimedBehavior() = default;
72 
73  // Derived classes can override this method to catch the command and perform some checks
74  // before getting into the main loop. The method will only be called
75  // once and should return SUCCEEDED otherwise behavior will return FAILED.
76  virtual Status onRun(const std::shared_ptr<const typename ActionT::Goal> command) = 0;
77 
78 
79  // This is the method derived classes should mainly implement
80  // and will be called cyclically while it returns RUNNING.
81  // Implement the behavior such that it runs some unit of work on each call
82  // and provides a status. The Behavior will finish once SUCCEEDED is returned
83  // It's up to the derived class to define the final commanded velocity.
84  virtual Status onCycleUpdate() = 0;
85 
86  // an opportunity for derived classes to do something on configuration
87  // if they chose
88  virtual void onConfigure()
89  {
90  }
91 
92  // an opportunity for derived classes to do something on cleanup
93  // if they chose
94  virtual void onCleanup()
95  {
96  }
97 
98  // an opportunity for a derived class to do something on action completion
99  virtual void onActionCompletion()
100  {
101  }
102 
103  // configure the server on lifecycle setup
104  void configure(
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
108  {
109  node_ = parent;
110  auto node = node_.lock();
111  logger_ = node->get_logger();
112  clock_ = node->get_clock();
113 
114  RCLCPP_INFO(logger_, "Configuring %s", name.c_str());
115 
116  behavior_name_ = name;
117  tf_ = tf;
118 
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_);
123 
124  action_server_ = std::make_shared<ActionServer>(
125  node, behavior_name_,
126  std::bind(&TimedBehavior::execute, this));
127 
128  collision_checker_ = collision_checker;
129 
130  vel_pub_ = node->template create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);
131 
132  onConfigure();
133  }
134 
135  // Cleanup server on lifecycle transition
136  void cleanup() override
137  {
138  action_server_.reset();
139  vel_pub_.reset();
140  onCleanup();
141  }
142 
143  // Activate server on lifecycle transition
144  void activate() override
145  {
146  RCLCPP_INFO(logger_, "Activating %s", behavior_name_.c_str());
147 
148  vel_pub_->on_activate();
149  action_server_->activate();
150  enabled_ = true;
151  }
152 
153  // Deactivate server on lifecycle transition
154  void deactivate() override
155  {
156  vel_pub_->on_deactivate();
157  action_server_->deactivate();
158  enabled_ = false;
159  }
160 
161 protected:
162  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
163 
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_;
169 
170  double cycle_frequency_;
171  double enabled_;
172  std::string global_frame_;
173  std::string robot_base_frame_;
174  double transform_tolerance_;
175  rclcpp::Duration elasped_time_{0, 0};
176 
177  // Clock
178  rclcpp::Clock::SharedPtr clock_;
179 
180  // Logger
181  rclcpp::Logger logger_{rclcpp::get_logger("nav2_behaviors")};
182 
183  // Main execution callbacks for the action server implementation calling the Behavior's
184  // onRun and cycle functions to execute a specific behavior
185  void execute()
186  {
187  RCLCPP_INFO(logger_, "Running %s", behavior_name_.c_str());
188 
189  if (!enabled_) {
190  RCLCPP_WARN(
191  logger_,
192  "Called while inactive, ignoring request.");
193  return;
194  }
195 
196  if (onRun(action_server_->get_current_goal()) != Status::SUCCEEDED) {
197  RCLCPP_INFO(
198  logger_,
199  "Initial checks failed for %s", behavior_name_.c_str());
200  action_server_->terminate_current();
201  return;
202  }
203 
204  auto start_time = clock_->now();
205 
206  // Initialize the ActionT result
207  auto result = std::make_shared<typename ActionT::Result>();
208 
209  rclcpp::WallRate loop_rate(cycle_frequency_);
210 
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());
215  stopRobot();
216  result->total_elapsed_time = elasped_time_;
217  action_server_->terminate_all(result);
218  onActionCompletion();
219  return;
220  }
221 
222  // TODO(orduno) #868 Enable preempting a Behavior on-the-fly without stopping
223  if (action_server_->is_preempt_requested()) {
224  RCLCPP_ERROR(
225  logger_, "Received a preemption request for %s,"
226  " however feature is currently not implemented. Aborting and stopping.",
227  behavior_name_.c_str());
228  stopRobot();
229  result->total_elapsed_time = clock_->now() - start_time;
230  action_server_->terminate_current(result);
231  onActionCompletion();
232  return;
233  }
234 
235  switch (onCycleUpdate()) {
236  case Status::SUCCEEDED:
237  RCLCPP_INFO(
238  logger_,
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();
243  return;
244 
245  case Status::FAILED:
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();
250  return;
251 
252  case Status::RUNNING:
253 
254  default:
255  loop_rate.sleep();
256  break;
257  }
258  }
259  }
260 
261  // Stop the robot with a commanded velocity
262  void stopRobot()
263  {
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;
268 
269  vel_pub_->publish(std::move(cmd_vel));
270  }
271 };
272 
273 } // namespace nav2_behaviors
274 
275 #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 > collision_checker) override
Abstract interface for behaviors to adhere to with pluginlib.
Definition: behavior.hpp:34
An action server wrapper to make applications simpler using Actions.