Classes | Typedefs | Functions | Variables
mesh_map Namespace Reference

Classes

class  AbstractLayer
 
class  MeshMap
 
struct  NanoFlannMeshAdaptor
 

Typedefs

using HDF5MeshIO = lvr2::Hdf5IO< lvr2::hdf5features::ArrayIO, lvr2::hdf5features::ChannelIO, lvr2::hdf5features::VariantChannelIO, lvr2::hdf5features::MeshIO >
 
typedef lvr2::Normal< float > Normal
 use normals with datatype float More...
 
typedef std::function< void(const std::string &)> notify_func
 
typedef lvr2::BaseVector< float > Vector
 use vectors with datatype folat More...
 

Functions

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, v1, v2. More...
 
geometry_msgs::Pose calculatePoseFromDirection (const Vector &position, const Vector &direction, const Normal &normal)
 
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. More...
 
geometry_msgs::Pose calculatePoseFromPosition (const Vector &current, const Vector &next, const Normal &normal, float &cost)
 Calculates a geometry_msgs/Pose message from two positions and a normal vector. More...
 
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. More...
 
void getMinMax (const lvr2::VertexMap< float > &map, float &min, float &max)
 Function to compute the minimum and maximum of a cost layer. More...
 
std_msgs::ColorRGBA getRainbowColor (const float value)
 map value to color on color rainbow More...
 
void getRainbowColor (float value, float &r, float &g, float &b)
 map value to color on color rainbow More...
 
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 using an epsilon. More...
 
template<typename T >
linearCombineBarycentricCoords (const std::array< lvr2::VertexHandle, 3 > &vertices, const lvr2::VertexMap< T > &attribute_map, const std::array< float, 3 > &barycentric_coords)
 Computes a linear combination of vertex properties and the barycentric coordinates. More...
 
template<typename 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. More...
 
mesh_map::Normal poseToDirectionVector (const geometry_msgs::PoseStamped &pose, const tf2::Vector3 &axis=tf2::Vector3(1, 0, 0))
 
mesh_map::Vector poseToPositionVector (const geometry_msgs::PoseStamped &pose)
 
bool projectedBarycentricCoords (const Vector &p, const std::array< Vector, 3 > &vertices, std::array< float, 3 > &barycentric_coords)
 
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 given triangle. More...
 
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 vector. More...
 
Vector toVector (const geometry_msgs::Point &point)
 Converts a ROS geometry_msgs/Point message to a lvr2 vector. More...
 

Variables

constexpr float kEpsilon = 1e-8
 

Typedef Documentation

◆ HDF5MeshIO

Definition at line 63 of file mesh_map.cpp.

◆ Normal

typedef lvr2::Normal< float > mesh_map::Normal

use normals with datatype float

Definition at line 52 of file abstract_layer.h.

◆ notify_func

typedef std::function<void(const std::string&)> mesh_map::notify_func

Definition at line 54 of file abstract_layer.h.

◆ Vector

use vectors with datatype folat

Definition at line 49 of file abstract_layer.h.

Function Documentation

◆ barycentricCoords()

bool mesh_map::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, v1, v2.

Parameters
pThe query point
v0First vertex of the triangle
v1Second vertex of the triangle
v2Third vertex of the triangle
uFirst barycentric coordinate
vSecond barycentric coordinate
wThird barycentric coordinate
Returns
true if the query point lies inside the triangle

Definition at line 159 of file util.cpp.

◆ calculatePoseFromDirection()

geometry_msgs::Pose mesh_map::calculatePoseFromDirection ( const Vector position,
const Vector direction,
const Normal normal 
)

Computes a geometry_msgs/Pose message from a position, direction and normal vector

Parameters
positionThe position vector
directionThe direction vector
normalThe normal vector / z-axis
Returns
The converted pose message, in the right-hand / ROS coordinate system

Definition at line 67 of file util.cpp.

◆ calculatePoseFromPosition() [1/2]

geometry_msgs::Pose mesh_map::calculatePoseFromPosition ( const Vector current,
const Vector next,
const Normal normal 
)

Calculates a geometry_msgs/Pose message from two positions and a normal vector.

Parameters
currentThe position vector
nextThe vector in which the x-axis points to
normalThe normal vector / z-axis
Returns
The converted pose message, in the right-hand / ROS coordinate system

Definition at line 86 of file util.cpp.

◆ calculatePoseFromPosition() [2/2]

geometry_msgs::Pose mesh_map::calculatePoseFromPosition ( const Vector current,
const Vector next,
const Normal normal,
float &  cost 
)

Calculates a geometry_msgs/Pose message from two positions and a normal vector.

Parameters
currentThe position vector
nextThe vector in which the x-axis points to
normalThe normal vector / z-axis
costThe distance between "current" and "next"
Returns
The converted pose message, in the right-hand / ROS coordinate system

Definition at line 92 of file util.cpp.

◆ color()

std_msgs::ColorRGBA mesh_map::color ( const float &  r,
const float &  g,
const float &  b,
const float &  a = 1.0 
)

Function to build std_msgs color instances.

Parameters
rred, value between 0 and 1
ggreen, value between 0 and 1
bblue, value between 0 and 1
aalpha (optional, default is 1.0)
Returns
std_msgs/ColorRGBA message

Definition at line 149 of file util.cpp.

◆ getMinMax()

void mesh_map::getMinMax ( const lvr2::VertexMap< float > &  map,
float &  min,
float &  max 
)

Function to compute the minimum and maximum of a cost layer.

Parameters
mapThe cost layer or vertex float map to evaluate
minThe computed minimum
maxThe computed maximum

Definition at line 47 of file util.cpp.

◆ getRainbowColor() [1/2]

std_msgs::ColorRGBA mesh_map::getRainbowColor ( const float  value)

map value to color on color rainbow

Parameters
valuevalue in range from 0 to 1
Returns
color message

Definition at line 201 of file util.cpp.

◆ getRainbowColor() [2/2]

void mesh_map::getRainbowColor ( float  value,
float &  r,
float &  g,
float &  b 
)

map value to color on color rainbow

Parameters
valuevalue in range from 0 to 1
[out]rresulting red value
[out]gresulting green value
[out]bresultning blue value

Definition at line 211 of file util.cpp.

◆ inTriangle()

bool mesh_map::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 using an epsilon.

Parameters
pThe query point
v0First vertex of the triangle
v1Second vertex of the triangle
v2Third vertex of the triangle
max_distThe point's maximum distance to the triangle plane
epsilonThe epsilon used for the inside / outside check
Returns
true if the point lies inside the triangle

Definition at line 100 of file util.cpp.

◆ linearCombineBarycentricCoords() [1/2]

template<typename T >
T mesh_map::linearCombineBarycentricCoords ( const std::array< lvr2::VertexHandle, 3 > &  vertices,
const lvr2::VertexMap< T > &  attribute_map,
const std::array< float, 3 > &  barycentric_coords 
)

Computes a linear combination of vertex properties and the barycentric coordinates.

Template Parameters
TThe value to combine with barycentric coordinates, it must support the star/*-operator
Parameters
verticesThe three vertex handles of a triangle
attribute_mapAn attribute map to access with the given vertex handles
barycentric_coordsThe barycentric coordinates
Returns
The linear combined value, e.g. a vector, or cost value

Definition at line 185 of file util.h.

◆ linearCombineBarycentricCoords() [2/2]

template<typename T >
T mesh_map::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.

Template Parameters
TThe value to combine with barycentric coordinates, it must support the star/*-operator
Parameters
vertex_propertiesThe vertex properties of a triangle
barycentric_coordsThe barycentric coordinates
Returns
The linear combined value, e.g. a vector, or cost value

Definition at line 169 of file util.h.

◆ poseToDirectionVector()

mesh_map::Normal mesh_map::poseToDirectionVector ( const geometry_msgs::PoseStamped &  pose,
const tf2::Vector3 axis = tf2::Vector3(1,0,0) 
)

Converts the orientation of a geometry_msgs/PoseStamped message to a direction vector

Parameters
posethe pose to convert
Returns
direction normal vector

Definition at line 235 of file util.cpp.

◆ poseToPositionVector()

mesh_map::Vector mesh_map::poseToPositionVector ( const geometry_msgs::PoseStamped &  pose)

Converts the position of a geometry_msgs/PoseStamped message to a position vector

Parameters
posethe pose to convert
Returns
position vector

Definition at line 244 of file util.cpp.

◆ projectedBarycentricCoords() [1/2]

bool mesh_map::projectedBarycentricCoords ( const Vector p,
const std::array< Vector, 3 > &  vertices,
std::array< float, 3 > &  barycentric_coords 
)

Definition at line 113 of file util.cpp.

◆ projectedBarycentricCoords() [2/2]

bool mesh_map::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 given triangle.

Parameters
pThe query point
verticesThe three triangle vertices
barycentric_coordsThe computed barycentric coordinates
distThe distance from the plane to the point
Returns
true if the point lies inside or outside the triangle

Definition at line 120 of file util.cpp.

◆ projectVectorOntoPlane()

Vector mesh_map::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 vector.

Parameters
vecThe point which should be projected onto the plane
refThe plane's reference vector
normalThe plane's normal vector
Returns
The projected vector

Definition at line 108 of file util.cpp.

◆ toVector()

Vector mesh_map::toVector ( const geometry_msgs::Point point)

Converts a ROS geometry_msgs/Point message to a lvr2 vector.

Parameters
pointThe point message to convert
Returns
The point converted to a lvr2 vector

Definition at line 62 of file util.cpp.

Variable Documentation

◆ kEpsilon

constexpr float mesh_map::kEpsilon = 1e-8
constexpr

Definition at line 1100 of file mesh_map.cpp.



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