Public Types | Public Member Functions | Public Attributes | Private Types | Private Attributes | List of all members
mesh_map::MeshMap Class Reference

#include <mesh_map.h>

Public Types

typedef boost::shared_ptr< MeshMapPtr
 

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< VectordirectionAtPosition (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::AttributeMeshIOBasemesh_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< NanoFlannMeshAdaptoradaptor_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< Normalface_normals
 triangle normals More...
 
bool first_config
 first reconfigure call More...
 
std::string global_frame
 global frame / coordinate system id More...
 
std::unique_ptr< KDTreekd_tree_ptr
 k-d tree to query mesh vertices in logarithmic time More...
 
pluginlib::ClassLoader< mesh_map::AbstractLayerlayer_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::Ptrlayer_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::VertexHandlelethals
 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::Buffertf_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::Vectorvector_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< Normalvertex_normals
 vertex normals More...
 

Detailed Description

Definition at line 60 of file mesh_map.h.

Member Typedef Documentation

◆ KDTree

k-d tree type for 3D with a custom mesh adaptor

Definition at line 510 of file mesh_map.h.

◆ Ptr

Definition at line 63 of file mesh_map.h.

Constructor & Destructor Documentation

◆ MeshMap()

mesh_map::MeshMap::MeshMap ( tf2_ros::Buffer tf)

Definition at line 65 of file mesh_map.cpp.

Member Function Documentation

◆ barycentricCoords()

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

Parameters
pThe query position
triangleThe corresponding triangle
uThe barycentric coordinate if the first vertex
vThe barycentric coordinate if the second vertex
wThe barycentric coordinate if the third vertex
Returns
true if the query position lies inside the triangle

Definition at line 1114 of file mesh_map.cpp.

◆ combineVertexCosts()

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.

◆ costAtPosition() [1/2]

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

Parameters
costsThe cost map to use
verticesThe triangles vertices
barycentric_coordsThe barycentric coordinates of the query position.
Returns
A cost value for the given barycentric coordinates.

Definition at line 633 of file mesh_map.cpp.

◆ costAtPosition() [2/2]

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

Parameters
verticesThe triangles vertices
barycentric_coordsThe barycentric coordinates of the query position.
Returns
A cost value for the given barycentric coordinates.

Definition at line 627 of file mesh_map.cpp.

◆ directionAtPosition()

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

Parameters
vector_mapThe vector map to use
verticesThe triangles vertices
barycentric_coordsThe barycentric coordinates of the query position.
Returns
An optional vector of the computed direction. It is valid if a vector has been computed successfully.

Definition at line 600 of file mesh_map.cpp.

◆ edgeDistances()

const lvr2::DenseEdgeMap<float>& mesh_map::MeshMap::edgeDistances ( )
inline

Returns the mesh's vertex distances.

Definition at line 316 of file mesh_map.h.

◆ edgeWeights()

const lvr2::DenseEdgeMap<float>& mesh_map::MeshMap::edgeWeights ( )
inline

Returns the mesh's edge weights.

Definition at line 308 of file mesh_map.h.

◆ faceNormals()

const lvr2::DenseFaceMap<Normal>& mesh_map::MeshMap::faceNormals ( )
inline

Returns the mesh's triangle normals.

Definition at line 292 of file mesh_map.h.

◆ findContours()

void mesh_map::MeshMap::findContours ( std::vector< std::vector< lvr2::VertexHandle >> &  contours,
int  min_contour_size 
)

Computes contours.

Parameters
contoursthe vector to bo filled with contours
min_contour_sizeThe minimum contour size, i.e. the number of vertices per contour.

Definition at line 515 of file mesh_map.cpp.

◆ findLethalByContours()

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.

Parameters
min_contour_sizeThe minimum contour size, i.e. the number of vertices per contour.
min_contour_size
lethalsthe vector which is filled with contour vertices

Definition at line 503 of file mesh_map.cpp.

◆ getContainingFace()

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.

Parameters
positionThe query position
max_distThe maximum distance to the triangle
Returns
Optional face handle, the optional is valid if a corresponding triangle has been found.

Definition at line 1029 of file mesh_map.cpp.

◆ getGlobalFrameID()

const std::string mesh_map::MeshMap::getGlobalFrameID ( )

Returns the global frame / coordinate system id string.

Definition at line 1250 of file mesh_map.cpp.

◆ getNearestVertexHandle()

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.

Parameters
posthe search position
Returns

Definition at line 1082 of file mesh_map.cpp.

◆ getVectorMap()

const lvr2::DenseVertexMap<mesh_map::Vector>& mesh_map::MeshMap::getVectorMap ( )
inline

Returns the stored vector map.

Definition at line 260 of file mesh_map.h.

◆ initLayerPlugins()

bool mesh_map::MeshMap::initLayerPlugins ( )

Initialized all loaded layer plugins.

Returns
true if the loaded layer plugins have been initialized successfully.

Definition at line 384 of file mesh_map.cpp.

◆ inTriangle()

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.

Parameters
posThe query position
faceThe triangle to check for
distThe maximum distance to the triangle
Returns
true if the query position is inside the triangle within the maximum distance

Definition at line 911 of file mesh_map.cpp.

◆ isLethal()

bool mesh_map::MeshMap::isLethal ( const lvr2::VertexHandle vH)
inline

Checks if the given vertex handle corresponds to a lethal / not passable vertex.

◆ layer()

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.

◆ layerChanged()

void mesh_map::MeshMap::layerChanged ( const std::string &  layer_name)

Callback function which is called from inside a layer plugin if cost values change.

Parameters
layer_namethe name of the layer.

Definition at line 335 of file mesh_map.cpp.

◆ loadLayerPlugins()

bool mesh_map::MeshMap::loadLayerPlugins ( )

Loads all configures layer plugins.

Returns
true if the layer plugins have been load successfully.

Definition at line 267 of file mesh_map.cpp.

◆ mapFrame()

const std::string& mesh_map::MeshMap::mapFrame ( )
inline

Returns the map frame / coordinate system id.

Definition at line 284 of file mesh_map.h.

◆ mesh()

const lvr2::HalfEdgeMesh<Vector>& mesh_map::MeshMap::mesh ( )
inline

Returns the stored mesh.

Definition at line 268 of file mesh_map.h.

◆ meshAhead()

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

Parameters
vecdirection vector from which the next step vector is calculated
faceface of the direction vector
step_widthThe step length to go ahead on the mesh surface
Returns
new vector (also updates the ahead_face handle to correspond to the new vector)

Definition at line 989 of file mesh_map.cpp.

◆ projectedBarycentricCoords()

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.

Parameters
pthe query position
trianglethe corresponding triangle
barycentric_coordsThe array will be filled with the barycentric coordinates
distThe distance if the query position to the triangle
Returns
ture if the query position lies inside the triangle

Definition at line 1102 of file mesh_map.cpp.

◆ publishCombinedVectorField()

void mesh_map::MeshMap::publishCombinedVectorField ( )

Publishes the vector field as visualisation_msgs/Marker.

Definition at line 710 of file mesh_map.cpp.

◆ publishCostLayers()

void mesh_map::MeshMap::publishCostLayers ( )

Publishes all layer costs as mesh_msgs/VertexCosts.

Definition at line 1185 of file mesh_map.cpp.

◆ publishDebugFace()

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.

Parameters
face_handleThe face handle for the triangle
colorThe marker's color
nameThe marker's name

Definition at line 673 of file mesh_map.cpp.

◆ publishDebugPoint()

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.

Parameters
posThe position to publish as marker
colorThe marker's color
nameThe marker's name

Definition at line 649 of file mesh_map.cpp.

◆ publishVectorField() [1/2]

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.

Parameters
nameThe marker's name
vector_mapThe vector field to publish
publish_face_vectorsEnables to publish an additional vertex for the triangle's center.

Definition at line 703 of file mesh_map.cpp.

◆ publishVectorField() [2/2]

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.

Parameters
nameThe marker's name
vector_mapThe vector field to publish
valuesThe vertex cost values
cost_functionA cost function to compute costs inside a triangle
publish_face_vectorsEnables to publish an additional vertex for the triangle's center.

Definition at line 758 of file mesh_map.cpp.

◆ publishVertexColors()

void mesh_map::MeshMap::publishVertexColors ( )

@briefP Publishes the vertex colors if these exists.

Definition at line 1202 of file mesh_map.cpp.

◆ publishVertexCosts()

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.

Parameters
costsThe cost map to publish
nameThe name of the cost map

Definition at line 1196 of file mesh_map.cpp.

◆ rayTriangleIntersect()

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

Parameters
origThe ray origin
dirThe ray direction
v0The triangle's first vertex
v1The triangle's second vertex
v2The triangle's third vertex
tThe signed distance to the triangle
uThe first barycentric coordinate
vThe second barycentric coordinate
pThe thrid barycentric coordinate
Returns
True if the intersection point lies inside the triangle

Definition at line 1120 of file mesh_map.cpp.

◆ readMap()

bool mesh_map::MeshMap::readMap ( )

Reads in the mesh geometry, normals and cost values and publishes all as mesh_msgs.

Returns
true f the mesh and its attributes have been load successfully.

Definition at line 105 of file mesh_map.cpp.

◆ reconfigureCallback()

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.

◆ resetLayers()

bool mesh_map::MeshMap::resetLayers ( )

Resets all layers.

Todo:
implement
Returns
true if successfully reset

Definition at line 1180 of file mesh_map.cpp.

◆ searchContainingFace()

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.

Parameters
positionThe query position
max_distThe maximum distance to the triangle
Returns
optional tuple of the corresponding triangle, the triangle's vertices, and barycentric coordinates, if a corresponding triangle has been found.

Definition at line 1038 of file mesh_map.cpp.

◆ searchNeighbourFaces()

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.

Parameters
pose_vecVector of the position which searched for
faceFace handle from which search begins
max_radiusThe radius in which the controller searches for a consecutive face
max_distThe maximum distance to the given face vertices
Returns
Optional of (face handle, vertices, and barycentric coord) tuple

Definition at line 919 of file mesh_map.cpp.

◆ setVectorMap()

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.

◆ toPoint()

const geometry_msgs::Point mesh_map::MeshMap::toPoint ( const Vector vec)
inline

Converts a vector to a ROS geometry_msgs/Point message.

Definition at line 1091 of file mesh_map.cpp.

◆ vertexCosts()

const lvr2::DenseVertexMap<float>& mesh_map::MeshMap::vertexCosts ( )
inline

Returns the stored combined costs.

Definition at line 276 of file mesh_map.h.

◆ vertexNormals()

const lvr2::DenseVertexMap<Normal>& mesh_map::MeshMap::vertexNormals ( )
inline

Returns the mesh's vertex normals.

Definition at line 300 of file mesh_map.h.

Member Data Documentation

◆ adaptor_ptr

std::unique_ptr<NanoFlannMeshAdaptor> mesh_map::MeshMap::adaptor_ptr
private

k-d tree nano flann mesh adaptor to access mesh data

Definition at line 513 of file mesh_map.h.

◆ bb_max_x

float mesh_map::MeshMap::bb_max_x
private

Definition at line 440 of file mesh_map.h.

◆ bb_max_y

float mesh_map::MeshMap::bb_max_y
private

Definition at line 441 of file mesh_map.h.

◆ bb_max_z

float mesh_map::MeshMap::bb_max_z
private

Definition at line 442 of file mesh_map.h.

◆ bb_min_x

float mesh_map::MeshMap::bb_min_x
private

Definition at line 437 of file mesh_map.h.

◆ bb_min_y

float mesh_map::MeshMap::bb_min_y
private

Definition at line 438 of file mesh_map.h.

◆ bb_min_z

float mesh_map::MeshMap::bb_min_z
private

Definition at line 439 of file mesh_map.h.

◆ config

MeshMapConfig mesh_map::MeshMap::config
private

current mesh map configuration

Definition at line 493 of file mesh_map.h.

◆ config_callback

dynamic_reconfigure::Server<mesh_map::MeshMapConfig>::CallbackType mesh_map::MeshMap::config_callback
private

dynamic reconfigure callback function binding

Definition at line 484 of file mesh_map.h.

◆ edge_distances

lvr2::DenseEdgeMap<float> mesh_map::MeshMap::edge_distances
private

vertex distance for each edge

Definition at line 454 of file mesh_map.h.

◆ edge_weights

lvr2::DenseEdgeMap<float> mesh_map::MeshMap::edge_weights
private

edge weights

Definition at line 457 of file mesh_map.h.

◆ face_normals

lvr2::DenseFaceMap<Normal> mesh_map::MeshMap::face_normals
private

triangle normals

Definition at line 460 of file mesh_map.h.

◆ first_config

bool mesh_map::MeshMap::first_config
private

first reconfigure call

Definition at line 487 of file mesh_map.h.

◆ global_frame

std::string mesh_map::MeshMap::global_frame
private

global frame / coordinate system id

Definition at line 420 of file mesh_map.h.

◆ invalid

lvr2::DenseVertexMap<bool> mesh_map::MeshMap::invalid

Definition at line 401 of file mesh_map.h.

◆ kd_tree_ptr

std::unique_ptr<KDTree> mesh_map::MeshMap::kd_tree_ptr
private

k-d tree to query mesh vertices in logarithmic time

Definition at line 516 of file mesh_map.h.

◆ layer_loader

pluginlib::ClassLoader<mesh_map::AbstractLayer> mesh_map::MeshMap::layer_loader
private

plugin class loader for for the layer plugins

Definition at line 405 of file mesh_map.h.

◆ layer_mtx

std::mutex mesh_map::MeshMap::layer_mtx
private

layer mutex to handle simultaneous layer changes

Definition at line 505 of file mesh_map.h.

◆ layer_names

std::map<std::string, mesh_map::AbstractLayer::Ptr> mesh_map::MeshMap::layer_names
private

mapping from name to layer instance

Definition at line 408 of file mesh_map.h.

◆ layers

std::vector<std::pair<std::string, mesh_map::AbstractLayer::Ptr> > mesh_map::MeshMap::layers
private

vector of name and layer instances

Definition at line 411 of file mesh_map.h.

◆ lethal_indices

std::map<std::string, std::set<lvr2::VertexHandle> > mesh_map::MeshMap::lethal_indices
private

each layer maps to a set of impassable indices

Definition at line 414 of file mesh_map.h.

◆ lethals

std::set<lvr2::VertexHandle> mesh_map::MeshMap::lethals
private

all impassable vertices

Definition at line 417 of file mesh_map.h.

◆ map_loaded

bool mesh_map::MeshMap::map_loaded
private

indicates whether the map has been loaded

Definition at line 490 of file mesh_map.h.

◆ marker_pub

ros::Publisher mesh_map::MeshMap::marker_pub
private

publisher for the debug markers

Definition at line 475 of file mesh_map.h.

◆ max_height_diff

float mesh_map::MeshMap::max_height_diff
private

Definition at line 436 of file mesh_map.h.

◆ max_roughness

float mesh_map::MeshMap::max_roughness
private

Definition at line 434 of file mesh_map.h.

◆ mesh_file

std::string mesh_map::MeshMap::mesh_file
private

Definition at line 444 of file mesh_map.h.

◆ mesh_geometry_pub

ros::Publisher mesh_map::MeshMap::mesh_geometry_pub
private

publisher for the mesh geometry

Definition at line 472 of file mesh_map.h.

◆ mesh_io_ptr

std::shared_ptr<lvr2::AttributeMeshIOBase> mesh_map::MeshMap::mesh_io_ptr

Definition at line 398 of file mesh_map.h.

◆ mesh_layer

std::string mesh_map::MeshMap::mesh_layer
private

Definition at line 431 of file mesh_map.h.

◆ mesh_part

std::string mesh_map::MeshMap::mesh_part
private

Definition at line 445 of file mesh_map.h.

◆ mesh_ptr

std::shared_ptr<lvr2::HalfEdgeMesh<Vector> > mesh_map::MeshMap::mesh_ptr

Definition at line 399 of file mesh_map.h.

◆ min_height_diff

float mesh_map::MeshMap::min_height_diff
private

Definition at line 435 of file mesh_map.h.

◆ min_roughness

float mesh_map::MeshMap::min_roughness
private

Definition at line 433 of file mesh_map.h.

◆ private_nh

ros::NodeHandle mesh_map::MeshMap::private_nh
private

private node handle within the mesh map namespace

Definition at line 496 of file mesh_map.h.

◆ reconfigure_server_ptr

boost::shared_ptr<dynamic_reconfigure::Server<mesh_map::MeshMapConfig> > mesh_map::MeshMap::reconfigure_server_ptr
private

shared pointer to dynamic reconfigure server

Definition at line 481 of file mesh_map.h.

◆ srv_password

std::string mesh_map::MeshMap::srv_password
private

login password to connect to the server

Definition at line 429 of file mesh_map.h.

◆ srv_url

std::string mesh_map::MeshMap::srv_url
private

server url

Definition at line 423 of file mesh_map.h.

◆ srv_username

std::string mesh_map::MeshMap::srv_username
private

login username to connect to the server

Definition at line 426 of file mesh_map.h.

◆ tf_buffer

tf2_ros::Buffer& mesh_map::MeshMap::tf_buffer
private

transformation buffer

Definition at line 499 of file mesh_map.h.

◆ uuid_str

std::string mesh_map::MeshMap::uuid_str
private

uuid for the load mesh map

Definition at line 502 of file mesh_map.h.

◆ vector_field_pub

ros::Publisher mesh_map::MeshMap::vector_field_pub
private

publisher for the stored vector field

Definition at line 478 of file mesh_map.h.

◆ vector_map

lvr2::DenseVertexMap<mesh_map::Vector> mesh_map::MeshMap::vector_map
private

stored vector map to share between planner and controller

Definition at line 451 of file mesh_map.h.

◆ vertex_colors_pub

ros::Publisher mesh_map::MeshMap::vertex_colors_pub
private

publisher for vertex colors

Definition at line 469 of file mesh_map.h.

◆ vertex_costs

lvr2::DenseVertexMap<float> mesh_map::MeshMap::vertex_costs
private

combined layer costs

Definition at line 448 of file mesh_map.h.

◆ vertex_costs_pub

ros::Publisher mesh_map::MeshMap::vertex_costs_pub
private

publisher for vertex costs

Definition at line 466 of file mesh_map.h.

◆ vertex_normals

lvr2::DenseVertexMap<Normal> mesh_map::MeshMap::vertex_normals
private

vertex normals

Definition at line 463 of file mesh_map.h.


The documentation for this class was generated from the following files:


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