23 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_constrained_smoother/constrained_smoother.hpp"
26 #include "nav2_util/node_utils.hpp"
27 #include "nav2_util/geometry_utils.hpp"
28 #include "nav2_core/smoother_exceptions.hpp"
30 #include "pluginlib/class_loader.hpp"
31 #include "pluginlib/class_list_macros.hpp"
33 #include "tf2/utils.hpp"
35 using nav2_util::declare_parameter_if_not_declared;
36 using nav2_util::geometry_utils::euclidean_distance;
39 namespace nav2_constrained_smoother
42 void ConstrainedSmoother::configure(
43 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
44 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
45 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
46 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
48 auto node = parent.lock();
50 throw std::runtime_error(
"Unable to lock node!");
53 costmap_sub_ = costmap_sub;
56 logger_ = node->get_logger();
58 smoother_ = std::make_unique<nav2_constrained_smoother::Smoother>();
59 optimizer_params_.get(node.get(), name);
60 smoother_params_.get(node.get(), name);
61 smoother_->initialize(optimizer_params_);
64 void ConstrainedSmoother::cleanup()
68 "Cleaning up smoother: %s of type"
69 " nav2_constrained_smoother::ConstrainedSmoother",
70 plugin_name_.c_str());
73 void ConstrainedSmoother::activate()
77 "Activating smoother: %s of type "
78 "nav2_constrained_smoother::ConstrainedSmoother",
79 plugin_name_.c_str());
82 void ConstrainedSmoother::deactivate()
86 "Deactivating smoother: %s of type "
87 "nav2_constrained_smoother::ConstrainedSmoother",
88 plugin_name_.c_str());
91 bool ConstrainedSmoother::smooth(nav_msgs::msg::Path & path,
const rclcpp::Duration & max_time)
93 if (path.poses.size() < 2) {
98 std::vector<Eigen::Vector3d> path_world;
99 path_world.reserve(path.poses.size());
102 Eigen::Vector2d start_dir;
103 Eigen::Vector2d end_dir;
104 for (
size_t i = 0; i < path.poses.size(); i++) {
105 auto & pose = path.poses[i].pose;
106 double angle = tf2::getYaw(pose.orientation);
107 Eigen::Vector2d orientation(cos(angle), sin(angle));
108 if (i == path.poses.size() - 1) {
112 path_world.emplace_back(pose.position.x, pose.position.y, path_world.back()[2]);
113 end_dir = orientation;
115 auto & pos_next = path.poses[i + 1].pose.position;
116 Eigen::Vector2d mvmt(pos_next.x - pose.position.x, pos_next.y - pose.position.y);
119 bool reversing = smoother_params_.reversing_enabled && orientation.dot(mvmt) < 0;
122 path_world.emplace_back(pose.position.x, pose.position.y, reversing ? -1 : 1);
124 start_dir = orientation;
125 }
else if (i == 1 && !smoother_params_.keep_start_orientation) {
128 path_world[0][2] = path_world.back()[2];
133 smoother_params_.max_time = max_time.seconds();
136 auto costmap = costmap_sub_->getCostmap();
137 std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
138 if (!smoother_->smooth(path_world, start_dir, end_dir, costmap.get(), smoother_params_)) {
141 "%s: failed to smooth plan, Ceres could not find a usable solution to optimize.",
142 plugin_name_.c_str());
144 "Failed to smooth plan, Ceres could not find a usable solution");
148 geometry_msgs::msg::PoseStamped pose;
149 pose.header = path.poses.front().header;
151 path.poses.reserve(path_world.size());
152 for (
auto & pw : path_world) {
153 pose.pose.position.x = pw[0];
154 pose.pose.position.y = pw[1];
155 pose.pose.orientation.z = sin(pw[2] / 2);
156 pose.pose.orientation.w = cos(pw[2] / 2);
158 path.poses.push_back(pose);
167 PLUGINLIB_EXPORT_CLASS(
Regulated pure pursuit controller plugin.
smoother interface that acts as a virtual base class for all smoother plugins