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"
28 using namespace std::chrono_literals;
30 namespace nav2_smoother
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"}
39 RCLCPP_INFO(get_logger(),
"Creating smoother server");
42 "costmap_topic", rclcpp::ParameterValue(
44 "global_costmap/costmap_raw")));
47 rclcpp::ParameterValue(
48 std::string(
"global_costmap/published_footprint")));
51 rclcpp::ParameterValue(std::string(
"base_link")));
52 declare_parameter(
"transform_tolerance", rclcpp::ParameterValue(0.1));
53 declare_parameter(
"smoother_plugins", default_ids_);
64 RCLCPP_INFO(get_logger(),
"Configuring smoother server");
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]));
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);
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>(
91 footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
92 shared_from_this(), footprint_topic, *tf_, robot_base_frame, transform_tolerance);
95 std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
96 *costmap_sub_, *footprint_sub_, this->get_name());
100 return nav2::CallbackReturn::FAILURE;
104 plan_publisher_ = create_publisher<nav_msgs::msg::Path>(
"plan_smoothed");
107 action_server_ = create_action_server<Action>(
111 std::chrono::milliseconds(500),
114 return nav2::CallbackReturn::SUCCESS;
121 smoother_types_.resize(smoother_ids_.size());
123 for (
size_t i = 0; i != smoother_ids_.size(); i++) {
126 nav2::get_plugin_type_param(node, smoother_ids_[i]);
127 nav2_core::Smoother::Ptr smoother =
128 lp_loader_.createUniqueInstance(smoother_types_[i]);
130 get_logger(),
"Created smoother : %s of type %s",
131 smoother_ids_[i].c_str(), smoother_types_[i].c_str());
133 node, smoother_ids_[i], tf_, costmap_sub_,
135 smoothers_.insert({smoother_ids_[i], smoother});
136 }
catch (
const std::exception & ex) {
138 get_logger(),
"Failed to create smoother. Exception: %s",
144 for (
size_t i = 0; i != smoother_ids_.size(); i++) {
145 smoother_ids_concat_ += smoother_ids_[i] + std::string(
" ");
149 get_logger(),
"Smoother Server has %s smoothers available.",
150 smoother_ids_concat_.c_str());
158 RCLCPP_INFO(get_logger(),
"Activating");
160 plan_publisher_->on_activate();
161 SmootherMap::iterator it;
162 for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
163 it->second->activate();
165 action_server_->activate();
170 return nav2::CallbackReturn::SUCCESS;
176 RCLCPP_INFO(get_logger(),
"Deactivating");
178 action_server_->deactivate();
179 SmootherMap::iterator it;
180 for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
181 it->second->deactivate();
183 plan_publisher_->on_deactivate();
188 return nav2::CallbackReturn::SUCCESS;
194 RCLCPP_INFO(get_logger(),
"Cleaning up");
197 SmootherMap::iterator it;
198 for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
199 it->second->cleanup();
204 action_server_.reset();
205 plan_publisher_.reset();
206 transform_listener_.reset();
208 footprint_sub_.reset();
209 costmap_sub_.reset();
210 collision_checker_.reset();
212 return nav2::CallbackReturn::SUCCESS;
218 RCLCPP_INFO(get_logger(),
"Shutting down");
219 return nav2::CallbackReturn::SUCCESS;
223 const std::string & c_name,
224 std::string & current_smoother)
226 if (smoothers_.find(c_name) == smoothers_.end()) {
227 if (smoothers_.size() == 1 && c_name.empty()) {
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;
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());
244 RCLCPP_DEBUG(get_logger(),
"Selected smoother: %s.", c_name.c_str());
245 current_smoother = c_name;
253 auto start_time = this->now();
255 RCLCPP_INFO(get_logger(),
"Received a path to smooth.");
257 auto result = std::make_shared<Action::Result>();
259 auto goal = action_server_->get_current_goal();
264 std::string c_name = goal->smoother_id;
265 std::string current_smoother;
267 current_smoother_ = current_smoother;
273 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;
283 if (!result->was_completed) {
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());
293 plan_publisher_->publish(result->path);
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) {
302 if (!collision_checker_->isCollisionFree(pose, fetch_data)) {
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)));
318 get_logger(),
"Smoother succeeded (time: %lf), setting result",
319 rclcpp::Duration(result->smoothing_duration).seconds());
321 action_server_->succeeded_current(result);
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);
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);
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);
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);
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);
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);
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);
369 if (path.poses.empty()) {
370 RCLCPP_WARN(get_logger(),
"Requested path to smooth is empty");
374 RCLCPP_DEBUG(get_logger(),
"Requested path to smooth is valid");
380 #include "rclcpp_components/register_node_macro.hpp"
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...