Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
nav2_smoother.cpp
1 // Copyright (c) 2019 RoboTech Vision
2 // Copyright (c) 2019 Intel Corporation
3 // Copyright (c) 2022 Samsung Research America
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #include <chrono>
18 #include <memory>
19 #include <string>
20 #include <utility>
21 #include <vector>
22 
23 #include "nav2_core/smoother_exceptions.hpp"
24 #include "nav2_smoother/nav2_smoother.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav_2d_utils/conversions.hpp"
27 #include "nav_2d_utils/tf_help.hpp"
28 #include "tf2_ros/create_timer_ros.h"
29 
30 using namespace std::chrono_literals;
31 
32 namespace nav2_smoother
33 {
34 
35 SmootherServer::SmootherServer(const rclcpp::NodeOptions & options)
36 : LifecycleNode("smoother_server", "", options),
37  lp_loader_("nav2_core", "nav2_core::Smoother"),
38  default_ids_{"simple_smoother"},
39  default_types_{"nav2_smoother::SimpleSmoother"}
40 {
41  RCLCPP_INFO(get_logger(), "Creating smoother server");
42 
43  declare_parameter(
44  "costmap_topic", rclcpp::ParameterValue(
45  std::string(
46  "global_costmap/costmap_raw")));
47  declare_parameter(
48  "footprint_topic",
49  rclcpp::ParameterValue(
50  std::string("global_costmap/published_footprint")));
51  declare_parameter(
52  "robot_base_frame",
53  rclcpp::ParameterValue(std::string("base_link")));
54  declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1));
55  declare_parameter("smoother_plugins", default_ids_);
56 }
57 
59 {
60  smoothers_.clear();
61 }
62 
63 nav2_util::CallbackReturn
64 SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
65 {
66  RCLCPP_INFO(get_logger(), "Configuring smoother server");
67 
68  auto node = shared_from_this();
69 
70  get_parameter("smoother_plugins", smoother_ids_);
71  if (smoother_ids_ == default_ids_) {
72  for (size_t i = 0; i < default_ids_.size(); ++i) {
73  nav2_util::declare_parameter_if_not_declared(
74  node, default_ids_[i] + ".plugin",
75  rclcpp::ParameterValue(default_types_[i]));
76  }
77  }
78 
79  tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
80  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
81  get_node_base_interface(), get_node_timers_interface());
82  tf_->setCreateTimerInterface(timer_interface);
83  transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
84 
85  std::string costmap_topic, footprint_topic, robot_base_frame;
86  double transform_tolerance = 0.1;
87  this->get_parameter("costmap_topic", costmap_topic);
88  this->get_parameter("footprint_topic", footprint_topic);
89  this->get_parameter("transform_tolerance", transform_tolerance);
90  this->get_parameter("robot_base_frame", robot_base_frame);
91  costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
92  shared_from_this(), costmap_topic);
93  footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
94  shared_from_this(), footprint_topic, *tf_, robot_base_frame, transform_tolerance);
95 
96  collision_checker_ =
97  std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
98  *costmap_sub_, *footprint_sub_, this->get_name());
99 
100  if (!loadSmootherPlugins()) {
101  on_cleanup(state);
102  return nav2_util::CallbackReturn::FAILURE;
103  }
104 
105  // Initialize pubs & subs
106  plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan_smoothed", 1);
107 
108  // Create the action server that we implement with our smoothPath method
109  action_server_ = std::make_unique<ActionServer>(
111  "smooth_path",
112  std::bind(&SmootherServer::smoothPlan, this),
113  nullptr,
114  std::chrono::milliseconds(500),
115  true);
116 
117  return nav2_util::CallbackReturn::SUCCESS;
118 }
119 
121 {
122  auto node = shared_from_this();
123 
124  smoother_types_.resize(smoother_ids_.size());
125 
126  for (size_t i = 0; i != smoother_ids_.size(); i++) {
127  try {
128  smoother_types_[i] =
129  nav2_util::get_plugin_type_param(node, smoother_ids_[i]);
130  nav2_core::Smoother::Ptr smoother =
131  lp_loader_.createUniqueInstance(smoother_types_[i]);
132  RCLCPP_INFO(
133  get_logger(), "Created smoother : %s of type %s",
134  smoother_ids_[i].c_str(), smoother_types_[i].c_str());
135  smoother->configure(
136  node, smoother_ids_[i], tf_, costmap_sub_,
137  footprint_sub_);
138  smoothers_.insert({smoother_ids_[i], smoother});
139  } catch (const std::exception & ex) {
140  RCLCPP_FATAL(
141  get_logger(), "Failed to create smoother. Exception: %s",
142  ex.what());
143  return false;
144  }
145  }
146 
147  for (size_t i = 0; i != smoother_ids_.size(); i++) {
148  smoother_ids_concat_ += smoother_ids_[i] + std::string(" ");
149  }
150 
151  RCLCPP_INFO(
152  get_logger(), "Smoother Server has %s smoothers available.",
153  smoother_ids_concat_.c_str());
154 
155  return true;
156 }
157 
158 nav2_util::CallbackReturn
159 SmootherServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
160 {
161  RCLCPP_INFO(get_logger(), "Activating");
162 
163  plan_publisher_->on_activate();
164  SmootherMap::iterator it;
165  for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
166  it->second->activate();
167  }
168  action_server_->activate();
169 
170  // create bond connection
171  createBond();
172 
173  return nav2_util::CallbackReturn::SUCCESS;
174 }
175 
176 nav2_util::CallbackReturn
177 SmootherServer::on_deactivate(const rclcpp_lifecycle::State &)
178 {
179  RCLCPP_INFO(get_logger(), "Deactivating");
180 
181  action_server_->deactivate();
182  SmootherMap::iterator it;
183  for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
184  it->second->deactivate();
185  }
186  plan_publisher_->on_deactivate();
187 
188  // destroy bond connection
189  destroyBond();
190 
191  return nav2_util::CallbackReturn::SUCCESS;
192 }
193 
194 nav2_util::CallbackReturn
195 SmootherServer::on_cleanup(const rclcpp_lifecycle::State &)
196 {
197  RCLCPP_INFO(get_logger(), "Cleaning up");
198 
199  // Cleanup the helper classes
200  SmootherMap::iterator it;
201  for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
202  it->second->cleanup();
203  }
204  smoothers_.clear();
205 
206  // Release any allocated resources
207  action_server_.reset();
208  plan_publisher_.reset();
209  transform_listener_.reset();
210  tf_.reset();
211  footprint_sub_.reset();
212  costmap_sub_.reset();
213  collision_checker_.reset();
214 
215  return nav2_util::CallbackReturn::SUCCESS;
216 }
217 
218 nav2_util::CallbackReturn
219 SmootherServer::on_shutdown(const rclcpp_lifecycle::State &)
220 {
221  RCLCPP_INFO(get_logger(), "Shutting down");
222  return nav2_util::CallbackReturn::SUCCESS;
223 }
224 
226  const std::string & c_name,
227  std::string & current_smoother)
228 {
229  if (smoothers_.find(c_name) == smoothers_.end()) {
230  if (smoothers_.size() == 1 && c_name.empty()) {
231  RCLCPP_WARN_ONCE(
232  get_logger(),
233  "No smoother was specified in action call."
234  " Server will use only plugin loaded %s. "
235  "This warning will appear once.",
236  smoother_ids_concat_.c_str());
237  current_smoother = smoothers_.begin()->first;
238  } else {
239  RCLCPP_ERROR(
240  get_logger(),
241  "SmoothPath called with smoother name %s, "
242  "which does not exist. Available smoothers are: %s.",
243  c_name.c_str(), smoother_ids_concat_.c_str());
244  return false;
245  }
246  } else {
247  RCLCPP_DEBUG(get_logger(), "Selected smoother: %s.", c_name.c_str());
248  current_smoother = c_name;
249  }
250 
251  return true;
252 }
253 
255 {
256  auto start_time = this->now();
257 
258  RCLCPP_INFO(get_logger(), "Received a path to smooth.");
259 
260  auto result = std::make_shared<Action::Result>();
261  try {
262  auto goal = action_server_->get_current_goal();
263  if (!goal) {
264  return; // if action_server_ is deactivate, goal would be a nullptr
265  }
266 
267  std::string c_name = goal->smoother_id;
268  std::string current_smoother;
269  if (findSmootherId(c_name, current_smoother)) {
270  current_smoother_ = current_smoother;
271  } else {
272  throw nav2_core::InvalidSmoother("Invalid Smoother: " + c_name);
273  }
274 
275  // Perform smoothing
276  result->path = goal->path;
277 
278  if (!validate(result->path)) {
279  throw nav2_core::InvalidPath("Requested path to smooth is invalid");
280  }
281 
282  result->was_completed = smoothers_[current_smoother_]->smooth(
283  result->path, goal->max_smoothing_duration);
284  result->smoothing_duration = this->now() - start_time;
285 
286  if (!result->was_completed) {
287  RCLCPP_INFO(
288  get_logger(),
289  "Smoother %s did not complete smoothing in specified time limit"
290  "(%lf seconds) and was interrupted after %lf seconds",
291  current_smoother_.c_str(),
292  rclcpp::Duration(goal->max_smoothing_duration).seconds(),
293  rclcpp::Duration(result->smoothing_duration).seconds());
294  }
295 
296  plan_publisher_->publish(result->path);
297 
298  // Check for collisions
299  if (goal->check_for_collisions) {
300  geometry_msgs::msg::Pose2D pose2d;
301  bool fetch_data = true;
302  for (const auto & pose : result->path.poses) {
303  pose2d.x = pose.pose.position.x;
304  pose2d.y = pose.pose.position.y;
305  pose2d.theta = tf2::getYaw(pose.pose.orientation);
306 
307  if (!collision_checker_->isCollisionFree(pose2d, fetch_data)) {
308  RCLCPP_ERROR(
309  get_logger(),
310  "Smoothed path leads to a collision at x: %lf, y: %lf, theta: %lf",
311  pose2d.x, pose2d.y, pose2d.theta);
313  "Smoothed Path collided at"
314  "X: " + std::to_string(pose2d.x) +
315  "Y: " + std::to_string(pose2d.y) +
316  "Theta: " + std::to_string(pose2d.theta));
317  }
318  fetch_data = false;
319  }
320  }
321 
322  RCLCPP_DEBUG(
323  get_logger(), "Smoother succeeded (time: %lf), setting result",
324  rclcpp::Duration(result->smoothing_duration).seconds());
325 
326  action_server_->succeeded_current(result);
327  } catch (nav2_core::InvalidSmoother & ex) {
328  result->error_msg = ex.what();
329  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
330  result->error_code = ActionResult::INVALID_SMOOTHER;
331  action_server_->terminate_current(result);
332  return;
333  } catch (nav2_core::SmootherTimedOut & ex) {
334  result->error_msg = ex.what();
335  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
336  result->error_code = ActionResult::TIMEOUT;
337  action_server_->terminate_current(result);
338  return;
339  } catch (nav2_core::SmoothedPathInCollision & ex) {
340  result->error_msg = ex.what();
341  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
342  result->error_code = ActionResult::SMOOTHED_PATH_IN_COLLISION;
343  action_server_->terminate_current(result);
344  return;
345  } catch (nav2_core::FailedToSmoothPath & ex) {
346  result->error_msg = ex.what();
347  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
348  result->error_code = ActionResult::FAILED_TO_SMOOTH_PATH;
349  action_server_->terminate_current(result);
350  return;
351  } catch (nav2_core::InvalidPath & ex) {
352  result->error_msg = ex.what();
353  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
354  result->error_code = ActionResult::INVALID_PATH;
355  action_server_->terminate_current(result);
356  return;
357  } catch (nav2_core::SmootherException & ex) {
358  result->error_msg = ex.what();
359  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
360  result->error_code = ActionResult::UNKNOWN;
361  action_server_->terminate_current(result);
362  return;
363  } catch (std::exception & ex) {
364  result->error_msg = ex.what();
365  RCLCPP_ERROR(this->get_logger(), result->error_msg.c_str());
366  result->error_code = ActionResult::UNKNOWN;
367  action_server_->terminate_current(result);
368  return;
369  }
370 }
371 
372 bool SmootherServer::validate(const nav_msgs::msg::Path & path)
373 {
374  if (path.poses.empty()) {
375  RCLCPP_WARN(get_logger(), "Requested path to smooth is empty");
376  return false;
377  }
378 
379  RCLCPP_DEBUG(get_logger(), "Requested path to smooth is valid");
380  return true;
381 }
382 
383 } // namespace nav2_smoother
384 
385 #include "rclcpp_components/register_node_macro.hpp"
386 
387 // Register the component with class_loader.
388 // This acts as a sort of entry point, allowing the component to be discoverable when its library
389 // is being loaded into a running process.
390 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_smoother::SmootherServer)
This class hosts variety of plugins of different algorithms to smooth or refine a path from the expos...
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
~SmootherServer()
Destructor for nav2_smoother::SmootherServer.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
bool loadSmootherPlugins()
Loads smoother plugins from parameter file.
bool validate(const nav_msgs::msg::Path &path)
Validate that the path contains a meaningful path for smoothing.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures smoother parameters and member variables.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
bool findSmootherId(const std::string &c_name, std::string &name)
Find the valid smoother ID name for the given request.
void smoothPlan()
SmoothPath action server callback. Handles action server updates and spins server until goal is reach...
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.