util.h
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 #ifndef MESH_MAP__UTIL_H
39 #define MESH_MAP__UTIL_H
40 
41 #include <geometry_msgs/Point.h>
42 #include <geometry_msgs/Pose.h>
43 #include <geometry_msgs/PoseStamped.h>
47 #include <lvr2/geometry/Normal.hpp>
48 #include <std_msgs/ColorRGBA.h>
49 #include <tf2/LinearMath/Vector3.h>
50 
51 namespace mesh_map
52 {
53 
56 
59 
60 
69 std_msgs::ColorRGBA color(const float& r, const float& g, const float& b, const float& a = 1.0);
70 
77 void getMinMax(const lvr2::VertexMap<float>& map, float& min, float& max);
78 
84 Vector toVector(const geometry_msgs::Point& point);
85 
93 geometry_msgs::Pose calculatePoseFromDirection(const Vector& position, const Vector& direction, const Normal& normal);
94 
102 geometry_msgs::Pose calculatePoseFromPosition(const Vector& current, const Vector& next, const Normal& normal);
103 
112 geometry_msgs::Pose calculatePoseFromPosition(const Vector& current, const Vector& next, const Normal& normal,
113  float& cost);
121 Vector projectVectorOntoPlane(const Vector& vec, const Vector& ref, const Normal& normal);
122 
133 bool inTriangle(const Vector& p, const Vector& v0, const Vector& v1, const Vector& v2, const float& max_dist,
134  const float& epsilon);
135 
144 bool projectedBarycentricCoords(const Vector& p, const std::array<Vector, 3>& vertices,
145  std::array<float, 3>& barycentric_coords, float& dist);
146 
158 bool barycentricCoords(const Vector& p, const Vector& v0, const Vector& v1, const Vector& v2, float& u, float& v,
159  float& w);
160 
168 template <typename T>
169 T linearCombineBarycentricCoords(const std::array<T, 3>& vertex_properties,
170  const std::array<float, 3>& barycentric_coords)
171 {
172  return vertex_properties[0] * barycentric_coords[0] + vertex_properties[1] * barycentric_coords[1] +
173  vertex_properties[2] * barycentric_coords[2];
174 }
175 
184 template <typename T>
185 T linearCombineBarycentricCoords(const std::array<lvr2::VertexHandle, 3>& vertices,
186  const lvr2::VertexMap<T>& attribute_map,
187  const std::array<float, 3>& barycentric_coords)
188 {
189  const std::array<T, 3> values = { attribute_map[vertices[0]], attribute_map[vertices[1]],
190  attribute_map[vertices[2]] };
191 
192  return linearCombineBarycentricCoords<T>(values, barycentric_coords);
193 }
194 
200 std_msgs::ColorRGBA getRainbowColor(const float value);
201 
209 void getRainbowColor(float value, float& r, float& g, float& b);
210 
217  const geometry_msgs::PoseStamped& pose,
218  const tf2::Vector3& axis=tf2::Vector3(1,0,0));
219 
220 
227  const geometry_msgs::PoseStamped& pose);
228 
229 } /* namespace mesh_map */
230 
231 #endif // MESH_MAP__UTIL_H
Handles.hpp
lvr2::BaseVector< float >
mesh_map
Definition: abstract_layer.h:47
lvr2::AttributeMap
mesh_map::linearCombineBarycentricCoords
T linearCombineBarycentricCoords(const std::array< T, 3 > &vertex_properties, const std::array< float, 3 > &barycentric_coords)
Computes a linear combination of vertex properties and the barycentric coordinates.
Definition: util.h:169
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
Vector3.h
mesh_map::Vector
lvr2::BaseVector< float > Vector
use vectors with datatype folat
Definition: abstract_layer.h:49
BaseVector.hpp
Normal
float4 Normal
AttrMaps.hpp
lvr2::Normal< float >
Normal.hpp
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
values
values
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
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
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
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


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