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 node->get_parameter(name +
".do_refinement", do_refinement_);
42 node->get_parameter(name +
".refinement_num", refinement_num_);
46 nav_msgs::msg::Path & path,
47 const rclcpp::Duration & max_time)
49 steady_clock::time_point start = steady_clock::now();
50 double time_remaining = max_time.seconds();
52 bool success =
true, reversing_segment;
53 nav_msgs::msg::Path curr_path_segment;
54 curr_path_segment.header = path.header;
56 std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
58 for (
unsigned int i = 0; i != path_segments.size(); i++) {
59 if (path_segments[i].end - path_segments[i].start > 9) {
61 curr_path_segment.poses.clear();
63 path.poses.begin() + path_segments[i].start,
64 path.poses.begin() + path_segments[i].end + 1,
65 std::back_inserter(curr_path_segment.poses));
68 steady_clock::time_point now = steady_clock::now();
69 time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
71 if (time_remaining <= 0.0) {
74 "Smoothing time exceeded allowed duration of %0.2f.", max_time.seconds());
79 success = success && smoothImpl(curr_path_segment, reversing_segment);
83 curr_path_segment.poses.begin(),
84 curr_path_segment.poses.end(),
85 path.poses.begin() + path_segments[i].start);
93 nav_msgs::msg::Path & path,
94 bool & reversing_segment)
97 const unsigned int & path_size = path.poses.size();
100 const std::array<double, 7> filter = {
109 auto applyFilter = [&](
const std::vector<geometry_msgs::msg::Point> & data)
110 -> geometry_msgs::msg::Point
112 geometry_msgs::msg::Point val;
113 for (
unsigned int i = 0; i != filter.size(); i++) {
114 val.x += filter[i] * data[i].x;
115 val.y += filter[i] * data[i].y;
120 auto applyFilterOverAxes =
121 [&](std::vector<geometry_msgs::msg::PoseStamped> & plan_pts,
122 const std::vector<geometry_msgs::msg::PoseStamped> & init_plan_pts) ->
void
124 auto pt_m3 = init_plan_pts[0].pose.position;
125 auto pt_m2 = init_plan_pts[0].pose.position;
126 auto pt_m1 = init_plan_pts[0].pose.position;
127 auto pt = init_plan_pts[1].pose.position;
128 auto pt_p1 = init_plan_pts[2].pose.position;
129 auto pt_p2 = init_plan_pts[3].pose.position;
130 auto pt_p3 = init_plan_pts[4].pose.position;
133 for (
unsigned int idx = 1; idx != path_size - 1; idx++) {
134 plan_pts[idx].pose.position = applyFilter({pt_m3, pt_m2, pt_m1, pt, pt_p1, pt_p2, pt_p3});
142 if (idx + 4 < path_size - 1) {
143 pt_p3 = init_plan_pts[idx + 4].pose.position;
146 pt_p3 = init_plan_pts[path_size - 1].pose.position;
151 const auto initial_path_poses = path.poses;
152 applyFilterOverAxes(path.poses, initial_path_poses);
155 if (do_refinement_) {
156 for (
int i = 0; i < refinement_num_; i++) {
157 const auto reined_initial_path_poses = path.poses;
158 applyFilterOverAxes(path.poses, reined_initial_path_poses);
162 updateApproximatePathOrientations(path, reversing_segment);
168 #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.