EasyNav Plugins
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
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"
26
27namespace easynav
28{
29
35inline geometry_msgs::msg::Quaternion orientationAroundZAxis(double angle)
36{
37 tf2::Quaternion q;
38 q.setRPY(0, 0, angle); // void returning function
39 return tf2::toMsg(q);
40}
41
49inline double euclidean_distance(
50 const geometry_msgs::msg::Point & pos1,
51 const geometry_msgs::msg::Point & pos2,
52 const bool is_3d = false)
53{
54 double dx = pos1.x - pos2.x;
55 double dy = pos1.y - pos2.y;
56
57 if (is_3d) {
58 double dz = pos1.z - pos2.z;
59 return std::hypot(dx, dy, dz);
60 }
61
62 return std::hypot(dx, dy);
63}
64
72inline double euclidean_distance(
73 const geometry_msgs::msg::Pose & pos1,
74 const geometry_msgs::msg::Pose & pos2,
75 const bool is_3d = false)
76{
77 double dx = pos1.position.x - pos2.position.x;
78 double dy = pos1.position.y - pos2.position.y;
79
80 if (is_3d) {
81 double dz = pos1.position.z - pos2.position.z;
82 return std::hypot(dx, dy, dz);
83 }
84
85 return std::hypot(dx, dy);
86}
87
95inline double euclidean_distance(
96 const geometry_msgs::msg::PoseStamped & pos1,
97 const geometry_msgs::msg::PoseStamped & pos2,
98 const bool is_3d = false)
99{
100 return euclidean_distance(pos1.pose, pos2.pose, is_3d);
101}
102
106template<typename Iter, typename Getter>
107inline Iter min_by(Iter begin, Iter end, Getter getCompareVal)
108{
109 if (begin == end) {
110 return end;
111 }
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) {
117 lowest = comp;
118 lowest_it = it;
119 }
120 }
121 return lowest_it;
122}
123
127template<typename Iter, typename Getter>
128inline Iter first_after_integrated_distance(Iter begin, Iter end, Getter getCompareVal)
129{
130 if (begin == end) {
131 return end;
132 }
133 Getter dist = 0.0;
134 for (Iter it = begin; it != end - 1; it++) {
135 dist += euclidean_distance(*it, *(it + 1));
136 if (dist > getCompareVal) {
137 return it + 1;
138 }
139 }
140 return end;
141}
142
151inline double calculate_path_length(const nav_msgs::msg::Path & path, size_t start_index = 0)
152{
153 if (start_index + 1 >= path.poses.size()) {
154 return 0.0;
155 }
156 double path_length = 0.0;
157 for (size_t idx = start_index; idx < path.poses.size() - 1; ++idx) {
158 path_length += euclidean_distance(path.poses[idx].pose, path.poses[idx + 1].pose);
159 }
160 return path_length;
161}
162
163} // namespace easynav
164
165#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: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