Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smoother_utils.hpp
1 // Copyright (c) 2022, Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #ifndef NAV2_SMOOTHER__SMOOTHER_UTILS_HPP_
16 #define NAV2_SMOOTHER__SMOOTHER_UTILS_HPP_
17 
18 #include <cmath>
19 #include <vector>
20 #include <string>
21 #include <iostream>
22 #include <memory>
23 #include <queue>
24 #include <utility>
25 
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"
34 
35 namespace smoother_utils
36 {
37 
43 {
44  unsigned int start;
45  unsigned int end;
46 };
47 
48 typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator;
49 typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator;
50 
51 inline std::vector<PathSegment> findDirectionalPathSegments(
52  const nav_msgs::msg::Path & path)
53 {
54  std::vector<PathSegment> segments;
55  PathSegment curr_segment;
56  curr_segment.start = 0;
57 
58  // Iterating through the path to determine the position of the cusp
59  for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
60  // We have two vectors for the dot product OA and AB. Determining the vectors.
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;
69 
70  // Checking for the existence of cusp, in the path, using the dot product.
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;
76  }
77 
78  // Checking for the existence of a differential rotation in place.
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;
86  }
87  }
88 
89  curr_segment.end = path.poses.size() - 1;
90  segments.push_back(curr_segment);
91  return segments;
92 }
93 
94 inline void updateApproximatePathOrientations(
95  nav_msgs::msg::Path & path,
96  bool & reversing_segment)
97 {
98  double dx, dy, theta, pt_yaw;
99  reversing_segment = false;
100 
101  // Find if this path segment is in reverse
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;
108  }
109 
110  // Find the angle relative the path position vectors
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);
115 
116  // If points are overlapping, pass
117  if (fabs(dx) < 1e-4 && fabs(dy) < 1e-4) {
118  continue;
119  }
120 
121  // Flip the angle if this path segment is in reverse
122  if (reversing_segment) {
123  theta += M_PI; // orientationAroundZAxis will normalize
124  }
125 
126  path.poses[i].pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta);
127  }
128 }
129 
130 } // namespace smoother_utils
131 
132 #endif // NAV2_SMOOTHER__SMOOTHER_UTILS_HPP_