23 #include "nav2_constrained_smoother/constrained_smoother.hpp"
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
26 #include "nav2_core/smoother_exceptions.hpp"
28 #include "pluginlib/class_loader.hpp"
29 #include "pluginlib/class_list_macros.hpp"
31 #include "tf2/utils.h"
33 using nav2_util::declare_parameter_if_not_declared;
34 using nav2_util::geometry_utils::euclidean_distance;
37 namespace nav2_constrained_smoother
40 void ConstrainedSmoother::configure(
41 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
42 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
43 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
44 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
46 auto node = parent.lock();
48 throw std::runtime_error(
"Unable to lock node!");
51 costmap_sub_ = costmap_sub;
54 logger_ = node->get_logger();
56 smoother_ = std::make_unique<nav2_constrained_smoother::Smoother>();
57 optimizer_params_.get(node.get(), name);
58 smoother_params_.get(node.get(), name);
59 smoother_->initialize(optimizer_params_);
62 void ConstrainedSmoother::cleanup()
66 "Cleaning up smoother: %s of type"
67 " nav2_constrained_smoother::ConstrainedSmoother",
68 plugin_name_.c_str());
71 void ConstrainedSmoother::activate()
75 "Activating smoother: %s of type "
76 "nav2_constrained_smoother::ConstrainedSmoother",
77 plugin_name_.c_str());
80 void ConstrainedSmoother::deactivate()
84 "Deactivating smoother: %s of type "
85 "nav2_constrained_smoother::ConstrainedSmoother",
86 plugin_name_.c_str());
89 bool ConstrainedSmoother::smooth(nav_msgs::msg::Path & path,
const rclcpp::Duration & max_time)
91 if (path.poses.size() < 2) {
96 std::vector<Eigen::Vector3d> path_world;
97 path_world.reserve(path.poses.size());
100 Eigen::Vector2d start_dir;
101 Eigen::Vector2d end_dir;
102 for (
size_t i = 0; i < path.poses.size(); i++) {
103 auto & pose = path.poses[i].pose;
104 double angle = tf2::getYaw(pose.orientation);
105 Eigen::Vector2d orientation(cos(angle), sin(angle));
106 if (i == path.poses.size() - 1) {
110 path_world.emplace_back(pose.position.x, pose.position.y, path_world.back()[2]);
111 end_dir = orientation;
113 auto & pos_next = path.poses[i + 1].pose.position;
114 Eigen::Vector2d mvmt(pos_next.x - pose.position.x, pos_next.y - pose.position.y);
117 bool reversing = smoother_params_.reversing_enabled && orientation.dot(mvmt) < 0;
120 path_world.emplace_back(pose.position.x, pose.position.y, reversing ? -1 : 1);
122 start_dir = orientation;
123 }
else if (i == 1 && !smoother_params_.keep_start_orientation) {
126 path_world[0][2] = path_world.back()[2];
131 smoother_params_.max_time = max_time.seconds();
134 auto costmap = costmap_sub_->getCostmap();
135 std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
136 if (!smoother_->smooth(path_world, start_dir, end_dir, costmap.get(), smoother_params_)) {
139 "%s: failed to smooth plan, Ceres could not find a usable solution to optimize.",
140 plugin_name_.c_str());
142 "Failed to smooth plan, Ceres could not find a usable solution");
146 geometry_msgs::msg::PoseStamped pose;
147 pose.header = path.poses.front().header;
149 path.poses.reserve(path_world.size());
150 for (
auto & pw : path_world) {
151 pose.pose.position.x = pw[0];
152 pose.pose.position.y = pw[1];
153 pose.pose.orientation.z = sin(pw[2] / 2);
154 pose.pose.orientation.w = cos(pw[2] / 2);
156 path.poses.push_back(pose);
165 PLUGINLIB_EXPORT_CLASS(
Regulated pure pursuit controller plugin.
smoother interface that acts as a virtual base class for all smoother plugins