Nav2 Navigation Stack - jazzy  jazzy
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 
20 #include "geometry_msgs/msg/pose.hpp"
21 #include "geometry_msgs/msg/pose_stamped.hpp"
22 #include "geometry_msgs/msg/pose2_d.hpp"
23 #include "geometry_msgs/msg/point.hpp"
24 #include "geometry_msgs/msg/quaternion.hpp"
25 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
26 #include "nav_msgs/msg/path.hpp"
27 
28 namespace nav2_util
29 {
30 namespace geometry_utils
31 {
32 
38 inline geometry_msgs::msg::Quaternion orientationAroundZAxis(double angle)
39 {
40  tf2::Quaternion q;
41  q.setRPY(0, 0, angle); // void returning function
42  return tf2::toMsg(q);
43 }
44 
52 inline double euclidean_distance(
53  const geometry_msgs::msg::Point & pos1,
54  const geometry_msgs::msg::Point & pos2,
55  const bool is_3d = false)
56 {
57  double dx = pos1.x - pos2.x;
58  double dy = pos1.y - pos2.y;
59 
60  if (is_3d) {
61  double dz = pos1.z - pos2.z;
62  return std::hypot(dx, dy, dz);
63  }
64 
65  return std::hypot(dx, dy);
66 }
67 
75 inline double euclidean_distance(
76  const geometry_msgs::msg::Pose & pos1,
77  const geometry_msgs::msg::Pose & pos2,
78  const bool is_3d = false)
79 {
80  double dx = pos1.position.x - pos2.position.x;
81  double dy = pos1.position.y - pos2.position.y;
82 
83  if (is_3d) {
84  double dz = pos1.position.z - pos2.position.z;
85  return std::hypot(dx, dy, dz);
86  }
87 
88  return std::hypot(dx, dy);
89 }
90 
98 inline double euclidean_distance(
99  const geometry_msgs::msg::PoseStamped & pos1,
100  const geometry_msgs::msg::PoseStamped & pos2,
101  const bool is_3d = false)
102 {
103  return euclidean_distance(pos1.pose, pos2.pose, is_3d);
104 }
105 
112 inline double euclidean_distance(
113  const geometry_msgs::msg::Pose2D & pos1,
114  const geometry_msgs::msg::Pose2D & pos2)
115 {
116  double dx = pos1.x - pos2.x;
117  double dy = pos1.y - pos2.y;
118 
119  return std::hypot(dx, dy);
120 }
121 
125 template<typename Iter, typename Getter>
126 inline Iter min_by(Iter begin, Iter end, Getter getCompareVal)
127 {
128  if (begin == end) {
129  return end;
130  }
131  auto lowest = getCompareVal(*begin);
132  Iter lowest_it = begin;
133  for (Iter it = ++begin; it != end; ++it) {
134  auto comp = getCompareVal(*it);
135  if (comp <= lowest) {
136  lowest = comp;
137  lowest_it = it;
138  }
139  }
140  return lowest_it;
141 }
142 
146 template<typename Iter, typename Getter>
147 inline Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
148 {
149  if (begin == end) {
150  return end;
151  }
152  Getter dist = 0.0;
153  for (Iter it = begin; it != end - 1; it++) {
154  dist += euclidean_distance(*it, *(it + 1));
155  if (dist > getCompareVal) {
156  return it + 1;
157  }
158  }
159  return end;
160 }
161 
170 inline double calculate_path_length(const nav_msgs::msg::Path & path, size_t start_index = 0)
171 {
172  if (start_index + 1 >= path.poses.size()) {
173  return 0.0;
174  }
175  double path_length = 0.0;
176  for (size_t idx = start_index; idx < path.poses.size() - 1; ++idx) {
177  path_length += euclidean_distance(path.poses[idx].pose, path.poses[idx + 1].pose);
178  }
179  return path_length;
180 }
181 
182 } // namespace geometry_utils
183 } // namespace nav2_util
184 
185 #endif // NAV2_UTIL__GEOMETRY_UTILS_HPP_