#include <mesh_map.h>
| Public Types | |
| typedef boost::shared_ptr< MeshMap > | Ptr | 
| Public Member Functions | |
| bool | barycentricCoords (const Vector &p, const lvr2::FaceHandle &triangle, float &u, float &v, float &w) | 
| void | combineVertexCosts () | 
| A method which combines all layer costs with the respective weightings.  More... | |
| float | costAtPosition (const lvr2::DenseVertexMap< float > &costs, const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords) | 
| float | costAtPosition (const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords) | 
| boost::optional< Vector > | directionAtPosition (const lvr2::VertexMap< lvr2::BaseVector< float >> &vector_map, const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords) | 
| const lvr2::DenseEdgeMap< float > & | edgeDistances () | 
| Returns the mesh's vertex distances.  More... | |
| const lvr2::DenseEdgeMap< float > & | edgeWeights () | 
| Returns the mesh's edge weights.  More... | |
| const lvr2::DenseFaceMap< Normal > & | faceNormals () | 
| Returns the mesh's triangle normals.  More... | |
| void | findContours (std::vector< std::vector< lvr2::VertexHandle >> &contours, int min_contour_size) | 
| Computes contours.  More... | |
| void | findLethalByContours (const int &min_contour_size, std::set< lvr2::VertexHandle > &lethals) | 
| Compute all contours and returns the corresponding vertices to use these as lethal vertices.  More... | |
| lvr2::OptionalFaceHandle | getContainingFace (Vector &position, const float &max_dist) | 
| Searches for a triangle which contains the given position with respect to the maximum distance.  More... | |
| const std::string | getGlobalFrameID () | 
| Returns the global frame / coordinate system id string.  More... | |
| lvr2::OptionalVertexHandle | getNearestVertexHandle (const mesh_map::Vector &pos) | 
| Return and optional vertex handle of to the closest vertex to the given position.  More... | |
| const lvr2::DenseVertexMap< mesh_map::Vector > & | getVectorMap () | 
| Returns the stored vector map.  More... | |
| bool | initLayerPlugins () | 
| Initialized all loaded layer plugins.  More... | |
| bool | inTriangle (const Vector &pos, const lvr2::FaceHandle &face, const float &dist) | 
| return true if the given position lies inside the triangle with respect to the given maximum distance.  More... | |
| bool | isLethal (const lvr2::VertexHandle &vH) | 
| Checks if the given vertex handle corresponds to a lethal / not passable vertex.  More... | |
| mesh_map::AbstractLayer::Ptr | layer (const std::string &layer_name) | 
| returns a shared pointer to the specified layer  More... | |
| void | layerChanged (const std::string &layer_name) | 
| Callback function which is called from inside a layer plugin if cost values change.  More... | |
| bool | loadLayerPlugins () | 
| Loads all configures layer plugins.  More... | |
| const std::string & | mapFrame () | 
| Returns the map frame / coordinate system id.  More... | |
| const lvr2::HalfEdgeMesh< Vector > & | mesh () | 
| Returns the stored mesh.  More... | |
| bool | meshAhead (Vector &vec, lvr2::FaceHandle &face, const float &step_width) | 
| MeshMap (tf2_ros::Buffer &tf) | |
| bool | projectedBarycentricCoords (const Vector &p, const lvr2::FaceHandle &triangle, std::array< float, 3 > &barycentric_coords, float &dist) | 
| Computes the projected barycentric coordinates, it implements Heidrich's method See https://www.researchgate.net/publication/220494112_Computing_the_Barycentric_Coordinates_of_a_Projected_Point.  More... | |
| void | publishCombinedVectorField () | 
| Publishes the vector field as visualisation_msgs/Marker.  More... | |
| void | publishCostLayers () | 
| Publishes all layer costs as mesh_msgs/VertexCosts.  More... | |
| void | publishDebugFace (const lvr2::FaceHandle &face_handle, const std_msgs::ColorRGBA &color, const std::string &name) | 
| Publishes a triangle as marker. Used for debug purposes.  More... | |
| void | publishDebugPoint (const Vector pos, const std_msgs::ColorRGBA &color, const std::string &name) | 
| Publishes a position as marker. Used for debug purposes.  More... | |
| void | publishVectorField (const std::string &name, const lvr2::DenseVertexMap< lvr2::BaseVector< float >> &vector_map, const bool publish_face_vectors=false) | 
| Publishes a vector field as visualisation_msgs/Marker.  More... | |
| void | publishVectorField (const std::string &name, const lvr2::DenseVertexMap< lvr2::BaseVector< float >> &vector_map, const lvr2::DenseVertexMap< float > &values, const std::function< float(float)> &cost_function={}, const bool publish_face_vectors=false) | 
| Publishes a vector field as visualisation_msgs/Marker.  More... | |
| void | publishVertexColors () | 
| void | publishVertexCosts (const lvr2::VertexMap< float > &costs, const std::string &name) | 
| Publishes the given vertex map as mesh_msgs/VertexCosts, e.g. to visualize these.  More... | |
| bool | rayTriangleIntersect (const Vector &orig, const Vector &dir, const Vector &v0, const Vector &v1, const Vector &v2, float &t, float &u, float &v, Vector &p) | 
| bool | readMap () | 
| Reads in the mesh geometry, normals and cost values and publishes all as mesh_msgs.  More... | |
| void | reconfigureCallback (mesh_map::MeshMapConfig &config, uint32_t level) | 
| reconfigure callback function which is called if a dynamic reconfiguration were triggered.  More... | |
| bool | resetLayers () | 
| Resets all layers.  More... | |
| boost::optional< std::tuple< lvr2::FaceHandle, std::array< mesh_map::Vector, 3 >, std::array< float, 3 > > > | searchContainingFace (Vector &position, const float &max_dist) | 
| Searches for a triangle which contains the given position with respect to the maximum distance.  More... | |
| boost::optional< std::tuple< lvr2::FaceHandle, std::array< Vector, 3 >, std::array< float, 3 > > > | searchNeighbourFaces (const Vector &pos, const lvr2::FaceHandle &face, const float &max_radius, const float &max_dist) | 
| void | setVectorMap (lvr2::DenseVertexMap< mesh_map::Vector > &vector_map) | 
| Stores the given vector map.  More... | |
| const geometry_msgs::Point | toPoint (const Vector &vec) | 
| Converts a vector to a ROS geometry_msgs/Point message.  More... | |
| const lvr2::DenseVertexMap< float > & | vertexCosts () | 
| Returns the stored combined costs.  More... | |
| const lvr2::DenseVertexMap< Normal > & | vertexNormals () | 
| Returns the mesh's vertex normals.  More... | |
| Public Attributes | |
| lvr2::DenseVertexMap< bool > | invalid | 
| std::shared_ptr< lvr2::AttributeMeshIOBase > | mesh_io_ptr | 
| std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > | mesh_ptr | 
| Private Types | |
| typedef nanoflann::KDTreeSingleIndexAdaptor< nanoflann::L2_Simple_Adaptor< float, NanoFlannMeshAdaptor >, NanoFlannMeshAdaptor, 3 > | KDTree | 
| k-d tree type for 3D with a custom mesh adaptor  More... | |
| Private Attributes | |
| std::unique_ptr< NanoFlannMeshAdaptor > | adaptor_ptr | 
| k-d tree nano flann mesh adaptor to access mesh data  More... | |
| float | bb_max_x | 
| float | bb_max_y | 
| float | bb_max_z | 
| float | bb_min_x | 
| float | bb_min_y | 
| float | bb_min_z | 
| MeshMapConfig | config | 
| current mesh map configuration  More... | |
| dynamic_reconfigure::Server< mesh_map::MeshMapConfig >::CallbackType | config_callback | 
| dynamic reconfigure callback function binding  More... | |
| lvr2::DenseEdgeMap< float > | edge_distances | 
| vertex distance for each edge  More... | |
| lvr2::DenseEdgeMap< float > | edge_weights | 
| edge weights  More... | |
| lvr2::DenseFaceMap< Normal > | face_normals | 
| triangle normals  More... | |
| bool | first_config | 
| first reconfigure call  More... | |
| std::string | global_frame | 
| global frame / coordinate system id  More... | |
| std::unique_ptr< KDTree > | kd_tree_ptr | 
| k-d tree to query mesh vertices in logarithmic time  More... | |
| pluginlib::ClassLoader< mesh_map::AbstractLayer > | layer_loader | 
| plugin class loader for for the layer plugins  More... | |
| std::mutex | layer_mtx | 
| layer mutex to handle simultaneous layer changes  More... | |
| std::map< std::string, mesh_map::AbstractLayer::Ptr > | layer_names | 
| mapping from name to layer instance  More... | |
| std::vector< std::pair< std::string, mesh_map::AbstractLayer::Ptr > > | layers | 
| vector of name and layer instances  More... | |
| std::map< std::string, std::set< lvr2::VertexHandle > > | lethal_indices | 
| each layer maps to a set of impassable indices  More... | |
| std::set< lvr2::VertexHandle > | lethals | 
| all impassable vertices  More... | |
| bool | map_loaded | 
| indicates whether the map has been loaded  More... | |
| ros::Publisher | marker_pub | 
| publisher for the debug markers  More... | |
| float | max_height_diff | 
| float | max_roughness | 
| std::string | mesh_file | 
| ros::Publisher | mesh_geometry_pub | 
| publisher for the mesh geometry  More... | |
| std::string | mesh_layer | 
| std::string | mesh_part | 
| float | min_height_diff | 
| float | min_roughness | 
| ros::NodeHandle | private_nh | 
| private node handle within the mesh map namespace  More... | |
| boost::shared_ptr< dynamic_reconfigure::Server< mesh_map::MeshMapConfig > > | reconfigure_server_ptr | 
| shared pointer to dynamic reconfigure server  More... | |
| std::string | srv_password | 
| login password to connect to the server  More... | |
| std::string | srv_url | 
| server url  More... | |
| std::string | srv_username | 
| login username to connect to the server  More... | |
| tf2_ros::Buffer & | tf_buffer | 
| transformation buffer  More... | |
| std::string | uuid_str | 
| uuid for the load mesh map  More... | |
| ros::Publisher | vector_field_pub | 
| publisher for the stored vector field  More... | |
| lvr2::DenseVertexMap< mesh_map::Vector > | vector_map | 
| stored vector map to share between planner and controller  More... | |
| ros::Publisher | vertex_colors_pub | 
| publisher for vertex colors  More... | |
| lvr2::DenseVertexMap< float > | vertex_costs | 
| combined layer costs  More... | |
| ros::Publisher | vertex_costs_pub | 
| publisher for vertex costs  More... | |
| lvr2::DenseVertexMap< Normal > | vertex_normals | 
| vertex normals  More... | |
Definition at line 60 of file mesh_map.h.
| 
 | private | 
k-d tree type for 3D with a custom mesh adaptor
Definition at line 510 of file mesh_map.h.
Definition at line 63 of file mesh_map.h.
| mesh_map::MeshMap::MeshMap | ( | tf2_ros::Buffer & | tf | ) | 
Definition at line 65 of file mesh_map.cpp.
| bool mesh_map::MeshMap::barycentricCoords | ( | const Vector & | p, | 
| const lvr2::FaceHandle & | triangle, | ||
| float & | u, | ||
| float & | v, | ||
| float & | w | ||
| ) | 
Computes barycentric coordinates of the given query position and the corresponding triangle
| p | The query position | 
| triangle | The corresponding triangle | 
| u | The barycentric coordinate if the first vertex | 
| v | The barycentric coordinate if the second vertex | 
| w | The barycentric coordinate if the third vertex | 
Definition at line 1114 of file mesh_map.cpp.
| void mesh_map::MeshMap::combineVertexCosts | ( | ) | 
A method which combines all layer costs with the respective weightings.
Definition at line 417 of file mesh_map.cpp.
| float mesh_map::MeshMap::costAtPosition | ( | const lvr2::DenseVertexMap< float > & | costs, | 
| const std::array< lvr2::VertexHandle, 3 > & | vertices, | ||
| const std::array< float, 3 > & | barycentric_coords | ||
| ) | 
Computes the cost value for the given triangle's vertices and barycentric coordinates while using the given cost map
| costs | The cost map to use | 
| vertices | The triangles vertices | 
| barycentric_coords | The barycentric coordinates of the query position. | 
Definition at line 633 of file mesh_map.cpp.
| float mesh_map::MeshMap::costAtPosition | ( | const std::array< lvr2::VertexHandle, 3 > & | vertices, | 
| const std::array< float, 3 > & | barycentric_coords | ||
| ) | 
Computes the cost value for the given triangle's vertices and barycentric coordinates while using the combined cost map
| vertices | The triangles vertices | 
| barycentric_coords | The barycentric coordinates of the query position. | 
Definition at line 627 of file mesh_map.cpp.
| boost::optional< Vector > mesh_map::MeshMap::directionAtPosition | ( | const lvr2::VertexMap< lvr2::BaseVector< float >> & | vector_map, | 
| const std::array< lvr2::VertexHandle, 3 > & | vertices, | ||
| const std::array< float, 3 > & | barycentric_coords | ||
| ) | 
Computes the direction vector for the given triangle's vertices and barycentric coordinates while using the given vector map
| vector_map | The vector map to use | 
| vertices | The triangles vertices | 
| barycentric_coords | The barycentric coordinates of the query position. | 
Definition at line 600 of file mesh_map.cpp.
| 
 | inline | 
Returns the mesh's vertex distances.
Definition at line 316 of file mesh_map.h.
| 
 | inline | 
Returns the mesh's edge weights.
Definition at line 308 of file mesh_map.h.
| 
 | inline | 
Returns the mesh's triangle normals.
Definition at line 292 of file mesh_map.h.
| void mesh_map::MeshMap::findContours | ( | std::vector< std::vector< lvr2::VertexHandle >> & | contours, | 
| int | min_contour_size | ||
| ) | 
Computes contours.
| contours | the vector to bo filled with contours | 
| min_contour_size | The minimum contour size, i.e. the number of vertices per contour. | 
Definition at line 515 of file mesh_map.cpp.
| void mesh_map::MeshMap::findLethalByContours | ( | const int & | min_contour_size, | 
| std::set< lvr2::VertexHandle > & | lethals | ||
| ) | 
Compute all contours and returns the corresponding vertices to use these as lethal vertices.
| min_contour_size | The minimum contour size, i.e. the number of vertices per contour. | 
| min_contour_size | |
| lethals | the vector which is filled with contour vertices | 
Definition at line 503 of file mesh_map.cpp.
| lvr2::OptionalFaceHandle mesh_map::MeshMap::getContainingFace | ( | Vector & | position, | 
| const float & | max_dist | ||
| ) | 
Searches for a triangle which contains the given position with respect to the maximum distance.
| position | The query position | 
| max_dist | The maximum distance to the triangle | 
Definition at line 1029 of file mesh_map.cpp.
| const std::string mesh_map::MeshMap::getGlobalFrameID | ( | ) | 
Returns the global frame / coordinate system id string.
Definition at line 1250 of file mesh_map.cpp.
| lvr2::OptionalVertexHandle mesh_map::MeshMap::getNearestVertexHandle | ( | const mesh_map::Vector & | pos | ) | 
Return and optional vertex handle of to the closest vertex to the given position.
| pos | the search position | 
Definition at line 1082 of file mesh_map.cpp.
| 
 | inline | 
Returns the stored vector map.
Definition at line 260 of file mesh_map.h.
| bool mesh_map::MeshMap::initLayerPlugins | ( | ) | 
Initialized all loaded layer plugins.
Definition at line 384 of file mesh_map.cpp.
| bool mesh_map::MeshMap::inTriangle | ( | const Vector & | pos, | 
| const lvr2::FaceHandle & | face, | ||
| const float & | dist | ||
| ) | 
return true if the given position lies inside the triangle with respect to the given maximum distance.
| pos | The query position | 
| face | The triangle to check for | 
| dist | The maximum distance to the triangle | 
Definition at line 911 of file mesh_map.cpp.
| 
 | inline | 
Checks if the given vertex handle corresponds to a lethal / not passable vertex.
| mesh_map::AbstractLayer::Ptr mesh_map::MeshMap::layer | ( | const std::string & | layer_name | ) | 
returns a shared pointer to the specified layer
Definition at line 1109 of file mesh_map.cpp.
| void mesh_map::MeshMap::layerChanged | ( | const std::string & | layer_name | ) | 
Callback function which is called from inside a layer plugin if cost values change.
| layer_name | the name of the layer. | 
Definition at line 335 of file mesh_map.cpp.
| bool mesh_map::MeshMap::loadLayerPlugins | ( | ) | 
Loads all configures layer plugins.
Definition at line 267 of file mesh_map.cpp.
| 
 | inline | 
Returns the map frame / coordinate system id.
Definition at line 284 of file mesh_map.h.
| 
 | inline | 
Returns the stored mesh.
Definition at line 268 of file mesh_map.h.
| bool mesh_map::MeshMap::meshAhead | ( | mesh_map::Vector & | pos, | 
| lvr2::FaceHandle & | face, | ||
| const float & | step_width | ||
| ) | 
Finds the next position given a position vector and its corresponding face handle by following the direction For: look ahead when using mesh gradient
| vec | direction vector from which the next step vector is calculated | 
| face | face of the direction vector | 
| step_width | The step length to go ahead on the mesh surface | 
Definition at line 989 of file mesh_map.cpp.
| bool mesh_map::MeshMap::projectedBarycentricCoords | ( | const Vector & | p, | 
| const lvr2::FaceHandle & | triangle, | ||
| std::array< float, 3 > & | barycentric_coords, | ||
| float & | dist | ||
| ) | 
Computes the projected barycentric coordinates, it implements Heidrich's method See https://www.researchgate.net/publication/220494112_Computing_the_Barycentric_Coordinates_of_a_Projected_Point.
| p | the query position | 
| triangle | the corresponding triangle | 
| barycentric_coords | The array will be filled with the barycentric coordinates | 
| dist | The distance if the query position to the triangle | 
Definition at line 1102 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishCombinedVectorField | ( | ) | 
Publishes the vector field as visualisation_msgs/Marker.
Definition at line 710 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishCostLayers | ( | ) | 
Publishes all layer costs as mesh_msgs/VertexCosts.
Definition at line 1185 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishDebugFace | ( | const lvr2::FaceHandle & | face_handle, | 
| const std_msgs::ColorRGBA & | color, | ||
| const std::string & | name | ||
| ) | 
Publishes a triangle as marker. Used for debug purposes.
| face_handle | The face handle for the triangle | 
| color | The marker's color | 
| name | The marker's name | 
Definition at line 673 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishDebugPoint | ( | const Vector | pos, | 
| const std_msgs::ColorRGBA & | color, | ||
| const std::string & | name | ||
| ) | 
Publishes a position as marker. Used for debug purposes.
| pos | The position to publish as marker | 
| color | The marker's color | 
| name | The marker's name | 
Definition at line 649 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishVectorField | ( | const std::string & | name, | 
| const lvr2::DenseVertexMap< lvr2::BaseVector< float >> & | vector_map, | ||
| const bool | publish_face_vectors = false | ||
| ) | 
Publishes a vector field as visualisation_msgs/Marker.
| name | The marker's name | 
| vector_map | The vector field to publish | 
| publish_face_vectors | Enables to publish an additional vertex for the triangle's center. | 
Definition at line 703 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishVectorField | ( | const std::string & | name, | 
| const lvr2::DenseVertexMap< lvr2::BaseVector< float >> & | vector_map, | ||
| const lvr2::DenseVertexMap< float > & | values, | ||
| const std::function< float(float)> & | cost_function = {}, | ||
| const bool | publish_face_vectors = false | ||
| ) | 
Publishes a vector field as visualisation_msgs/Marker.
| name | The marker's name | 
| vector_map | The vector field to publish | 
| values | The vertex cost values | 
| cost_function | A cost function to compute costs inside a triangle | 
| publish_face_vectors | Enables to publish an additional vertex for the triangle's center. | 
Definition at line 758 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishVertexColors | ( | ) | 
@briefP Publishes the vertex colors if these exists.
Definition at line 1202 of file mesh_map.cpp.
| void mesh_map::MeshMap::publishVertexCosts | ( | const lvr2::VertexMap< float > & | costs, | 
| const std::string & | name | ||
| ) | 
Publishes the given vertex map as mesh_msgs/VertexCosts, e.g. to visualize these.
| costs | The cost map to publish | 
| name | The name of the cost map | 
Definition at line 1196 of file mesh_map.cpp.
| bool mesh_map::MeshMap::rayTriangleIntersect | ( | const Vector & | orig, | 
| const Vector & | dir, | ||
| const Vector & | v0, | ||
| const Vector & | v1, | ||
| const Vector & | v2, | ||
| float & | t, | ||
| float & | u, | ||
| float & | v, | ||
| Vector & | p | ||
| ) | 
Computes the barycentric coordinates of the ray intersection point for the given ray
| orig | The ray origin | 
| dir | The ray direction | 
| v0 | The triangle's first vertex | 
| v1 | The triangle's second vertex | 
| v2 | The triangle's third vertex | 
| t | The signed distance to the triangle | 
| u | The first barycentric coordinate | 
| v | The second barycentric coordinate | 
| p | The thrid barycentric coordinate | 
Definition at line 1120 of file mesh_map.cpp.
| bool mesh_map::MeshMap::readMap | ( | ) | 
Reads in the mesh geometry, normals and cost values and publishes all as mesh_msgs.
Definition at line 105 of file mesh_map.cpp.
| void mesh_map::MeshMap::reconfigureCallback | ( | mesh_map::MeshMapConfig & | config, | 
| uint32_t | level | ||
| ) | 
reconfigure callback function which is called if a dynamic reconfiguration were triggered.
Definition at line 1229 of file mesh_map.cpp.
| bool mesh_map::MeshMap::resetLayers | ( | ) | 
Resets all layers.
Definition at line 1180 of file mesh_map.cpp.
| boost::optional< std::tuple< lvr2::FaceHandle, std::array< mesh_map::Vector, 3 >, std::array< float, 3 > > > mesh_map::MeshMap::searchContainingFace | ( | Vector & | position, | 
| const float & | max_dist | ||
| ) | 
Searches for a triangle which contains the given position with respect to the maximum distance.
| position | The query position | 
| max_dist | The maximum distance to the triangle | 
Definition at line 1038 of file mesh_map.cpp.
| boost::optional< std::tuple< lvr2::FaceHandle, std::array< Vector, 3 >, std::array< float, 3 > > > mesh_map::MeshMap::searchNeighbourFaces | ( | const Vector & | pos, | 
| const lvr2::FaceHandle & | face, | ||
| const float & | max_radius, | ||
| const float & | max_dist | ||
| ) | 
Searches in the surrounding triangles for the triangle in which the given position lies.
| pose_vec | Vector of the position which searched for | 
| face | Face handle from which search begins | 
| max_radius | The radius in which the controller searches for a consecutive face | 
| max_dist | The maximum distance to the given face vertices | 
Definition at line 919 of file mesh_map.cpp.
| void mesh_map::MeshMap::setVectorMap | ( | lvr2::DenseVertexMap< mesh_map::Vector > & | vector_map | ) | 
Stores the given vector map.
Definition at line 595 of file mesh_map.cpp.
| 
 | inline | 
Converts a vector to a ROS geometry_msgs/Point message.
Definition at line 1091 of file mesh_map.cpp.
| 
 | inline | 
Returns the stored combined costs.
Definition at line 276 of file mesh_map.h.
| 
 | inline | 
Returns the mesh's vertex normals.
Definition at line 300 of file mesh_map.h.
| 
 | private | 
k-d tree nano flann mesh adaptor to access mesh data
Definition at line 513 of file mesh_map.h.
| 
 | private | 
Definition at line 440 of file mesh_map.h.
| 
 | private | 
Definition at line 441 of file mesh_map.h.
| 
 | private | 
Definition at line 442 of file mesh_map.h.
| 
 | private | 
Definition at line 437 of file mesh_map.h.
| 
 | private | 
Definition at line 438 of file mesh_map.h.
| 
 | private | 
Definition at line 439 of file mesh_map.h.
| 
 | private | 
current mesh map configuration
Definition at line 493 of file mesh_map.h.
| 
 | private | 
dynamic reconfigure callback function binding
Definition at line 484 of file mesh_map.h.
| 
 | private | 
vertex distance for each edge
Definition at line 454 of file mesh_map.h.
| 
 | private | 
edge weights
Definition at line 457 of file mesh_map.h.
| 
 | private | 
triangle normals
Definition at line 460 of file mesh_map.h.
| 
 | private | 
first reconfigure call
Definition at line 487 of file mesh_map.h.
| 
 | private | 
global frame / coordinate system id
Definition at line 420 of file mesh_map.h.
| lvr2::DenseVertexMap<bool> mesh_map::MeshMap::invalid | 
Definition at line 401 of file mesh_map.h.
| 
 | private | 
k-d tree to query mesh vertices in logarithmic time
Definition at line 516 of file mesh_map.h.
| 
 | private | 
plugin class loader for for the layer plugins
Definition at line 405 of file mesh_map.h.
| 
 | private | 
layer mutex to handle simultaneous layer changes
Definition at line 505 of file mesh_map.h.
| 
 | private | 
mapping from name to layer instance
Definition at line 408 of file mesh_map.h.
| 
 | private | 
vector of name and layer instances
Definition at line 411 of file mesh_map.h.
| 
 | private | 
each layer maps to a set of impassable indices
Definition at line 414 of file mesh_map.h.
| 
 | private | 
all impassable vertices
Definition at line 417 of file mesh_map.h.
| 
 | private | 
indicates whether the map has been loaded
Definition at line 490 of file mesh_map.h.
| 
 | private | 
publisher for the debug markers
Definition at line 475 of file mesh_map.h.
| 
 | private | 
Definition at line 436 of file mesh_map.h.
| 
 | private | 
Definition at line 434 of file mesh_map.h.
| 
 | private | 
Definition at line 444 of file mesh_map.h.
| 
 | private | 
publisher for the mesh geometry
Definition at line 472 of file mesh_map.h.
| std::shared_ptr<lvr2::AttributeMeshIOBase> mesh_map::MeshMap::mesh_io_ptr | 
Definition at line 398 of file mesh_map.h.
| 
 | private | 
Definition at line 431 of file mesh_map.h.
| 
 | private | 
Definition at line 445 of file mesh_map.h.
| std::shared_ptr<lvr2::HalfEdgeMesh<Vector> > mesh_map::MeshMap::mesh_ptr | 
Definition at line 399 of file mesh_map.h.
| 
 | private | 
Definition at line 435 of file mesh_map.h.
| 
 | private | 
Definition at line 433 of file mesh_map.h.
| 
 | private | 
private node handle within the mesh map namespace
Definition at line 496 of file mesh_map.h.
| 
 | private | 
shared pointer to dynamic reconfigure server
Definition at line 481 of file mesh_map.h.
| 
 | private | 
login password to connect to the server
Definition at line 429 of file mesh_map.h.
| 
 | private | 
server url
Definition at line 423 of file mesh_map.h.
| 
 | private | 
login username to connect to the server
Definition at line 426 of file mesh_map.h.
| 
 | private | 
transformation buffer
Definition at line 499 of file mesh_map.h.
| 
 | private | 
uuid for the load mesh map
Definition at line 502 of file mesh_map.h.
| 
 | private | 
publisher for the stored vector field
Definition at line 478 of file mesh_map.h.
| 
 | private | 
stored vector map to share between planner and controller
Definition at line 451 of file mesh_map.h.
| 
 | private | 
publisher for vertex colors
Definition at line 469 of file mesh_map.h.
| 
 | private | 
combined layer costs
Definition at line 448 of file mesh_map.h.
| 
 | private | 
publisher for vertex costs
Definition at line 466 of file mesh_map.h.
| 
 | private | 
vertex normals
Definition at line 463 of file mesh_map.h.