Go to the documentation of this file.
38 #ifndef MESH_MAP__MESH_MAP_H
39 #define MESH_MAP__MESH_MAP_H
42 #include <dynamic_reconfigure/server.h>
43 #include <geometry_msgs/Point.h>
46 #include <mesh_map/MeshMapConfig.h>
48 #include <mesh_msgs/MeshVertexCosts.h>
49 #include <mesh_msgs/MeshVertexColors.h>
52 #include <std_msgs/ColorRGBA.h>
115 boost::optional<std::tuple<lvr2::FaceHandle, std::array<mesh_map::Vector, 3>,
133 void findContours(std::vector<std::vector<lvr2::VertexHandle>>& contours,
int min_contour_size);
162 std::array<float, 3>& barycentric_coords,
float& dist);
202 inline const geometry_msgs::Point
toPoint(
const Vector& vec);
212 const std::array<lvr2::VertexHandle, 3>& vertices,
213 const std::array<float, 3>& barycentric_coords);
223 const std::array<float, 3>& barycentric_coords);
231 float costAtPosition(
const std::array<lvr2::VertexHandle, 3>& vertices,
232 const std::array<float, 3>& barycentric_coords);
248 float& t,
float& u,
float& v,
Vector& p);
330 boost::optional<std::tuple<lvr2::FaceHandle, std::array<Vector, 3>, std::array<float, 3>>>
332 const float& max_radius,
const float& max_dist);
373 const bool publish_face_vectors =
false);
385 const std::function<
float(
float)>& cost_function = {},
386 const bool publish_face_vectors =
false);
399 std::shared_ptr<lvr2::HalfEdgeMesh<Vector>>
mesh_ptr;
411 std::vector<std::pair<std::string, mesh_map::AbstractLayer::Ptr>>
layers;
521 #endif // MESH_NAVIGATION__MESH_MAP_H
tf2_ros::Buffer & tf_buffer
transformation buffer
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.
bool loadLayerPlugins()
Loads all configures layer plugins.
boost::shared_ptr< MeshMap > Ptr
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)
std::set< lvr2::VertexHandle > lethals
all impassable vertices
const lvr2::HalfEdgeMesh< Vector > & mesh()
Returns the stored mesh.
ros::Publisher vertex_costs_pub
publisher for vertex costs
const lvr2::DenseVertexMap< float > & vertexCosts()
Returns the stored combined costs.
MeshMapConfig config
current mesh map configuration
const std::string & mapFrame()
Returns the map frame / coordinate system id.
void combineVertexCosts()
A method which combines all layer costs with the respective weightings.
lvr2::DenseVertexMap< bool > invalid
const lvr2::DenseFaceMap< Normal > & faceNormals()
Returns the mesh's triangle normals.
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)
lvr2::DenseFaceMap< Normal > face_normals
triangle normals
lvr2::DenseEdgeMap< float > edge_weights
edge weights
std::string srv_username
login username to connect to the server
lvr2::DenseEdgeMap< float > edge_distances
vertex distance for each edge
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.
bool resetLayers()
Resets all layers.
std::mutex layer_mtx
layer mutex to handle simultaneous layer changes
ros::Publisher mesh_geometry_pub
publisher for the mesh geometry
ros::Publisher marker_pub
publisher for the debug markers
std::map< std::string, std::set< lvr2::VertexHandle > > lethal_indices
each layer maps to a set of impassable indices
std::vector< std::pair< std::string, mesh_map::AbstractLayer::Ptr > > layers
vector of name and layer instances
std::unique_ptr< NanoFlannMeshAdaptor > adaptor_ptr
k-d tree nano flann mesh adaptor to access mesh data
const geometry_msgs::Point toPoint(const Vector &vec)
Converts a vector to a ROS geometry_msgs/Point message.
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)
lvr2::OptionalFaceHandle getContainingFace(Vector &position, const float &max_dist)
Searches for a triangle which contains the given position with respect to the maximum distance.
nanoflann::KDTreeSingleIndexAdaptor< nanoflann::L2_Simple_Adaptor< float, NanoFlannMeshAdaptor >, NanoFlannMeshAdaptor, 3 > KDTree
k-d tree type for 3D with a custom mesh adaptor
lvr2::DenseVertexMap< float > vertex_costs
combined layer costs
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.
std::unique_ptr< KDTree > kd_tree_ptr
k-d tree to query mesh vertices in logarithmic time
boost::shared_ptr< dynamic_reconfigure::Server< mesh_map::MeshMapConfig > > reconfigure_server_ptr
shared pointer to dynamic reconfigure server
std::string uuid_str
uuid for the load mesh map
lvr2::OptionalVertexHandle getNearestVertexHandle(const mesh_map::Vector &pos)
Return and optional vertex handle of to the closest vertex to the given position.
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
stored vector map to share between planner and controller
MeshMap(tf2_ros::Buffer &tf)
std::string srv_password
login password to connect to the server
const lvr2::DenseVertexMap< Normal > & vertexNormals()
Returns the mesh's vertex normals.
bool initLayerPlugins()
Initialized all loaded layer plugins.
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
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...
bool first_config
first reconfigure call
ros::NodeHandle private_nh
private node handle within the mesh map namespace
mesh_map::AbstractLayer::Ptr layer(const std::string &layer_name)
returns a shared pointer to the specified layer
bool barycentricCoords(const Vector &p, const lvr2::FaceHandle &triangle, float &u, float &v, float &w)
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....
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
void publishCombinedVectorField()
Publishes the vector field as visualisation_msgs/Marker.
bool map_loaded
indicates whether the map has been loaded
void publishCostLayers()
Publishes all layer costs as mesh_msgs/VertexCosts.
lvr2::DenseVertexMap< Normal > vertex_normals
vertex normals
std::map< std::string, mesh_map::AbstractLayer::Ptr > layer_names
mapping from name to layer instance
const std::string getGlobalFrameID()
Returns the global frame / coordinate system id string.
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.
float costAtPosition(const lvr2::DenseVertexMap< float > &costs, const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords)
ros::Publisher vector_field_pub
publisher for the stored vector field
void setVectorMap(lvr2::DenseVertexMap< mesh_map::Vector > &vector_map)
Stores the given vector map.
void layerChanged(const std::string &layer_name)
Callback function which is called from inside a layer plugin if cost values change.
dynamic_reconfigure::Server< mesh_map::MeshMapConfig >::CallbackType config_callback
dynamic reconfigure callback function binding
bool isLethal(const lvr2::VertexHandle &vH)
Checks if the given vertex handle corresponds to a lethal / not passable vertex.
const lvr2::DenseEdgeMap< float > & edgeWeights()
Returns the mesh's edge weights.
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.
void publishDebugPoint(const Vector pos, const std_msgs::ColorRGBA &color, const std::string &name)
Publishes a position as marker. Used for debug purposes.
pluginlib::ClassLoader< mesh_map::AbstractLayer > layer_loader
plugin class loader for for the layer plugins
bool readMap()
Reads in the mesh geometry, normals and cost values and publishes all as mesh_msgs.
const lvr2::DenseEdgeMap< float > & edgeDistances()
Returns the mesh's vertex distances.
const lvr2::DenseVertexMap< mesh_map::Vector > & getVectorMap()
Returns the stored vector map.
ros::Publisher vertex_colors_pub
publisher for vertex colors
void publishVertexColors()
void reconfigureCallback(mesh_map::MeshMapConfig &config, uint32_t level)
reconfigure callback function which is called if a dynamic reconfiguration were triggered.
std::string srv_url
server url
bool meshAhead(Vector &vec, lvr2::FaceHandle &face, const float &step_width)
void findContours(std::vector< std::vector< lvr2::VertexHandle >> &contours, int min_contour_size)
Computes contours.
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.
std::string global_frame
global frame / coordinate system id
mesh_map
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:45