17 #include "nav2_smoother/savitzky_golay_smoother.hpp"
18 #include "nav2_core/smoother_exceptions.hpp"
20 namespace nav2_smoother
23 using namespace smoother_utils;
24 using namespace nav2_util::geometry_utils;
25 using namespace std::chrono;
26 using nav2_util::declare_parameter_if_not_declared;
28 void SavitzkyGolaySmoother::configure(
29 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
30 std::string name, std::shared_ptr<tf2_ros::Buffer>,
31 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
32 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
34 auto node = parent.lock();
35 logger_ = node->get_logger();
37 declare_parameter_if_not_declared(
38 node, name +
".do_refinement", rclcpp::ParameterValue(
true));
39 declare_parameter_if_not_declared(
40 node, name +
".refinement_num", rclcpp::ParameterValue(2));
41 declare_parameter_if_not_declared(
42 node, name +
".enforce_path_inversion", rclcpp::ParameterValue(
true));
43 node->get_parameter(name +
".do_refinement", do_refinement_);
44 node->get_parameter(name +
".refinement_num", refinement_num_);
45 node->get_parameter(name +
".enforce_path_inversion", enforce_path_inversion_);
49 nav_msgs::msg::Path & path,
50 const rclcpp::Duration & max_time)
52 steady_clock::time_point start = steady_clock::now();
53 double time_remaining = max_time.seconds();
55 bool success =
true, reversing_segment;
56 nav_msgs::msg::Path curr_path_segment;
57 curr_path_segment.header = path.header;
59 std::vector<PathSegment> path_segments{
60 PathSegment{0u,
static_cast<unsigned int>(path.poses.size() - 1)}};
61 if (enforce_path_inversion_) {
62 path_segments = findDirectionalPathSegments(path);
65 for (
unsigned int i = 0; i != path_segments.size(); i++) {
66 if (path_segments[i].end - path_segments[i].start > 9) {
68 curr_path_segment.poses.clear();
70 path.poses.begin() + path_segments[i].start,
71 path.poses.begin() + path_segments[i].end + 1,
72 std::back_inserter(curr_path_segment.poses));
75 steady_clock::time_point now = steady_clock::now();
76 time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
78 if (time_remaining <= 0.0) {
81 "Smoothing time exceeded allowed duration of %0.2f.", max_time.seconds());
86 success = success && smoothImpl(curr_path_segment, reversing_segment);
90 curr_path_segment.poses.begin(),
91 curr_path_segment.poses.end(),
92 path.poses.begin() + path_segments[i].start);
100 nav_msgs::msg::Path & path,
101 bool & reversing_segment)
104 const unsigned int & path_size = path.poses.size();
107 const std::array<double, 7> filter = {
116 auto applyFilter = [&](
const std::vector<geometry_msgs::msg::Point> & data)
117 -> geometry_msgs::msg::Point
119 geometry_msgs::msg::Point val;
120 for (
unsigned int i = 0; i != filter.size(); i++) {
121 val.x += filter[i] * data[i].x;
122 val.y += filter[i] * data[i].y;
127 auto applyFilterOverAxes =
128 [&](std::vector<geometry_msgs::msg::PoseStamped> & plan_pts,
129 const std::vector<geometry_msgs::msg::PoseStamped> & init_plan_pts) ->
void
131 auto pt_m3 = init_plan_pts[0].pose.position;
132 auto pt_m2 = init_plan_pts[0].pose.position;
133 auto pt_m1 = init_plan_pts[0].pose.position;
134 auto pt = init_plan_pts[1].pose.position;
135 auto pt_p1 = init_plan_pts[2].pose.position;
136 auto pt_p2 = init_plan_pts[3].pose.position;
137 auto pt_p3 = init_plan_pts[4].pose.position;
140 for (
unsigned int idx = 1; idx != path_size - 1; idx++) {
141 plan_pts[idx].pose.position = applyFilter({pt_m3, pt_m2, pt_m1, pt, pt_p1, pt_p2, pt_p3});
149 if (idx + 4 < path_size - 1) {
150 pt_p3 = init_plan_pts[idx + 4].pose.position;
153 pt_p3 = init_plan_pts[path_size - 1].pose.position;
158 const auto initial_path_poses = path.poses;
159 applyFilterOverAxes(path.poses, initial_path_poses);
162 if (do_refinement_) {
163 for (
int i = 0; i < refinement_num_; i++) {
164 const auto reined_initial_path_poses = path.poses;
165 applyFilterOverAxes(path.poses, reined_initial_path_poses);
169 updateApproximatePathOrientations(path, reversing_segment);
175 #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.