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