mesh_map.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
37 
38 #ifndef MESH_MAP__MESH_MAP_H
39 #define MESH_MAP__MESH_MAP_H
40 
41 #include <atomic>
42 #include <dynamic_reconfigure/server.h>
43 #include <geometry_msgs/Point.h>
45 #include <lvr2/io/HDF5IO.hpp>
46 #include <mesh_map/MeshMapConfig.h>
48 #include <mesh_msgs/MeshVertexCosts.h>
49 #include <mesh_msgs/MeshVertexColors.h>
50 #include <mutex>
51 #include <pluginlib/class_loader.h>
52 #include <std_msgs/ColorRGBA.h>
53 #include <tf2_ros/buffer.h>
54 #include <tuple>
55 #include "nanoflann.hpp"
56 #include "nanoflann_mesh_adaptor.h"
57 
58 namespace mesh_map
59 {
60 class MeshMap
61 {
62 public:
64 
66 
71  bool readMap();
72 
77  bool loadLayerPlugins();
78 
83  bool initLayerPlugins();
84 
91 
99  bool inTriangle(const Vector& pos, const lvr2::FaceHandle& face, const float& dist);
100 
107  lvr2::OptionalFaceHandle getContainingFace(Vector& position, const float& max_dist);
108 
115  boost::optional<std::tuple<lvr2::FaceHandle, std::array<mesh_map::Vector, 3>,
116  std::array<float, 3>>> searchContainingFace(Vector& position, const float& max_dist);
117 
121  void reconfigureCallback(mesh_map::MeshMapConfig& config, uint32_t level);
122 
126  void combineVertexCosts();
127 
133  void findContours(std::vector<std::vector<lvr2::VertexHandle>>& contours, int min_contour_size);
134 
140  void publishVertexCosts(const lvr2::VertexMap<float>& costs, const std::string& name);
141 
145  void publishVertexColors();
146 
150  void publishCostLayers();
151 
161  bool projectedBarycentricCoords(const Vector& p, const lvr2::FaceHandle& triangle,
162  std::array<float, 3>& barycentric_coords, float& dist);
163 
173  bool barycentricCoords(const Vector& p, const lvr2::FaceHandle& triangle, float& u, float& v, float& w);
174 
179  void layerChanged(const std::string& layer_name);
180 
187  void findLethalByContours(const int& min_contour_size, std::set<lvr2::VertexHandle>& lethals);
188 
192  const std::string getGlobalFrameID();
193 
197  inline bool isLethal(const lvr2::VertexHandle& vH);
198 
202  inline const geometry_msgs::Point toPoint(const Vector& vec);
203 
212  const std::array<lvr2::VertexHandle, 3>& vertices,
213  const std::array<float, 3>& barycentric_coords);
214 
222  float costAtPosition(const lvr2::DenseVertexMap<float>& costs, const std::array<lvr2::VertexHandle, 3>& vertices,
223  const std::array<float, 3>& barycentric_coords);
224 
231  float costAtPosition(const std::array<lvr2::VertexHandle, 3>& vertices,
232  const std::array<float, 3>& barycentric_coords);
233 
247  bool rayTriangleIntersect(const Vector& orig, const Vector& dir, const Vector& v0, const Vector& v1, const Vector& v2,
248  float& t, float& u, float& v, Vector& p);
249 
255  bool resetLayers();
256 
261  {
262  return vector_map;
263  };
264 
269  {
270  return *mesh_ptr;
271  }
272 
277  {
278  return vertex_costs;
279  }
280 
284  const std::string& mapFrame()
285  {
286  return global_frame;
287  }
288 
293  {
294  return face_normals;
295  }
296 
301  {
302  return vertex_normals;
303  }
304 
309  {
310  return edge_weights;
311  }
312 
317  {
318  return edge_distances;
319  }
320 
330  boost::optional<std::tuple<lvr2::FaceHandle, std::array<Vector, 3>, std::array<float, 3>>>
331  searchNeighbourFaces(const Vector& pos, const lvr2::FaceHandle& face,
332  const float& max_radius, const float& max_dist);
333 
343  bool meshAhead(Vector& vec, lvr2::FaceHandle& face, const float& step_width);
344 
349 
356  void publishDebugPoint(const Vector pos, const std_msgs::ColorRGBA& color, const std::string& name);
357 
364  void publishDebugFace(const lvr2::FaceHandle& face_handle, const std_msgs::ColorRGBA& color, const std::string& name);
365 
372  void publishVectorField(const std::string& name, const lvr2::DenseVertexMap<lvr2::BaseVector<float>>& vector_map,
373  const bool publish_face_vectors = false);
374 
383  void publishVectorField(const std::string& name, const lvr2::DenseVertexMap<lvr2::BaseVector<float>>& vector_map,
384  const lvr2::DenseVertexMap<float>& values,
385  const std::function<float(float)>& cost_function = {},
386  const bool publish_face_vectors = false);
387 
392 
396  mesh_map::AbstractLayer::Ptr layer(const std::string& layer_name);
397 
398  std::shared_ptr<lvr2::AttributeMeshIOBase> mesh_io_ptr;
399  std::shared_ptr<lvr2::HalfEdgeMesh<Vector>> mesh_ptr;
400 
402 
403 private:
406 
408  std::map<std::string, mesh_map::AbstractLayer::Ptr> layer_names;
409 
411  std::vector<std::pair<std::string, mesh_map::AbstractLayer::Ptr>> layers;
412 
414  std::map<std::string, std::set<lvr2::VertexHandle>> lethal_indices;
415 
417  std::set<lvr2::VertexHandle> lethals;
418 
420  std::string global_frame;
421 
423  std::string srv_url;
424 
426  std::string srv_username;
427 
429  std::string srv_password;
430 
431  std::string mesh_layer;
432 
437  float bb_min_x;
438  float bb_min_y;
439  float bb_min_z;
440  float bb_max_x;
441  float bb_max_y;
442  float bb_max_z;
443 
444  std::string mesh_file;
445  std::string mesh_part;
446 
449 
452 
455 
458 
461 
464 
467 
470 
473 
476 
479 
482 
484  dynamic_reconfigure::Server<mesh_map::MeshMapConfig>::CallbackType config_callback;
485 
488 
491 
493  MeshMapConfig config;
494 
497 
500 
502  std::string uuid_str;
503 
505  std::mutex layer_mtx;
506 
511 
513  std::unique_ptr<NanoFlannMeshAdaptor> adaptor_ptr;
514 
516  std::unique_ptr<KDTree> kd_tree_ptr;
517 };
518 
519 } /* namespace mesh_map */
520 
521 #endif // MESH_NAVIGATION__MESH_MAP_H
mesh_map::MeshMap::tf_buffer
tf2_ros::Buffer & tf_buffer
transformation buffer
Definition: mesh_map.h:499
mesh_map::MeshMap::publishDebugFace
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.
Definition: mesh_map.cpp:673
mesh_map::MeshMap::loadLayerPlugins
bool loadLayerPlugins()
Loads all configures layer plugins.
Definition: mesh_map.cpp:267
mesh_map::MeshMap::Ptr
boost::shared_ptr< MeshMap > Ptr
Definition: mesh_map.h:63
mesh_map::MeshMap::directionAtPosition
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)
Definition: mesh_map.cpp:600
mesh_map::MeshMap::lethals
std::set< lvr2::VertexHandle > lethals
all impassable vertices
Definition: mesh_map.h:417
mesh_map::MeshMap::mesh
const lvr2::HalfEdgeMesh< Vector > & mesh()
Returns the stored mesh.
Definition: mesh_map.h:268
nanoflann::L2_Simple_Adaptor
Definition: nanoflann.hpp:423
mesh_map::MeshMap::vertex_costs_pub
ros::Publisher vertex_costs_pub
publisher for vertex costs
Definition: mesh_map.h:466
ros::Publisher
lvr2::BaseVector< float >
mesh_map::MeshMap::vertexCosts
const lvr2::DenseVertexMap< float > & vertexCosts()
Returns the stored combined costs.
Definition: mesh_map.h:276
mesh_map::MeshMap::config
MeshMapConfig config
current mesh map configuration
Definition: mesh_map.h:493
mesh_map::MeshMap::mapFrame
const std::string & mapFrame()
Returns the map frame / coordinate system id.
Definition: mesh_map.h:284
class_loader.h
boost::shared_ptr
mesh_map::MeshMap::combineVertexCosts
void combineVertexCosts()
A method which combines all layer costs with the respective weightings.
Definition: mesh_map.cpp:417
mesh_map::MeshMap::max_roughness
float max_roughness
Definition: mesh_map.h:434
mesh_map::MeshMap::invalid
lvr2::DenseVertexMap< bool > invalid
Definition: mesh_map.h:401
mesh_map
Definition: abstract_layer.h:47
lvr2::FaceHandle
mesh_map::MeshMap::faceNormals
const lvr2::DenseFaceMap< Normal > & faceNormals()
Returns the mesh's triangle normals.
Definition: mesh_map.h:292
mesh_map::MeshMap::mesh_part
std::string mesh_part
Definition: mesh_map.h:445
mesh_map::MeshMap::rayTriangleIntersect
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)
Definition: mesh_map.cpp:1120
mesh_map::MeshMap::face_normals
lvr2::DenseFaceMap< Normal > face_normals
triangle normals
Definition: mesh_map.h:460
lvr2::AttributeMap
mesh_map::MeshMap::mesh_layer
std::string mesh_layer
Definition: mesh_map.h:431
mesh_map::MeshMap::edge_weights
lvr2::DenseEdgeMap< float > edge_weights
edge weights
Definition: mesh_map.h:457
mesh_map::MeshMap::srv_username
std::string srv_username
login username to connect to the server
Definition: mesh_map.h:426
lvr2::OptionalVertexHandle
mesh_map::MeshMap::edge_distances
lvr2::DenseEdgeMap< float > edge_distances
vertex distance for each edge
Definition: mesh_map.h:454
mesh_map::MeshMap::min_height_diff
float min_height_diff
Definition: mesh_map.h:435
mesh_map::color
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.
Definition: util.cpp:149
mesh_map::MeshMap::bb_max_x
float bb_max_x
Definition: mesh_map.h:440
mesh_map::MeshMap::resetLayers
bool resetLayers()
Resets all layers.
Definition: mesh_map.cpp:1180
mesh_map::MeshMap::layer_mtx
std::mutex layer_mtx
layer mutex to handle simultaneous layer changes
Definition: mesh_map.h:505
buffer.h
mesh_map::MeshMap::mesh_geometry_pub
ros::Publisher mesh_geometry_pub
publisher for the mesh geometry
Definition: mesh_map.h:472
mesh_map::MeshMap::marker_pub
ros::Publisher marker_pub
publisher for the debug markers
Definition: mesh_map.h:475
mesh_map::MeshMap::lethal_indices
std::map< std::string, std::set< lvr2::VertexHandle > > lethal_indices
each layer maps to a set of impassable indices
Definition: mesh_map.h:414
mesh_map::MeshMap::bb_min_y
float bb_min_y
Definition: mesh_map.h:438
mesh_map::MeshMap::layers
std::vector< std::pair< std::string, mesh_map::AbstractLayer::Ptr > > layers
vector of name and layer instances
Definition: mesh_map.h:411
mesh_map::MeshMap::adaptor_ptr
std::unique_ptr< NanoFlannMeshAdaptor > adaptor_ptr
k-d tree nano flann mesh adaptor to access mesh data
Definition: mesh_map.h:513
mesh_map::MeshMap::toPoint
const geometry_msgs::Point toPoint(const Vector &vec)
Converts a vector to a ROS geometry_msgs/Point message.
Definition: mesh_map.cpp:1091
mesh_map::MeshMap::searchNeighbourFaces
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)
Definition: mesh_map.cpp:919
mesh_map::MeshMap::getContainingFace
lvr2::OptionalFaceHandle getContainingFace(Vector &position, const float &max_dist)
Searches for a triangle which contains the given position with respect to the maximum distance.
Definition: mesh_map.cpp:1029
HDF5IO.hpp
mesh_map::MeshMap::KDTree
nanoflann::KDTreeSingleIndexAdaptor< nanoflann::L2_Simple_Adaptor< float, NanoFlannMeshAdaptor >, NanoFlannMeshAdaptor, 3 > KDTree
k-d tree type for 3D with a custom mesh adaptor
Definition: mesh_map.h:510
mesh_map::MeshMap::vertex_costs
lvr2::DenseVertexMap< float > vertex_costs
combined layer costs
Definition: mesh_map.h:448
BaseVector.hpp
mesh_map::MeshMap::publishVectorField
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.
Definition: mesh_map.cpp:703
mesh_map::MeshMap::kd_tree_ptr
std::unique_ptr< KDTree > kd_tree_ptr
k-d tree to query mesh vertices in logarithmic time
Definition: mesh_map.h:516
mesh_map::NanoFlannMeshAdaptor
Definition: nanoflann_mesh_adaptor.h:45
lvr2::VectorMap
mesh_map::MeshMap::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< mesh_map::MeshMapConfig > > reconfigure_server_ptr
shared pointer to dynamic reconfigure server
Definition: mesh_map.h:481
nanoflann::KDTreeSingleIndexAdaptor
mesh_map::MeshMap::uuid_str
std::string uuid_str
uuid for the load mesh map
Definition: mesh_map.h:502
mesh_map::MeshMap::getNearestVertexHandle
lvr2::OptionalVertexHandle getNearestVertexHandle(const mesh_map::Vector &pos)
Return and optional vertex handle of to the closest vertex to the given position.
Definition: mesh_map.cpp:1082
mesh_map::MeshMap::vector_map
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
stored vector map to share between planner and controller
Definition: mesh_map.h:451
mesh_map::MeshMap::bb_max_y
float bb_max_y
Definition: mesh_map.h:441
mesh_map::MeshMap::MeshMap
MeshMap(tf2_ros::Buffer &tf)
Definition: mesh_map.cpp:65
mesh_map::MeshMap::srv_password
std::string srv_password
login password to connect to the server
Definition: mesh_map.h:429
mesh_map::MeshMap::vertexNormals
const lvr2::DenseVertexMap< Normal > & vertexNormals()
Returns the mesh's vertex normals.
Definition: mesh_map.h:300
mesh_map::MeshMap::mesh_file
std::string mesh_file
Definition: mesh_map.h:444
mesh_map::MeshMap::initLayerPlugins
bool initLayerPlugins()
Initialized all loaded layer plugins.
Definition: mesh_map.cpp:384
mesh_map::MeshMap::mesh_ptr
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
Definition: mesh_map.h:399
lvr2::OptionalFaceHandle
mesh_map::MeshMap::inTriangle
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...
Definition: mesh_map.cpp:911
mesh_map::MeshMap::first_config
bool first_config
first reconfigure call
Definition: mesh_map.h:487
nanoflann.hpp
lvr2::VertexHandle
mesh_map::MeshMap::private_nh
ros::NodeHandle private_nh
private node handle within the mesh map namespace
Definition: mesh_map.h:496
mesh_map::MeshMap::layer
mesh_map::AbstractLayer::Ptr layer(const std::string &layer_name)
returns a shared pointer to the specified layer
Definition: mesh_map.cpp:1109
tf2_ros::Buffer
mesh_map::MeshMap::min_roughness
float min_roughness
Definition: mesh_map.h:433
abstract_layer.h
pluginlib::ClassLoader< mesh_map::AbstractLayer >
mesh_map::MeshMap::barycentricCoords
bool barycentricCoords(const Vector &p, const lvr2::FaceHandle &triangle, float &u, float &v, float &w)
Definition: mesh_map.cpp:1114
mesh_map::MeshMap::projectedBarycentricCoords
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....
Definition: mesh_map.cpp:1102
mesh_map::MeshMap::mesh_io_ptr
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
Definition: mesh_map.h:398
mesh_map::MeshMap::publishCombinedVectorField
void publishCombinedVectorField()
Publishes the vector field as visualisation_msgs/Marker.
Definition: mesh_map.cpp:710
mesh_map::MeshMap::bb_min_x
float bb_min_x
Definition: mesh_map.h:437
mesh_map::MeshMap::map_loaded
bool map_loaded
indicates whether the map has been loaded
Definition: mesh_map.h:490
mesh_map::MeshMap::publishCostLayers
void publishCostLayers()
Publishes all layer costs as mesh_msgs/VertexCosts.
Definition: mesh_map.cpp:1185
mesh_map::MeshMap::vertex_normals
lvr2::DenseVertexMap< Normal > vertex_normals
vertex normals
Definition: mesh_map.h:463
mesh_map::MeshMap::layer_names
std::map< std::string, mesh_map::AbstractLayer::Ptr > layer_names
mapping from name to layer instance
Definition: mesh_map.h:408
mesh_map::MeshMap::getGlobalFrameID
const std::string getGlobalFrameID()
Returns the global frame / coordinate system id string.
Definition: mesh_map.cpp:1250
mesh_map::MeshMap::searchContainingFace
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.
Definition: mesh_map.cpp:1038
mesh_map::MeshMap::costAtPosition
float costAtPosition(const lvr2::DenseVertexMap< float > &costs, const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords)
Definition: mesh_map.cpp:633
mesh_map::MeshMap::vector_field_pub
ros::Publisher vector_field_pub
publisher for the stored vector field
Definition: mesh_map.h:478
mesh_map::MeshMap::setVectorMap
void setVectorMap(lvr2::DenseVertexMap< mesh_map::Vector > &vector_map)
Stores the given vector map.
Definition: mesh_map.cpp:595
mesh_map::MeshMap::layerChanged
void layerChanged(const std::string &layer_name)
Callback function which is called from inside a layer plugin if cost values change.
Definition: mesh_map.cpp:335
mesh_map::MeshMap::max_height_diff
float max_height_diff
Definition: mesh_map.h:436
mesh_map::MeshMap::config_callback
dynamic_reconfigure::Server< mesh_map::MeshMapConfig >::CallbackType config_callback
dynamic reconfigure callback function binding
Definition: mesh_map.h:484
mesh_map::MeshMap
Definition: mesh_map.h:60
mesh_map::MeshMap::bb_max_z
float bb_max_z
Definition: mesh_map.h:442
mesh_map::MeshMap::isLethal
bool isLethal(const lvr2::VertexHandle &vH)
Checks if the given vertex handle corresponds to a lethal / not passable vertex.
mesh_map::MeshMap::edgeWeights
const lvr2::DenseEdgeMap< float > & edgeWeights()
Returns the mesh's edge weights.
Definition: mesh_map.h:308
mesh_map::MeshMap::findLethalByContours
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.
Definition: mesh_map.cpp:503
mesh_map::MeshMap::publishDebugPoint
void publishDebugPoint(const Vector pos, const std_msgs::ColorRGBA &color, const std::string &name)
Publishes a position as marker. Used for debug purposes.
Definition: mesh_map.cpp:649
mesh_map::MeshMap::bb_min_z
float bb_min_z
Definition: mesh_map.h:439
mesh_map::MeshMap::layer_loader
pluginlib::ClassLoader< mesh_map::AbstractLayer > layer_loader
plugin class loader for for the layer plugins
Definition: mesh_map.h:405
mesh_map::MeshMap::readMap
bool readMap()
Reads in the mesh geometry, normals and cost values and publishes all as mesh_msgs.
Definition: mesh_map.cpp:105
mesh_map::MeshMap::edgeDistances
const lvr2::DenseEdgeMap< float > & edgeDistances()
Returns the mesh's vertex distances.
Definition: mesh_map.h:316
mesh_map::MeshMap::getVectorMap
const lvr2::DenseVertexMap< mesh_map::Vector > & getVectorMap()
Returns the stored vector map.
Definition: mesh_map.h:260
mesh_map::MeshMap::vertex_colors_pub
ros::Publisher vertex_colors_pub
publisher for vertex colors
Definition: mesh_map.h:469
mesh_map::MeshMap::publishVertexColors
void publishVertexColors()
Definition: mesh_map.cpp:1202
mesh_map::MeshMap::reconfigureCallback
void reconfigureCallback(mesh_map::MeshMapConfig &config, uint32_t level)
reconfigure callback function which is called if a dynamic reconfiguration were triggered.
Definition: mesh_map.cpp:1229
mesh_map::MeshMap::srv_url
std::string srv_url
server url
Definition: mesh_map.h:423
mesh_map::MeshMap::meshAhead
bool meshAhead(Vector &vec, lvr2::FaceHandle &face, const float &step_width)
Definition: mesh_map.cpp:989
nanoflann_mesh_adaptor.h
ros::NodeHandle
mesh_map::MeshMap::findContours
void findContours(std::vector< std::vector< lvr2::VertexHandle >> &contours, int min_contour_size)
Computes contours.
Definition: mesh_map.cpp:515
lvr2::HalfEdgeMesh
mesh_map::MeshMap::publishVertexCosts
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.
Definition: mesh_map.cpp:1196
mesh_map::MeshMap::global_frame
std::string global_frame
global frame / coordinate system id
Definition: mesh_map.h:420


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