|  | 
| 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.  More... 
 | 
|  | 
| geometry_msgs::Pose | mesh_map::calculatePoseFromDirection (const Vector &position, const Vector &direction, const Normal &normal) | 
|  | 
| geometry_msgs::Pose | mesh_map::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 | mesh_map::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 | mesh_map::color (const float &r, const float &g, const float &b, const float &a=1.0) | 
|  | Function to build std_msgs color instances.  More... 
 | 
|  | 
| void | mesh_map::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 | mesh_map::getRainbowColor (const float value) | 
|  | map value to color on color rainbow  More... 
 | 
|  | 
| void | mesh_map::getRainbowColor (float value, float &r, float &g, float &b) | 
|  | map value to color on color rainbow  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| 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) | 
|  | 
| 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.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| Vector | mesh_map::toVector (const geometry_msgs::Point &point) | 
|  | Converts a ROS geometry_msgs/Point message to a lvr2 vector.  More... 
 | 
|  |