17 #include "nav2_smoother/savitzky_golay_smoother.hpp"
19 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 SavitzkyGolaySmoother::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>,
31 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
33 auto node = parent.lock();
34 logger_ = node->get_logger();
36 declare_parameter_if_not_declared(
37 node, name +
".do_refinement", rclcpp::ParameterValue(
true));
38 declare_parameter_if_not_declared(
39 node, name +
".refinement_num", rclcpp::ParameterValue(2));
40 node->get_parameter(name +
".do_refinement", do_refinement_);
41 node->get_parameter(name +
".refinement_num", refinement_num_);
45 nav_msgs::msg::Path & path,
46 const rclcpp::Duration & max_time)
48 steady_clock::time_point start = steady_clock::now();
49 double time_remaining = max_time.seconds();
51 bool success =
true, reversing_segment;
52 nav_msgs::msg::Path curr_path_segment;
53 curr_path_segment.header = path.header;
55 std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
57 for (
unsigned int i = 0; i != path_segments.size(); i++) {
58 if (path_segments[i].end - path_segments[i].start > 9) {
60 curr_path_segment.poses.clear();
62 path.poses.begin() + path_segments[i].start,
63 path.poses.begin() + path_segments[i].end + 1,
64 std::back_inserter(curr_path_segment.poses));
67 steady_clock::time_point now = steady_clock::now();
68 time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
70 if (time_remaining <= 0.0) {
73 "Smoothing time exceeded allowed duration of %0.2f.", max_time.seconds());
78 success = success && smoothImpl(curr_path_segment, reversing_segment);
82 curr_path_segment.poses.begin(),
83 curr_path_segment.poses.end(),
84 path.poses.begin() + path_segments[i].start);
92 nav_msgs::msg::Path & path,
93 bool & reversing_segment)
96 const unsigned int & path_size = path.poses.size();
99 const std::array<double, 7> filter = {
108 auto applyFilter = [&](
const std::vector<geometry_msgs::msg::Point> & data)
109 -> geometry_msgs::msg::Point
111 geometry_msgs::msg::Point val;
112 for (
unsigned int i = 0; i != filter.size(); i++) {
113 val.x += filter[i] * data[i].x;
114 val.y += filter[i] * data[i].y;
119 auto applyFilterOverAxes =
120 [&](std::vector<geometry_msgs::msg::PoseStamped> & plan_pts) ->
void
123 unsigned int idx = 1;
124 plan_pts[idx].pose.position = applyFilter(
126 plan_pts[idx - 1].pose.position,
127 plan_pts[idx - 1].pose.position,
128 plan_pts[idx - 1].pose.position,
129 plan_pts[idx].pose.position,
130 plan_pts[idx + 1].pose.position,
131 plan_pts[idx + 2].pose.position,
132 plan_pts[idx + 3].pose.position});
135 plan_pts[idx].pose.position = applyFilter(
137 plan_pts[idx - 2].pose.position,
138 plan_pts[idx - 2].pose.position,
139 plan_pts[idx - 1].pose.position,
140 plan_pts[idx].pose.position,
141 plan_pts[idx + 1].pose.position,
142 plan_pts[idx + 2].pose.position,
143 plan_pts[idx + 3].pose.position});
146 for (idx = 3; idx < path_size - 4; ++idx) {
147 plan_pts[idx].pose.position = applyFilter(
149 plan_pts[idx - 3].pose.position,
150 plan_pts[idx - 2].pose.position,
151 plan_pts[idx - 1].pose.position,
152 plan_pts[idx].pose.position,
153 plan_pts[idx + 1].pose.position,
154 plan_pts[idx + 2].pose.position,
155 plan_pts[idx + 3].pose.position});
160 plan_pts[idx].pose.position = applyFilter(
162 plan_pts[idx - 3].pose.position,
163 plan_pts[idx - 2].pose.position,
164 plan_pts[idx - 1].pose.position,
165 plan_pts[idx].pose.position,
166 plan_pts[idx + 1].pose.position,
167 plan_pts[idx + 2].pose.position,
168 plan_pts[idx + 2].pose.position});
171 plan_pts[idx].pose.position = applyFilter(
173 plan_pts[idx - 3].pose.position,
174 plan_pts[idx - 2].pose.position,
175 plan_pts[idx - 1].pose.position,
176 plan_pts[idx].pose.position,
177 plan_pts[idx + 1].pose.position,
178 plan_pts[idx + 1].pose.position,
179 plan_pts[idx + 1].pose.position});
182 applyFilterOverAxes(path.poses);
185 if (do_refinement_) {
186 for (
int i = 0; i < refinement_num_; i++) {
187 applyFilterOverAxes(path.poses);
191 updateApproximatePathOrientations(path, reversing_segment);
197 #include "pluginlib/class_list_macros.hpp"
smoother interface that acts as a virtual base class for all smoother plugins
A path smoother implementation using Savitzky Golay filters.
bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment)
Smoother method - does the smoothing on a segment.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.