15 #ifndef NAV2_UTIL__GEOMETRY_UTILS_HPP_
16 #define NAV2_UTIL__GEOMETRY_UTILS_HPP_
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"
32 namespace geometry_utils
40 inline geometry_msgs::msg::Quaternion orientationAroundZAxis(
double angle)
43 q.setRPY(0, 0, angle);
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)
59 double dx = pos1.x - pos2.x;
60 double dy = pos1.y - pos2.y;
63 double dz = pos1.z - pos2.z;
64 return std::hypot(dx, dy, dz);
67 return std::hypot(dx, dy);
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)
82 double dx = pos1.position.x - pos2.position.x;
83 double dy = pos1.position.y - pos2.position.y;
86 double dz = pos1.position.z - pos2.position.z;
87 return std::hypot(dx, dy, dz);
90 return std::hypot(dx, dy);
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)
105 return euclidean_distance(pos1.pose, pos2.pose, is_3d);
114 inline double euclidean_distance(
115 const geometry_msgs::msg::Pose2D & pos1,
116 const geometry_msgs::msg::Pose2D & pos2)
118 double dx = pos1.x - pos2.x;
119 double dy = pos1.y - pos2.y;
121 return std::hypot(dx, dy);
127 template<
typename Iter,
typename Getter>
128 inline Iter min_by(Iter begin, Iter end, Getter getCompareVal)
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) {
148 template<
typename Iter,
typename Getter>
149 inline Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
155 for (Iter it = begin; it != end - 1; it++) {
156 dist += euclidean_distance(*it, *(it + 1));
157 if (dist > getCompareVal) {
172 inline double calculate_path_length(
const nav_msgs::msg::Path & path,
size_t start_index = 0)
174 if (start_index + 1 >= path.poses.size()) {
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);
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)
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;
201 if (itr == waypoint_statuses.end()) {
205 return itr - waypoint_statuses.begin();