Nav2 Navigation Stack - humble  humble
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 <limits>
19 #include <memory>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
24 #include "nav2_core/exceptions.hpp"
25 #include "nav2_smoother/nav2_smoother.hpp"
26 #include "nav2_util/geometry_utils.hpp"
27 #include "nav2_util/node_utils.hpp"
28 #include "nav_2d_utils/conversions.hpp"
29 #include "nav_2d_utils/tf_help.hpp"
30 #include "tf2_ros/create_timer_ros.h"
31 
32 using namespace std::chrono_literals;
33 
34 namespace nav2_smoother
35 {
36 
37 SmootherServer::SmootherServer(const rclcpp::NodeOptions & options)
38 : LifecycleNode("smoother_server", "", options),
39  lp_loader_("nav2_core", "nav2_core::Smoother"),
40  default_ids_{"simple_smoother"},
41  default_types_{"nav2_smoother::SimpleSmoother"}
42 {
43  RCLCPP_INFO(get_logger(), "Creating smoother server");
44 
45  declare_parameter(
46  "costmap_topic", rclcpp::ParameterValue(
47  std::string(
48  "global_costmap/costmap_raw")));
49  declare_parameter(
50  "footprint_topic",
51  rclcpp::ParameterValue(
52  std::string("global_costmap/published_footprint")));
53  declare_parameter(
54  "robot_base_frame",
55  rclcpp::ParameterValue(std::string("base_link")));
56  declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1));
57  declare_parameter("smoother_plugins", default_ids_);
58 }
59 
61 {
62  smoothers_.clear();
63 }
64 
65 nav2_util::CallbackReturn
66 SmootherServer::on_configure(const rclcpp_lifecycle::State &)
67 {
68  RCLCPP_INFO(get_logger(), "Configuring smoother server");
69 
70  auto node = shared_from_this();
71 
72  get_parameter("smoother_plugins", smoother_ids_);
73  if (smoother_ids_ == default_ids_) {
74  for (size_t i = 0; i < default_ids_.size(); ++i) {
75  nav2_util::declare_parameter_if_not_declared(
76  node, default_ids_[i] + ".plugin",
77  rclcpp::ParameterValue(default_types_[i]));
78  }
79  }
80 
81  tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
82  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
83  get_node_base_interface(), get_node_timers_interface());
84  tf_->setCreateTimerInterface(timer_interface);
85  transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
86 
87  std::string costmap_topic, footprint_topic, robot_base_frame;
88  double transform_tolerance;
89  this->get_parameter("costmap_topic", costmap_topic);
90  this->get_parameter("footprint_topic", footprint_topic);
91  this->get_parameter("transform_tolerance", transform_tolerance);
92  this->get_parameter("robot_base_frame", robot_base_frame);
93  costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
94  shared_from_this(), costmap_topic);
95  footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
96  shared_from_this(), footprint_topic, *tf_, robot_base_frame, transform_tolerance);
97 
98  collision_checker_ =
99  std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
100  *costmap_sub_, *footprint_sub_, this->get_name());
101 
102  if (!loadSmootherPlugins()) {
103  return nav2_util::CallbackReturn::FAILURE;
104  }
105 
106  // Initialize pubs & subs
107  plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan_smoothed", 1);
108 
109  // Create the action server that we implement with our smoothPath method
110  action_server_ = std::make_unique<ActionServer>(
112  "smooth_path",
113  std::bind(&SmootherServer::smoothPlan, this),
114  nullptr,
115  std::chrono::milliseconds(500),
116  true);
117 
118  return nav2_util::CallbackReturn::SUCCESS;
119 }
120 
122 {
123  auto node = shared_from_this();
124 
125  smoother_types_.resize(smoother_ids_.size());
126 
127  for (size_t i = 0; i != smoother_ids_.size(); i++) {
128  try {
129  smoother_types_[i] =
130  nav2_util::get_plugin_type_param(node, smoother_ids_[i]);
131  nav2_core::Smoother::Ptr smoother =
132  lp_loader_.createUniqueInstance(smoother_types_[i]);
133  RCLCPP_INFO(
134  get_logger(), "Created smoother : %s of type %s",
135  smoother_ids_[i].c_str(), smoother_types_[i].c_str());
136  smoother->configure(
137  node, smoother_ids_[i], tf_, costmap_sub_,
138  footprint_sub_);
139  smoothers_.insert({smoother_ids_[i], smoother});
140  } catch (const pluginlib::PluginlibException & ex) {
141  RCLCPP_FATAL(
142  get_logger(), "Failed to create smoother. Exception: %s",
143  ex.what());
144  return false;
145  }
146  }
147 
148  for (size_t i = 0; i != smoother_ids_.size(); i++) {
149  smoother_ids_concat_ += smoother_ids_[i] + std::string(" ");
150  }
151 
152  RCLCPP_INFO(
153  get_logger(), "Smoother Server has %s smoothers available.",
154  smoother_ids_concat_.c_str());
155 
156  return true;
157 }
158 
159 nav2_util::CallbackReturn
160 SmootherServer::on_activate(const rclcpp_lifecycle::State &)
161 {
162  RCLCPP_INFO(get_logger(), "Activating");
163 
164  plan_publisher_->on_activate();
165  SmootherMap::iterator it;
166  for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
167  it->second->activate();
168  }
169  action_server_->activate();
170 
171  // create bond connection
172  createBond();
173 
174  return nav2_util::CallbackReturn::SUCCESS;
175 }
176 
177 nav2_util::CallbackReturn
178 SmootherServer::on_deactivate(const rclcpp_lifecycle::State &)
179 {
180  RCLCPP_INFO(get_logger(), "Deactivating");
181 
182  action_server_->deactivate();
183  SmootherMap::iterator it;
184  for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
185  it->second->deactivate();
186  }
187  plan_publisher_->on_deactivate();
188 
189  // destroy bond connection
190  destroyBond();
191 
192  return nav2_util::CallbackReturn::SUCCESS;
193 }
194 
195 nav2_util::CallbackReturn
196 SmootherServer::on_cleanup(const rclcpp_lifecycle::State &)
197 {
198  RCLCPP_INFO(get_logger(), "Cleaning up");
199 
200  // Cleanup the helper classes
201  SmootherMap::iterator it;
202  for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
203  it->second->cleanup();
204  }
205  smoothers_.clear();
206 
207  // Release any allocated resources
208  action_server_.reset();
209  plan_publisher_.reset();
210  transform_listener_.reset();
211  tf_.reset();
212  footprint_sub_.reset();
213  costmap_sub_.reset();
214  collision_checker_.reset();
215 
216  return nav2_util::CallbackReturn::SUCCESS;
217 }
218 
219 nav2_util::CallbackReturn
220 SmootherServer::on_shutdown(const rclcpp_lifecycle::State &)
221 {
222  RCLCPP_INFO(get_logger(), "Shutting down");
223  return nav2_util::CallbackReturn::SUCCESS;
224 }
225 
227  const std::string & c_name,
228  std::string & current_smoother)
229 {
230  if (smoothers_.find(c_name) == smoothers_.end()) {
231  if (smoothers_.size() == 1 && c_name.empty()) {
232  RCLCPP_WARN_ONCE(
233  get_logger(),
234  "No smoother was specified in action call."
235  " Server will use only plugin loaded %s. "
236  "This warning will appear once.",
237  smoother_ids_concat_.c_str());
238  current_smoother = smoothers_.begin()->first;
239  } else {
240  RCLCPP_ERROR(
241  get_logger(),
242  "SmoothPath called with smoother name %s, "
243  "which does not exist. Available smoothers are: %s.",
244  c_name.c_str(), smoother_ids_concat_.c_str());
245  return false;
246  }
247  } else {
248  RCLCPP_DEBUG(get_logger(), "Selected smoother: %s.", c_name.c_str());
249  current_smoother = c_name;
250  }
251 
252  return true;
253 }
254 
256 {
257  auto start_time = this->now();
258 
259  RCLCPP_INFO(get_logger(), "Received a path to smooth.");
260 
261  auto result = std::make_shared<Action::Result>();
262  try {
263  auto goal = action_server_->get_current_goal();
264  if (!goal) {
265  return; // if action_server_ is inactivate, goal would be a nullptr
266  }
267 
268  std::string c_name = goal->smoother_id;
269  std::string current_smoother;
270  if (findSmootherId(c_name, current_smoother)) {
271  current_smoother_ = current_smoother;
272  } else {
273  action_server_->terminate_current();
274  return;
275  }
276 
277  // Perform smoothing
278  result->path = goal->path;
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  plan_publisher_->publish(result->path);
293 
294  // Check for collisions
295  if (goal->check_for_collisions) {
296  geometry_msgs::msg::Pose2D pose2d;
297  bool fetch_data = true;
298  for (const auto & pose : result->path.poses) {
299  pose2d.x = pose.pose.position.x;
300  pose2d.y = pose.pose.position.y;
301  pose2d.theta = tf2::getYaw(pose.pose.orientation);
302 
303  if (!collision_checker_->isCollisionFree(pose2d, fetch_data)) {
304  RCLCPP_ERROR(
305  get_logger(),
306  "Smoothed path leads to a collision at x: %lf, y: %lf, theta: %lf",
307  pose2d.x, pose2d.y, pose2d.theta);
308  action_server_->terminate_current(result);
309  return;
310  }
311  fetch_data = false;
312  }
313  }
314 
315  RCLCPP_DEBUG(
316  get_logger(), "Smoother succeeded (time: %lf), setting result",
317  rclcpp::Duration(result->smoothing_duration).seconds());
318 
319  action_server_->succeeded_current(result);
320  } catch (nav2_core::PlannerException & e) {
321  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
322  action_server_->terminate_current();
323  return;
324  } catch (std::exception & ex) {
325  RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
326  action_server_->terminate_current(result);
327  return;
328  }
329 }
330 
331 } // namespace nav2_smoother
332 
333 #include "rclcpp_components/register_node_macro.hpp"
334 
335 // Register the component with class_loader.
336 // This acts as a sort of entry point, allowing the component to be discoverable when its library
337 // is being loaded into a running process.
338 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.
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.