| 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 ¤t, 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 ¤t, 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 > | |
| 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 > | |
| 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 | 
| using mesh_map::HDF5MeshIO = typedef lvr2::Hdf5IO<lvr2::hdf5features::ArrayIO, lvr2::hdf5features::ChannelIO, lvr2::hdf5features::VariantChannelIO, lvr2::hdf5features::MeshIO> | 
Definition at line 63 of file mesh_map.cpp.
| typedef lvr2::Normal< float > mesh_map::Normal | 
use normals with datatype float
Definition at line 52 of file abstract_layer.h.
| typedef std::function<void(const std::string&)> mesh_map::notify_func | 
Definition at line 54 of file abstract_layer.h.
| typedef lvr2::BaseVector< float > mesh_map::Vector | 
use vectors with datatype folat
Definition at line 49 of file abstract_layer.h.
| 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.
| p | The query point | 
| v0 | First vertex of the triangle | 
| v1 | Second vertex of the triangle | 
| v2 | Third vertex of the triangle | 
| u | First barycentric coordinate | 
| v | Second barycentric coordinate | 
| w | Third barycentric coordinate | 
| 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
| position | The position vector | 
| direction | The direction vector | 
| normal | The normal vector / z-axis | 
| 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.
| current | The position vector | 
| next | The vector in which the x-axis points to | 
| normal | The normal vector / z-axis | 
| 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.
| current | The position vector | 
| next | The vector in which the x-axis points to | 
| normal | The normal vector / z-axis | 
| cost | The distance between "current" and "next" | 
| std_msgs::ColorRGBA mesh_map::color | ( | const float & | r, | 
| const float & | g, | ||
| const float & | b, | ||
| const float & | a = 1.0 | ||
| ) | 
| void mesh_map::getMinMax | ( | const lvr2::VertexMap< float > & | map, | 
| float & | min, | ||
| float & | max | ||
| ) | 
| std_msgs::ColorRGBA mesh_map::getRainbowColor | ( | const float | value | ) | 
| void mesh_map::getRainbowColor | ( | float | value, | 
| float & | r, | ||
| float & | g, | ||
| float & | b | ||
| ) | 
| 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.
| p | The query point | 
| v0 | First vertex of the triangle | 
| v1 | Second vertex of the triangle | 
| v2 | Third vertex of the triangle | 
| max_dist | The point's maximum distance to the triangle plane | 
| epsilon | The epsilon used for the inside / outside check | 
| 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.
| T | The value to combine with barycentric coordinates, it must support the star/*-operator | 
| vertices | The three vertex handles of a triangle | 
| attribute_map | An attribute map to access with the given vertex handles | 
| barycentric_coords | The barycentric coordinates | 
| 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.
| T | The value to combine with barycentric coordinates, it must support the star/*-operator | 
| vertex_properties | The vertex properties of a triangle | 
| barycentric_coords | The barycentric coordinates | 
| mesh_map::Normal mesh_map::poseToDirectionVector | ( | const geometry_msgs::PoseStamped & | pose, | 
| const tf2::Vector3 & | axis = tf2::Vector3(1,0,0) | ||
| ) | 
| mesh_map::Vector mesh_map::poseToPositionVector | ( | const geometry_msgs::PoseStamped & | pose | ) | 
| 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.
| p | The query point | 
| vertices | The three triangle vertices | 
| barycentric_coords | The computed barycentric coordinates | 
| dist | The distance from the plane to the point | 
| 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.
| vec | The point which should be projected onto the plane | 
| ref | The plane's reference vector | 
| normal | The plane's normal vector | 
| Vector mesh_map::toVector | ( | const geometry_msgs::Point & | point | ) | 
| 
 | constexpr | 
Definition at line 1100 of file mesh_map.cpp.