15 #ifndef NAV2_UTIL__GEOMETRY_UTILS_HPP_
16 #define NAV2_UTIL__GEOMETRY_UTILS_HPP_
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"
30 namespace geometry_utils
38 inline geometry_msgs::msg::Quaternion orientationAroundZAxis(
double angle)
41 q.setRPY(0, 0, angle);
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)
57 double dx = pos1.x - pos2.x;
58 double dy = pos1.y - pos2.y;
61 double dz = pos1.z - pos2.z;
62 return std::hypot(dx, dy, dz);
65 return std::hypot(dx, dy);
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)
80 double dx = pos1.position.x - pos2.position.x;
81 double dy = pos1.position.y - pos2.position.y;
84 double dz = pos1.position.z - pos2.position.z;
85 return std::hypot(dx, dy, dz);
88 return std::hypot(dx, dy);
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)
103 return euclidean_distance(pos1.pose, pos2.pose, is_3d);
112 inline double euclidean_distance(
113 const geometry_msgs::msg::Pose2D & pos1,
114 const geometry_msgs::msg::Pose2D & pos2)
116 double dx = pos1.x - pos2.x;
117 double dy = pos1.y - pos2.y;
119 return std::hypot(dx, dy);
125 template<
typename Iter,
typename Getter>
126 inline Iter min_by(Iter begin, Iter end, Getter getCompareVal)
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) {
146 template<
typename Iter,
typename Getter>
147 inline Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
153 for (Iter it = begin; it != end - 1; it++) {
154 dist += euclidean_distance(*it, *(it + 1));
155 if (dist > getCompareVal) {
170 inline double calculate_path_length(
const nav_msgs::msg::Path & path,
size_t start_index = 0)
172 if (start_index + 1 >= path.poses.size()) {
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);