util.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
37 
38 #include <mesh_map/util.h>
39 #include <std_msgs/ColorRGBA.h>
41 #include <tf2/LinearMath/Vector3.h>
44 
45 namespace mesh_map
46 {
47 void getMinMax(const lvr2::VertexMap<float>& costs, float& min, float& max)
48 {
49  max = std::numeric_limits<float>::min();
50  min = std::numeric_limits<float>::max();
51 
52  // Calculate minimum and maximum values
53  for (auto vH : costs)
54  {
55  if (max < costs[vH] && std::isfinite(costs[vH]))
56  max = costs[vH];
57  if (min > costs[vH] && std::isfinite(costs[vH]))
58  min = costs[vH];
59  }
60 }
61 
62 Vector toVector(const geometry_msgs::Point& p)
63 {
64  return Vector(p.x, p.y, p.z);
65 }
66 
67 geometry_msgs::Pose calculatePoseFromDirection(const Vector& position, const Vector& direction, const Normal& normal)
68 {
69  Normal ez = normal.normalized();
70  Normal ey = normal.cross(direction).normalized();
71  Normal ex = ey.cross(normal).normalized();
72 
73  tf2::Matrix3x3 tf_basis(ex.x, ey.x, ez.x, ex.y, ey.y, ez.y, ex.z, ey.z, ez.z);
74 
75  tf2::Vector3 tf_origin(position.x, position.y, position.z);
76 
77  tf2::Transform tf_pose;
78  tf_pose.setBasis(tf_basis);
79  tf_pose.setRotation(tf_pose.getRotation().normalize());
80  tf_pose.setOrigin(tf_origin);
81  geometry_msgs::Pose pose;
82  tf2::toMsg(tf_pose, pose);
83  return pose;
84 }
85 
86 geometry_msgs::Pose calculatePoseFromPosition(const Vector& current, const Vector& next, const Normal& normal)
87 {
88  float cost = 0;
89  return calculatePoseFromPosition(current, next, normal, cost);
90 }
91 
92 geometry_msgs::Pose calculatePoseFromPosition(const Vector& current, const Vector& next, const Normal& normal,
93  float& cost)
94 {
95  const Vector direction = next - current;
96  cost = direction.length();
97  return calculatePoseFromDirection(current, direction, normal);
98 }
99 
100 bool inTriangle(const Vector& p, const Vector& v0, const Vector& v1, const Vector& v2, const float& max_dist,
101  const float& epsilon)
102 {
103  float dist;
104  std::array<float, 3> barycentric_coords;
105  return projectedBarycentricCoords(p, { v0, v1, v2 }, barycentric_coords, dist) && dist < max_dist;
106 }
107 
108 Vector projectVectorOntoPlane(const Vector& vec, const Vector& ref, const Normal& normal)
109 {
110  return vec - (normal * (vec.dot(normal) - (ref.dot(normal))));
111 }
112 
113 bool projectedBarycentricCoords(const Vector& p, const std::array<Vector, 3>& vertices,
114  std::array<float, 3>& barycentric_coords)
115 {
116  float dist;
117  return projectedBarycentricCoords(p, vertices, barycentric_coords, dist);
118 }
119 
120 bool projectedBarycentricCoords(const Vector& p, const std::array<Vector, 3>& vertices,
121  std::array<float, 3>& barycentric_coords, float& dist)
122 {
123  const Vector& a = vertices[0];
124  const Vector& b = vertices[1];
125  const Vector& c = vertices[2];
126 
127  Vector u = b - a;
128  Vector v = c - a;
129  Vector w = p - a;
130  Vector n = u.cross(v);
131  // Barycentric coordinates of the projection P′of P onto T:
132  // γ=[(u×w)⋅n]/n²
133  float oneOver4ASquared = 1.0 / n.dot(n);
134 
135  const float gamma = u.cross(w).dot(n) * oneOver4ASquared;
136  // β=[(w×v)⋅n]/n²
137  const float beta = w.cross(v).dot(n) * oneOver4ASquared;
138  const float alpha = 1 - gamma - beta;
139 
140  barycentric_coords = { alpha, beta, gamma };
141  dist = n.dot(w) / n.length();
142 
143  const float EPSILON = 0.01;
144  // The point P′ lies inside T if:
145  return ((0 - EPSILON <= alpha) && (alpha <= 1 + EPSILON) && (0 - EPSILON <= beta) && (beta <= 1 + EPSILON) &&
146  (0 - EPSILON <= gamma) && (gamma <= 1 + EPSILON));
147 }
148 
149 std_msgs::ColorRGBA color(const float& r, const float& g, const float& b, const float& a)
150 {
151  std_msgs::ColorRGBA color;
152  color.r = r;
153  color.g = g;
154  color.b = b;
155  color.a = a;
156  return color;
157 }
158 
159 bool barycentricCoords(const Vector& p, const Vector& v0, const Vector& v1, const Vector& v2, float& u, float& v,
160  float& w)
161 {
162  // compute plane's normal
163  Vector v0v1 = v1 - v0;
164  Vector v0v2 = v2 - v0;
165 
166  // no need to normalize
167  Vector N = v0v1.cross(v0v2); // N
168  float denom = N.dot(N);
169 
170  // Step 2: inside-outside test
171  Vector C; // vector perpendicular to triangle's plane
172 
173  // edge 0
174  Vector edge0 = v1 - v0;
175  Vector vp0 = p - v0;
176  C = edge0.cross(vp0);
177  if (N.dot(C) < 0)
178  return false; // P is on the right side
179 
180  // edge 1
181  Vector edge1 = v2 - v1;
182  Vector vp1 = p - v1;
183  C = edge1.cross(vp1);
184  if ((u = N.dot(C)) < 0)
185  return false; // P is on the right side
186 
187  // edge 2
188  Vector edge2 = v0 - v2;
189  Vector vp2 = p - v2;
190  C = edge2.cross(vp2);
191  if ((v = N.dot(C)) < 0)
192  return false; // P is on the right side;
193 
194  u /= denom;
195  v /= denom;
196  w = 1 - u - v;
197 
198  return true;
199 }
200 
201 std_msgs::ColorRGBA getRainbowColor(const float value)
202 {
203  if (!std::isfinite(value))
204  return std_msgs::ColorRGBA();
205  std_msgs::ColorRGBA color;
206  getRainbowColor(value, color.r, color.g, color.b);
207  color.a = 1;
208  return color;
209 }
210 
211 void getRainbowColor(float value, float& r, float& g, float& b)
212 {
213  value = std::min(value, 1.0f);
214  value = std::max(value, 0.0f);
215 
216  float h = value * 5.0f + 1.0f;
217  int i = floor(h);
218  float f = h - i;
219  if (!(i & 1))
220  f = 1 - f; // if i is even
221  float n = 1 - f;
222 
223  if (i <= 1)
224  r = n, g = 0, b = 1;
225  else if (i == 2)
226  r = 0, g = n, b = 1;
227  else if (i == 3)
228  r = 0, g = 1, b = n;
229  else if (i == 4)
230  r = n, g = 1, b = 0;
231  else if (i >= 5)
232  r = 1, g = n, b = 0;
233 }
234 
235 mesh_map::Normal poseToDirectionVector(const geometry_msgs::PoseStamped& pose, const tf2::Vector3& axis)
236 {
238  fromMsg(pose, transform);
239  tf2::Vector3 v = transform.getBasis() * axis;
240  return mesh_map::Normal(v.x(), v.y(), v.z());
241 }
242 
243 
244 mesh_map::Vector poseToPositionVector(const geometry_msgs::PoseStamped& pose)
245 {
246  return mesh_map::Vector(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z);
247 }
248 
249 } /* namespace mesh_map */
min
int min(int a, int b)
lvr2::BaseVector::length
CoordT length() const
lvr2::BaseVector< float >
transform
mesh_map
Definition: abstract_layer.h:47
fromMsg
void fromMsg(const A &, B &b)
lvr2::AttributeMap
tf2::Transform::setRotation
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
mesh_map::color
std_msgs::ColorRGBA color(const float &r, const float &g, const float &b, const float &a=1.0)
Function to build std_msgs color instances.
Definition: util.cpp:149
tf2::Quaternion::normalize
Quaternion & normalize()
tf2::Stamped
p
SharedPointer p
Vector3.h
lvr2::BaseVector::x
CoordT x
lvr2::BaseVector::cross
BaseVector< CoordT > cross(const BaseVector &other) const
f
f
mesh_map::Vector
lvr2::BaseVector< float > Vector
use vectors with datatype folat
Definition: abstract_layer.h:49
lvr2::Normal< float >
tf2::Transform::setOrigin
TF2SIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
lvr2::BaseVector::y
CoordT y
tf2::Transform::setBasis
TF2SIMD_FORCE_INLINE void setBasis(const Matrix3x3 &basis)
EPSILON
#define EPSILON
mesh_map::projectedBarycentricCoords
bool projectedBarycentricCoords(const Vector &p, const std::array< Vector, 3 > &vertices, std::array< float, 3 > &barycentric_coords, float &dist)
Computes projected barycentric coordinates and whether the query point lies inside or outside the giv...
Definition: util.cpp:120
mesh_map::inTriangle
bool inTriangle(const Vector &p, const Vector &v0, const Vector &v1, const Vector &v2, const float &max_dist, const float &epsilon)
Computes whether a points lies inside or outside a triangle with respect to a maximum distance while ...
Definition: util.cpp:100
tf2::Transform
tf2::Transform::getRotation
Quaternion getRotation() const
mesh_map::poseToPositionVector
mesh_map::Vector poseToPositionVector(const geometry_msgs::PoseStamped &pose)
Definition: util.cpp:244
mesh_map::getMinMax
void getMinMax(const lvr2::VertexMap< float > &map, float &min, float &max)
Function to compute the minimum and maximum of a cost layer.
Definition: util.cpp:47
mesh_map::poseToDirectionVector
mesh_map::Normal poseToDirectionVector(const geometry_msgs::PoseStamped &pose, const tf2::Vector3 &axis=tf2::Vector3(1, 0, 0))
Definition: util.cpp:235
lvr2::BaseVector::z
CoordT z
mesh_map::projectVectorOntoPlane
Vector projectVectorOntoPlane(const Vector &vec, const Vector &ref, const Normal &normal)
Projects a vector / point onto a plane, which is defined by the reference vector and the normal vecto...
Definition: util.cpp:108
lvr2::BaseVector::dot
CoordT dot(const BaseVector &other) const
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
mesh_map::toVector
Vector toVector(const geometry_msgs::Point &point)
Converts a ROS geometry_msgs/Point message to a lvr2 vector.
Definition: util.cpp:62
mesh_map::Normal
lvr2::Normal< float > Normal
use normals with datatype float
Definition: abstract_layer.h:52
mesh_map::getRainbowColor
std_msgs::ColorRGBA getRainbowColor(const float value)
map value to color on color rainbow
Definition: util.cpp:201
mesh_map::calculatePoseFromPosition
geometry_msgs::Pose calculatePoseFromPosition(const Vector &current, const Vector &next, const Normal &normal)
Calculates a geometry_msgs/Pose message from two positions and a normal vector.
Definition: util.cpp:86
tf2::Matrix3x3
mesh_map::calculatePoseFromDirection
geometry_msgs::Pose calculatePoseFromDirection(const Vector &position, const Vector &direction, const Normal &normal)
Definition: util.cpp:67
mesh_map::barycentricCoords
bool barycentricCoords(const Vector &p, const Vector &v0, const Vector &v1, const Vector &v2, float &u, float &v, float &w)
Computes the barycentric coordinates u, v,q of a query point p onto the triangle v0,...
Definition: util.cpp:159
util.h
Matrix3x3.h
Transform.h


mesh_map
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:45