15 #ifndef NAV2_SMOOTHER__SMOOTHER_UTILS_HPP_
16 #define NAV2_SMOOTHER__SMOOTHER_UTILS_HPP_
26 #include "nav2_core/smoother.hpp"
27 #include "nav2_costmap_2d/costmap_2d.hpp"
28 #include "nav2_costmap_2d/cost_values.hpp"
29 #include "nav2_util/geometry_utils.hpp"
30 #include "nav2_ros_common/node_utils.hpp"
31 #include "nav_msgs/msg/path.hpp"
32 #include "angles/angles.h"
33 #include "tf2/utils.hpp"
35 namespace smoother_utils
48 typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator;
49 typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator;
51 inline std::vector<PathSegment> findDirectionalPathSegments(
52 const nav_msgs::msg::Path & path)
54 std::vector<PathSegment> segments;
56 curr_segment.start = 0;
59 for (
unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
61 double oa_x = path.poses[idx].pose.position.x -
62 path.poses[idx - 1].pose.position.x;
63 double oa_y = path.poses[idx].pose.position.y -
64 path.poses[idx - 1].pose.position.y;
65 double ab_x = path.poses[idx + 1].pose.position.x -
66 path.poses[idx].pose.position.x;
67 double ab_y = path.poses[idx + 1].pose.position.y -
68 path.poses[idx].pose.position.y;
71 double dot_product = (oa_x * ab_x) + (oa_y * ab_y);
72 if (dot_product < 0.0) {
73 curr_segment.end = idx;
74 segments.push_back(curr_segment);
75 curr_segment.start = idx;
79 double cur_theta = tf2::getYaw(path.poses[idx].pose.orientation);
80 double next_theta = tf2::getYaw(path.poses[idx + 1].pose.orientation);
81 double dtheta = angles::shortest_angular_distance(cur_theta, next_theta);
82 if (fabs(ab_x) < 1e-4 && fabs(ab_y) < 1e-4 && fabs(dtheta) > 1e-4) {
83 curr_segment.end = idx;
84 segments.push_back(curr_segment);
85 curr_segment.start = idx;
89 curr_segment.end = path.poses.size() - 1;
90 segments.push_back(curr_segment);
94 inline void updateApproximatePathOrientations(
95 nav_msgs::msg::Path & path,
96 bool & reversing_segment)
98 double dx, dy, theta, pt_yaw;
99 reversing_segment =
false;
102 dx = path.poses[2].pose.position.x - path.poses[1].pose.position.x;
103 dy = path.poses[2].pose.position.y - path.poses[1].pose.position.y;
104 theta = atan2(dy, dx);
105 pt_yaw = tf2::getYaw(path.poses[1].pose.orientation);
106 if (fabs(angles::shortest_angular_distance(pt_yaw, theta)) > M_PI_2) {
107 reversing_segment =
true;
111 for (
unsigned int i = 0; i != path.poses.size() - 1; i++) {
112 dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x;
113 dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y;
114 theta = atan2(dy, dx);
117 if (fabs(dx) < 1e-4 && fabs(dy) < 1e-4) {
122 if (reversing_segment) {
126 path.poses[i].pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta);