EasyNav Costmap Stack
Loading...
Searching...
No Matches
geometry_utils.hpp
Go to the documentation of this file.
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 EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
16#define EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
17
18#include <cmath>
19#include <vector>
20
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"
27
28namespace easynav
29{
30
36inline geometry_msgs::msg::Quaternion orientationAroundZAxis(double angle)
37{
38 tf2::Quaternion q;
39 q.setRPY(0, 0, angle); // void returning function
40 return tf2::toMsg(q);
41}
42
50inline double euclidean_distance(
51 const geometry_msgs::msg::Point & pos1,
52 const geometry_msgs::msg::Point & pos2,
53 const bool is_3d = false)
54{
55 double dx = pos1.x - pos2.x;
56 double dy = pos1.y - pos2.y;
57
58 if (is_3d) {
59 double dz = pos1.z - pos2.z;
60 return std::hypot(dx, dy, dz);
61 }
62
63 return std::hypot(dx, dy);
64}
65
73inline double euclidean_distance(
74 const geometry_msgs::msg::Pose & pos1,
75 const geometry_msgs::msg::Pose & pos2,
76 const bool is_3d = false)
77{
78 double dx = pos1.position.x - pos2.position.x;
79 double dy = pos1.position.y - pos2.position.y;
80
81 if (is_3d) {
82 double dz = pos1.position.z - pos2.position.z;
83 return std::hypot(dx, dy, dz);
84 }
85
86 return std::hypot(dx, dy);
87}
88
96inline double euclidean_distance(
97 const geometry_msgs::msg::PoseStamped & pos1,
98 const geometry_msgs::msg::PoseStamped & pos2,
99 const bool is_3d = false)
100{
101 return euclidean_distance(pos1.pose, pos2.pose, is_3d);
102}
103
107template<typename Iter, typename Getter>
108inline Iter min_by(Iter begin, Iter end, Getter getCompareVal)
109{
110 if (begin == end) {
111 return end;
112 }
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) {
118 lowest = comp;
119 lowest_it = it;
120 }
121 }
122 return lowest_it;
123}
124
128template<typename Iter, typename Getter>
129inline Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
130{
131 if (begin == end) {
132 return end;
133 }
134 Getter dist = 0.0;
135 for (Iter it = begin; it != end - 1; it++) {
136 dist += euclidean_distance(*it, *(it + 1));
137 if (dist > getCompareVal) {
138 return it + 1;
139 }
140 }
141 return end;
142}
143
152inline double calculate_path_length(const nav_msgs::msg::Path & path, size_t start_index = 0)
153{
154 if (start_index + 1 >= path.poses.size()) {
155 return 0.0;
156 }
157 double path_length = 0.0;
158 for (size_t idx = start_index; idx < path.poses.size() - 1; ++idx) {
159 path_length += euclidean_distance(path.poses[idx].pose, path.poses[idx + 1].pose);
160 }
161 return path_length;
162}
163
164} // namespace easynav
165
166#endif // EASYNAV_COSTMAP_COMMON__GEOMETRY_UTILS_HPP_
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