15#ifndef EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
16#define EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
20#include "geometry_msgs/msg/pose.hpp"
21#include "geometry_msgs/msg/pose_stamped.hpp"
22#include "geometry_msgs/msg/point.hpp"
23#include "geometry_msgs/msg/quaternion.hpp"
24#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
25#include "nav_msgs/msg/path.hpp"
38 q.setRPY(0, 0, angle);
50 const geometry_msgs::msg::Point & pos1,
51 const geometry_msgs::msg::Point & pos2,
52 const bool is_3d =
false)
54 double dx = pos1.x - pos2.x;
55 double dy = pos1.y - pos2.y;
58 double dz = pos1.z - pos2.z;
59 return std::hypot(dx, dy, dz);
62 return std::hypot(dx, dy);
73 const geometry_msgs::msg::Pose & pos1,
74 const geometry_msgs::msg::Pose & pos2,
75 const bool is_3d =
false)
77 double dx = pos1.position.x - pos2.position.x;
78 double dy = pos1.position.y - pos2.position.y;
81 double dz = pos1.position.z - pos2.position.z;
82 return std::hypot(dx, dy, dz);
85 return std::hypot(dx, dy);
96 const geometry_msgs::msg::PoseStamped & pos1,
97 const geometry_msgs::msg::PoseStamped & pos2,
98 const bool is_3d =
false)
106template<
typename Iter,
typename Getter>
107inline Iter
min_by(Iter begin, Iter end, Getter getCompareVal)
112 auto lowest = getCompareVal(*begin);
113 Iter lowest_it = begin;
114 for (Iter it = ++begin; it != end; ++it) {
115 auto comp = getCompareVal(*it);
116 if (comp <= lowest) {
127template<
typename Iter,
typename Getter>
134 for (Iter it = begin; it != end - 1; it++) {
136 if (dist > getCompareVal) {
153 if (start_index + 1 >= path.poses.size()) {
156 double path_length = 0.0;
157 for (
size_t idx = start_index; idx < path.poses.size() - 1; ++idx) {
Provides a mapping for often used cost values.
Definition cost_values.hpp:41
double euclidean_distance(const geometry_msgs::msg::Point &pos1, const geometry_msgs::msg::Point &pos2, const bool is_3d=false)
Get the euclidean distance between 2 geometry_msgs::Points.
Definition geometry_utils.hpp:49
Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
Find first element in iterator that is greater integrated distance than comparevalue.
Definition geometry_utils.hpp:128
Iter min_by(Iter begin, Iter end, Getter getCompareVal)
Find element in iterator with the minimum calculated value.
Definition geometry_utils.hpp:107
geometry_msgs::msg::Quaternion orientationAroundZAxis(double angle)
Get a geometry_msgs Quaternion from a yaw angle.
Definition geometry_utils.hpp:35
double calculate_path_length(const nav_msgs::msg::Path &path, size_t start_index=0)
Calculate the length of the provided path, starting at the provided index.
Definition geometry_utils.hpp:151