Nav2 Navigation Stack - kilted  kilted
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.hpp"
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  std::string error_msg;
57 };
58 
59 using namespace std::chrono_literals; //NOLINT
60 
65 template<typename ActionT>
67 {
68 public:
70 
75  : action_server_(nullptr),
76  cycle_frequency_(10.0),
77  enabled_(false),
78  transform_tolerance_(0.0)
79  {
80  }
81 
82  virtual ~TimedBehavior() = default;
83 
84  // Derived classes can override this method to catch the command and perform some checks
85  // before getting into the main loop. The method will only be called
86  // once and should return SUCCEEDED otherwise behavior will return FAILED.
87  virtual ResultStatus onRun(const std::shared_ptr<const typename ActionT::Goal> command) = 0;
88 
89 
90  // This is the method derived classes should mainly implement
91  // and will be called cyclically while it returns RUNNING.
92  // Implement the behavior such that it runs some unit of work on each call
93  // and provides a status. The Behavior will finish once SUCCEEDED is returned
94  // It's up to the derived class to define the final commanded velocity.
95  virtual ResultStatus onCycleUpdate() = 0;
96 
97  // an opportunity for derived classes to do something on configuration
98  // if they chose
99  virtual void onConfigure()
100  {
101  }
102 
103  // an opportunity for derived classes to do something on cleanup
104  // if they chose
105  virtual void onCleanup()
106  {
107  }
108 
109  // an opportunity for a derived class to do something on action completion
110  virtual void onActionCompletion(std::shared_ptr<typename ActionT::Result>/*result*/)
111  {
112  }
113 
114  // configure the server on lifecycle setup
115  void configure(
116  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
117  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf,
118  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker,
119  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker)
120  override
121  {
122  node_ = parent;
123  auto node = node_.lock();
124  logger_ = node->get_logger();
125  clock_ = node->get_clock();
126 
127  RCLCPP_INFO(logger_, "Configuring %s", name.c_str());
128 
129  behavior_name_ = name;
130  tf_ = tf;
131 
132  node->get_parameter("cycle_frequency", cycle_frequency_);
133  node->get_parameter("local_frame", local_frame_);
134  node->get_parameter("global_frame", global_frame_);
135  node->get_parameter("robot_base_frame", robot_base_frame_);
136  node->get_parameter("transform_tolerance", transform_tolerance_);
137 
138  action_server_ = std::make_shared<ActionServer>(
139  node, behavior_name_,
140  std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds(
141  500), false);
142 
143  local_collision_checker_ = local_collision_checker;
144  global_collision_checker_ = global_collision_checker;
145 
146  vel_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel", 1);
147 
148  onConfigure();
149  }
150 
151  // Cleanup server on lifecycle transition
152  void cleanup() override
153  {
154  action_server_.reset();
155  vel_pub_.reset();
156  onCleanup();
157  }
158 
159  // Activate server on lifecycle transition
160  void activate() override
161  {
162  RCLCPP_INFO(logger_, "Activating %s", behavior_name_.c_str());
163 
164  vel_pub_->on_activate();
165  action_server_->activate();
166  enabled_ = true;
167  }
168 
169  // Deactivate server on lifecycle transition
170  void deactivate() override
171  {
172  vel_pub_->on_deactivate();
173  action_server_->deactivate();
174  enabled_ = false;
175  }
176 
177 protected:
178  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
179 
180  std::string behavior_name_;
181  std::unique_ptr<nav2_util::TwistPublisher> vel_pub_;
182  std::shared_ptr<ActionServer> action_server_;
183  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker_;
184  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker_;
185  std::shared_ptr<tf2_ros::Buffer> tf_;
186 
187  double cycle_frequency_;
188  double enabled_;
189  std::string local_frame_;
190  std::string global_frame_;
191  std::string robot_base_frame_;
192  double transform_tolerance_;
193  rclcpp::Duration elapsed_time_{0, 0};
194 
195  // Clock
196  rclcpp::Clock::SharedPtr clock_;
197 
198  // Logger
199  rclcpp::Logger logger_{rclcpp::get_logger("nav2_behaviors")};
200 
201  // Main execution callbacks for the action server implementation calling the Behavior's
202  // onRun and cycle functions to execute a specific behavior
203  void execute()
204  {
205  RCLCPP_INFO(logger_, "Running %s", behavior_name_.c_str());
206 
207  if (!enabled_) {
208  RCLCPP_WARN(
209  logger_,
210  "Called while inactive, ignoring request.");
211  return;
212  }
213 
214  // Initialize the ActionT result
215  auto result = std::make_shared<typename ActionT::Result>();
216 
217  ResultStatus on_run_result = onRun(action_server_->get_current_goal());
218  if (on_run_result.status != Status::SUCCEEDED) {
219  result->error_code = on_run_result.error_code;
220  result->error_msg = on_run_result.error_msg;
221  RCLCPP_INFO(logger_, "Initial checks failed for %s - %s", behavior_name_.c_str(),
222  on_run_result.error_msg.c_str());
223  action_server_->terminate_current(result);
224  return;
225  }
226 
227  auto start_time = clock_->now();
228  rclcpp::WallRate loop_rate(cycle_frequency_);
229 
230  while (rclcpp::ok()) {
231  elapsed_time_ = clock_->now() - start_time;
232  // TODO(orduno) #868 Enable preempting a Behavior on-the-fly without stopping
233  if (action_server_->is_preempt_requested()) {
234  RCLCPP_ERROR(
235  logger_, "Received a preemption request for %s,"
236  " however feature is currently not implemented. Aborting and stopping.",
237  behavior_name_.c_str());
238  stopRobot();
239  result->total_elapsed_time = clock_->now() - start_time;
240  onActionCompletion(result);
241  action_server_->terminate_current(result);
242  return;
243  }
244 
245  if (action_server_->is_cancel_requested()) {
246  RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
247  stopRobot();
248  result->total_elapsed_time = elapsed_time_;
249  onActionCompletion(result);
250  action_server_->terminate_all(result);
251  return;
252  }
253 
254  ResultStatus on_cycle_update_result = onCycleUpdate();
255  switch (on_cycle_update_result.status) {
256  case Status::SUCCEEDED:
257  RCLCPP_INFO(
258  logger_,
259  "%s completed successfully", behavior_name_.c_str());
260  result->total_elapsed_time = clock_->now() - start_time;
261  onActionCompletion(result);
262  action_server_->succeeded_current(result);
263  return;
264 
265  case Status::FAILED:
266  result->error_code = on_cycle_update_result.error_code;
267  result->error_msg = behavior_name_ + " failed:" + on_cycle_update_result.error_msg;
268  RCLCPP_WARN(logger_, result->error_msg.c_str());
269  result->total_elapsed_time = clock_->now() - start_time;
270  onActionCompletion(result);
271  action_server_->terminate_current(result);
272  return;
273 
274  case Status::RUNNING:
275 
276  default:
277  loop_rate.sleep();
278  break;
279  }
280  }
281  }
282 
283  // Stop the robot with a commanded velocity
284  void stopRobot()
285  {
286  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
287  cmd_vel->header.frame_id = robot_base_frame_;
288  cmd_vel->header.stamp = clock_->now();
289  cmd_vel->twist.linear.x = 0.0;
290  cmd_vel->twist.linear.y = 0.0;
291  cmd_vel->twist.angular.z = 0.0;
292 
293  vel_pub_->publish(std::move(cmd_vel));
294  }
295 };
296 
297 } // namespace nav2_behaviors
298 
299 #endif // NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_
TimedBehavior()
A TimedBehavior constructor.
void deactivate() override
Method to deactivate 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.