17 #include "nav2_smoother/simple_smoother.hpp"
18 #include "nav2_core/smoother_exceptions.hpp"
20 namespace nav2_smoother
22 using namespace smoother_utils;
23 using namespace nav2_util::geometry_utils;
24 using namespace std::chrono;
25 using nav2_util::declare_parameter_if_not_declared;
27 void SimpleSmoother::configure(
28 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
29 std::string name, std::shared_ptr<tf2_ros::Buffer>,
30 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
31 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
33 costmap_sub_ = costmap_sub;
35 auto node = parent.lock();
36 logger_ = node->get_logger();
38 declare_parameter_if_not_declared(
39 node, name +
".tolerance", rclcpp::ParameterValue(1e-10));
40 declare_parameter_if_not_declared(
41 node, name +
".max_its", rclcpp::ParameterValue(1000));
42 declare_parameter_if_not_declared(
43 node, name +
".w_data", rclcpp::ParameterValue(0.2));
44 declare_parameter_if_not_declared(
45 node, name +
".w_smooth", rclcpp::ParameterValue(0.3));
46 declare_parameter_if_not_declared(
47 node, name +
".do_refinement", rclcpp::ParameterValue(
true));
48 declare_parameter_if_not_declared(
49 node, name +
".refinement_num", rclcpp::ParameterValue(2));
51 node->get_parameter(name +
".tolerance", tolerance_);
52 node->get_parameter(name +
".max_its", max_its_);
53 node->get_parameter(name +
".w_data", data_w_);
54 node->get_parameter(name +
".w_smooth", smooth_w_);
55 node->get_parameter(name +
".do_refinement", do_refinement_);
56 node->get_parameter(name +
".refinement_num", refinement_num_);
60 nav_msgs::msg::Path & path,
61 const rclcpp::Duration & max_time)
63 auto costmap = costmap_sub_->getCostmap();
65 steady_clock::time_point start = steady_clock::now();
66 double time_remaining = max_time.seconds();
68 bool reversing_segment;
69 nav_msgs::msg::Path curr_path_segment;
70 curr_path_segment.header = path.header;
72 std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
74 std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
76 for (
unsigned int i = 0; i != path_segments.size(); i++) {
77 if (path_segments[i].end - path_segments[i].start > 9) {
79 curr_path_segment.poses.clear();
81 path.poses.begin() + path_segments[i].start,
82 path.poses.begin() + path_segments[i].end + 1,
83 std::back_inserter(curr_path_segment.poses));
86 steady_clock::time_point now = steady_clock::now();
87 time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
92 smoothImpl(curr_path_segment, reversing_segment, costmap.get(), time_remaining);
96 curr_path_segment.poses.begin(),
97 curr_path_segment.poses.end(),
98 path.poses.begin() + path_segments[i].start);
106 nav_msgs::msg::Path & path,
107 bool & reversing_segment,
109 const double & max_time)
111 steady_clock::time_point a = steady_clock::now();
112 rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time);
115 double change = tolerance_;
116 const unsigned int & path_size = path.poses.size();
117 double x_i, y_i, y_m1, y_ip1, y_i_org;
120 nav_msgs::msg::Path new_path = path;
121 nav_msgs::msg::Path last_path = path;
123 while (change >= tolerance_) {
128 if (its >= max_its_) {
131 "Number of iterations has exceeded limit of %i.", max_its_);
133 updateApproximatePathOrientations(path, reversing_segment);
138 steady_clock::time_point b = steady_clock::now();
139 rclcpp::Duration timespan(duration_cast<duration<double>>(b - a));
140 if (timespan > max_dur) {
143 "Smoothing time exceeded allowed duration of %0.2f.", max_time);
145 updateApproximatePathOrientations(path, reversing_segment);
149 for (
unsigned int i = 1; i != path_size - 1; i++) {
150 for (
unsigned int j = 0; j != 2; j++) {
151 x_i = getFieldByDim(path.poses[i], j);
152 y_i = getFieldByDim(new_path.poses[i], j);
153 y_m1 = getFieldByDim(new_path.poses[i - 1], j);
154 y_ip1 = getFieldByDim(new_path.poses[i + 1], j);
158 y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i));
159 setFieldByDim(new_path.poses[i], j, y_i);
160 change += abs(y_i - y_i_org);
167 getFieldByDim(new_path.poses[i], 0),
168 getFieldByDim(new_path.poses[i], 1),
170 cost =
static_cast<float>(costmap->
getCost(mx, my));
173 if (cost > nav2_costmap_2d::MAX_NON_OBSTACLE && cost != nav2_costmap_2d::NO_INFORMATION) {
175 rclcpp::get_logger(
"SmacPlannerSmoother"),
176 "Smoothing process resulted in an infeasible collision. "
177 "Returning the last path before the infeasibility was introduced.");
179 updateApproximatePathOrientations(path, reversing_segment);
184 last_path = new_path;
189 if (do_refinement_ && refinement_ctr_ < refinement_num_) {
191 smoothImpl(new_path, reversing_segment, costmap, max_time);
194 updateApproximatePathOrientations(new_path, reversing_segment);
199 const geometry_msgs::msg::PoseStamped & msg,
const unsigned int & dim)
202 return msg.pose.position.x;
203 }
else if (dim == 1) {
204 return msg.pose.position.y;
206 return msg.pose.position.z;
211 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
212 const double & value)
215 msg.pose.position.x = value;
216 }
else if (dim == 1) {
217 msg.pose.position.y = value;
219 msg.pose.position.z = value;
225 #include "pluginlib/class_list_macros.hpp"
smoother interface that acts as a virtual base class for all smoother plugins
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
A path smoother implementation.
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
void smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.