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"
32 using namespace std::chrono_literals;
34 namespace nav2_smoother
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"}
43 RCLCPP_INFO(get_logger(),
"Creating smoother server");
46 "costmap_topic", rclcpp::ParameterValue(
48 "global_costmap/costmap_raw")));
51 rclcpp::ParameterValue(
52 std::string(
"global_costmap/published_footprint")));
55 rclcpp::ParameterValue(std::string(
"base_link")));
56 declare_parameter(
"transform_tolerance", rclcpp::ParameterValue(0.1));
57 declare_parameter(
"smoother_plugins", default_ids_);
65 nav2_util::CallbackReturn
68 RCLCPP_INFO(get_logger(),
"Configuring smoother server");
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]));
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_);
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>(
95 footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
96 shared_from_this(), footprint_topic, *tf_, robot_base_frame, transform_tolerance);
99 std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
100 *costmap_sub_, *footprint_sub_, this->get_name());
103 return nav2_util::CallbackReturn::FAILURE;
107 plan_publisher_ = create_publisher<nav_msgs::msg::Path>(
"plan_smoothed", 1);
110 action_server_ = std::make_unique<ActionServer>(
115 std::chrono::milliseconds(500),
118 return nav2_util::CallbackReturn::SUCCESS;
125 smoother_types_.resize(smoother_ids_.size());
127 for (
size_t i = 0; i != smoother_ids_.size(); 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]);
134 get_logger(),
"Created smoother : %s of type %s",
135 smoother_ids_[i].c_str(), smoother_types_[i].c_str());
137 node, smoother_ids_[i], tf_, costmap_sub_,
139 smoothers_.insert({smoother_ids_[i], smoother});
140 }
catch (
const pluginlib::PluginlibException & ex) {
142 get_logger(),
"Failed to create smoother. Exception: %s",
148 for (
size_t i = 0; i != smoother_ids_.size(); i++) {
149 smoother_ids_concat_ += smoother_ids_[i] + std::string(
" ");
153 get_logger(),
"Smoother Server has %s smoothers available.",
154 smoother_ids_concat_.c_str());
159 nav2_util::CallbackReturn
162 RCLCPP_INFO(get_logger(),
"Activating");
164 plan_publisher_->on_activate();
165 SmootherMap::iterator it;
166 for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
167 it->second->activate();
169 action_server_->activate();
174 return nav2_util::CallbackReturn::SUCCESS;
177 nav2_util::CallbackReturn
180 RCLCPP_INFO(get_logger(),
"Deactivating");
182 action_server_->deactivate();
183 SmootherMap::iterator it;
184 for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
185 it->second->deactivate();
187 plan_publisher_->on_deactivate();
192 return nav2_util::CallbackReturn::SUCCESS;
195 nav2_util::CallbackReturn
198 RCLCPP_INFO(get_logger(),
"Cleaning up");
201 SmootherMap::iterator it;
202 for (it = smoothers_.begin(); it != smoothers_.end(); ++it) {
203 it->second->cleanup();
208 action_server_.reset();
209 plan_publisher_.reset();
210 transform_listener_.reset();
212 footprint_sub_.reset();
213 costmap_sub_.reset();
214 collision_checker_.reset();
216 return nav2_util::CallbackReturn::SUCCESS;
219 nav2_util::CallbackReturn
222 RCLCPP_INFO(get_logger(),
"Shutting down");
223 return nav2_util::CallbackReturn::SUCCESS;
227 const std::string & c_name,
228 std::string & current_smoother)
230 if (smoothers_.find(c_name) == smoothers_.end()) {
231 if (smoothers_.size() == 1 && c_name.empty()) {
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;
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());
248 RCLCPP_DEBUG(get_logger(),
"Selected smoother: %s.", c_name.c_str());
249 current_smoother = c_name;
257 auto start_time = this->now();
259 RCLCPP_INFO(get_logger(),
"Received a path to smooth.");
261 auto result = std::make_shared<Action::Result>();
263 auto goal = action_server_->get_current_goal();
268 std::string c_name = goal->smoother_id;
269 std::string current_smoother;
271 current_smoother_ = current_smoother;
273 action_server_->terminate_current();
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;
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());
292 plan_publisher_->publish(result->path);
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);
303 if (!collision_checker_->isCollisionFree(pose2d, fetch_data)) {
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);
316 get_logger(),
"Smoother succeeded (time: %lf), setting result",
317 rclcpp::Duration(result->smoothing_duration).seconds());
319 action_server_->succeeded_current(result);
321 RCLCPP_ERROR(this->get_logger(),
"%s", e.what());
322 action_server_->terminate_current();
324 }
catch (std::exception & ex) {
325 RCLCPP_ERROR(this->get_logger(),
"%s", ex.what());
326 action_server_->terminate_current(result);
333 #include "rclcpp_components/register_node_macro.hpp"
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.