Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
geometry_utils.hpp
1 // Copyright (c) 2019 Intel Corporation
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.
14 
15 #ifndef NAV2_UTIL__GEOMETRY_UTILS_HPP_
16 #define NAV2_UTIL__GEOMETRY_UTILS_HPP_
17 
18 #include <cmath>
19 #include <vector>
20 
21 #include "geometry_msgs/msg/pose.hpp"
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "geometry_msgs/msg/pose2_d.hpp"
24 #include "geometry_msgs/msg/point.hpp"
25 #include "geometry_msgs/msg/quaternion.hpp"
26 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 #include "nav2_msgs/msg/waypoint_status.hpp"
29 
30 namespace nav2_util
31 {
32 namespace geometry_utils
33 {
34 
40 inline geometry_msgs::msg::Quaternion orientationAroundZAxis(double angle)
41 {
42  tf2::Quaternion q;
43  q.setRPY(0, 0, angle); // void returning function
44  return tf2::toMsg(q);
45 }
46 
54 inline double euclidean_distance(
55  const geometry_msgs::msg::Point & pos1,
56  const geometry_msgs::msg::Point & pos2,
57  const bool is_3d = false)
58 {
59  double dx = pos1.x - pos2.x;
60  double dy = pos1.y - pos2.y;
61 
62  if (is_3d) {
63  double dz = pos1.z - pos2.z;
64  return std::hypot(dx, dy, dz);
65  }
66 
67  return std::hypot(dx, dy);
68 }
69 
77 inline double euclidean_distance(
78  const geometry_msgs::msg::Pose & pos1,
79  const geometry_msgs::msg::Pose & pos2,
80  const bool is_3d = false)
81 {
82  double dx = pos1.position.x - pos2.position.x;
83  double dy = pos1.position.y - pos2.position.y;
84 
85  if (is_3d) {
86  double dz = pos1.position.z - pos2.position.z;
87  return std::hypot(dx, dy, dz);
88  }
89 
90  return std::hypot(dx, dy);
91 }
92 
100 inline double euclidean_distance(
101  const geometry_msgs::msg::PoseStamped & pos1,
102  const geometry_msgs::msg::PoseStamped & pos2,
103  const bool is_3d = false)
104 {
105  return euclidean_distance(pos1.pose, pos2.pose, is_3d);
106 }
107 
114 inline double euclidean_distance(
115  const geometry_msgs::msg::Pose2D & pos1,
116  const geometry_msgs::msg::Pose2D & pos2)
117 {
118  double dx = pos1.x - pos2.x;
119  double dy = pos1.y - pos2.y;
120 
121  return std::hypot(dx, dy);
122 }
123 
127 template<typename Iter, typename Getter>
128 inline Iter min_by(Iter begin, Iter end, Getter getCompareVal)
129 {
130  if (begin == end) {
131  return end;
132  }
133  auto lowest = getCompareVal(*begin);
134  Iter lowest_it = begin;
135  for (Iter it = ++begin; it != end; ++it) {
136  auto comp = getCompareVal(*it);
137  if (comp <= lowest) {
138  lowest = comp;
139  lowest_it = it;
140  }
141  }
142  return lowest_it;
143 }
144 
148 template<typename Iter, typename Getter>
149 inline Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
150 {
151  if (begin == end) {
152  return end;
153  }
154  Getter dist = 0.0;
155  for (Iter it = begin; it != end - 1; it++) {
156  dist += euclidean_distance(*it, *(it + 1));
157  if (dist > getCompareVal) {
158  return it + 1;
159  }
160  }
161  return end;
162 }
163 
172 inline double calculate_path_length(const nav_msgs::msg::Path & path, size_t start_index = 0)
173 {
174  if (start_index + 1 >= path.poses.size()) {
175  return 0.0;
176  }
177  double path_length = 0.0;
178  for (size_t idx = start_index; idx < path.poses.size() - 1; ++idx) {
179  path_length += euclidean_distance(path.poses[idx].pose, path.poses[idx + 1].pose);
180  }
181  return path_length;
182 }
183 
191 inline int find_next_matching_goal_in_waypoint_statuses(
192  const std::vector<nav2_msgs::msg::WaypointStatus> & waypoint_statuses,
193  const geometry_msgs::msg::PoseStamped & goal)
194 {
195  auto itr = std::find_if(waypoint_statuses.begin(), waypoint_statuses.end(),
196  [&goal](const nav2_msgs::msg::WaypointStatus & status){
197  return status.waypoint_pose == goal &&
198  status.waypoint_status == nav2_msgs::msg::WaypointStatus::PENDING;
199  });
200 
201  if (itr == waypoint_statuses.end()) {
202  return -1;
203  }
204 
205  return itr - waypoint_statuses.begin();
206 }
207 
208 } // namespace geometry_utils
209 } // namespace nav2_util
210 
211 #endif // NAV2_UTIL__GEOMETRY_UTILS_HPP_