15#ifndef EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
16#define EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
21#include "geometry_msgs/msg/pose.hpp"
22#include "geometry_msgs/msg/pose_stamped.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"
39 q.setRPY(0, 0, angle);
51 const geometry_msgs::msg::Point & pos1,
52 const geometry_msgs::msg::Point & pos2,
53 const bool is_3d =
false)
55 double dx = pos1.x - pos2.x;
56 double dy = pos1.y - pos2.y;
59 double dz = pos1.z - pos2.z;
60 return std::hypot(dx, dy, dz);
63 return std::hypot(dx, dy);
74 const geometry_msgs::msg::Pose & pos1,
75 const geometry_msgs::msg::Pose & pos2,
76 const bool is_3d =
false)
78 double dx = pos1.position.x - pos2.position.x;
79 double dy = pos1.position.y - pos2.position.y;
82 double dz = pos1.position.z - pos2.position.z;
83 return std::hypot(dx, dy, dz);
86 return std::hypot(dx, dy);
97 const geometry_msgs::msg::PoseStamped & pos1,
98 const geometry_msgs::msg::PoseStamped & pos2,
99 const bool is_3d =
false)
107template<
typename Iter,
typename Getter>
108inline Iter
min_by(Iter begin, Iter end, Getter getCompareVal)
113 auto lowest = getCompareVal(*begin);
114 Iter lowest_it = begin;
115 for (Iter it = ++begin; it != end; ++it) {
116 auto comp = getCompareVal(*it);
117 if (comp <= lowest) {
128template<
typename Iter,
typename Getter>
135 for (Iter it = begin; it != end - 1; it++) {
137 if (dist > getCompareVal) {
154 if (start_index + 1 >= path.poses.size()) {
157 double path_length = 0.0;
158 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:50
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:129
Iter min_by(Iter begin, Iter end, Getter getCompareVal)
Find element in iterator with the minimum calculated value.
Definition geometry_utils.hpp:108
geometry_msgs::msg::Quaternion orientationAroundZAxis(double angle)
Get a geometry_msgs Quaternion from a yaw angle.
Definition geometry_utils.hpp:36
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:152