Go to the documentation of this file.
38 #ifndef MESH_MAP__UTIL_H
39 #define MESH_MAP__UTIL_H
41 #include <geometry_msgs/Point.h>
42 #include <geometry_msgs/Pose.h>
43 #include <geometry_msgs/PoseStamped.h>
48 #include <std_msgs/ColorRGBA.h>
69 std_msgs::ColorRGBA
color(
const float& r,
const float& g,
const float& b,
const float& a = 1.0);
134 const float& epsilon);
145 std::array<float, 3>& barycentric_coords,
float& dist);
168 template <
typename T>
170 const std::array<float, 3>& barycentric_coords)
172 return vertex_properties[0] * barycentric_coords[0] + vertex_properties[1] * barycentric_coords[1] +
173 vertex_properties[2] * barycentric_coords[2];
184 template <
typename T>
187 const std::array<float, 3>& barycentric_coords)
189 const std::array<T, 3>
values = { attribute_map[vertices[0]], attribute_map[vertices[1]],
190 attribute_map[vertices[2]] };
192 return linearCombineBarycentricCoords<T>(
values, barycentric_coords);
217 const geometry_msgs::PoseStamped& pose,
218 const tf2::Vector3& axis=tf2::Vector3(1,0,0));
227 const geometry_msgs::PoseStamped& pose);
231 #endif // MESH_MAP__UTIL_H
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.
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.
lvr2::BaseVector< float > Vector
use vectors with datatype folat
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...
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 ...
mesh_map::Vector poseToPositionVector(const geometry_msgs::PoseStamped &pose)
void getMinMax(const lvr2::VertexMap< float > &map, float &min, float &max)
Function to compute the minimum and maximum of a cost layer.
mesh_map::Normal poseToDirectionVector(const geometry_msgs::PoseStamped &pose, const tf2::Vector3 &axis=tf2::Vector3(1, 0, 0))
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...
Vector toVector(const geometry_msgs::Point &point)
Converts a ROS geometry_msgs/Point message to a lvr2 vector.
lvr2::Normal< float > Normal
use normals with datatype float
std_msgs::ColorRGBA getRainbowColor(const float value)
map value to color on color rainbow
geometry_msgs::Pose calculatePoseFromPosition(const Vector ¤t, const Vector &next, const Normal &normal)
Calculates a geometry_msgs/Pose message from two positions and a normal vector.
geometry_msgs::Pose calculatePoseFromDirection(const Vector &position, const Vector &direction, const Normal &normal)
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,...
mesh_map
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:45