Go to the documentation of this file.
91 auto face_normals_opt =
95 if (face_normals_opt) {
96 face_normals = face_normals_opt.
get();
98 <<
" face normals in map file.");
101 "No face normals found in the given map file, computing them...");
104 <<
" face normals.");
105 if (
mesh_io_ptr->addDenseAttributeMap(face_normals,
"face_normals")) {
114 auto vertex_normals_opt =
118 if (vertex_normals_opt) {
119 vertex_normals = vertex_normals_opt.
get();
121 <<
" vertex normals in map file!");
124 "No vertex normals found in the given map file, computing them...");
126 if (
mesh_io_ptr->addDenseAttributeMap(vertex_normals,
"vertex_normals")) {
145 ROS_INFO_STREAM(
"New roughness layer config through dynamic reconfigure.");
152 if(
config.threshold != cfg.threshold)
166 dynamic_reconfigure::Server<mesh_layers::RoughnessLayerConfig>>(
167 new dynamic_reconfigure::Server<mesh_layers::RoughnessLayerConfig>(
#define ROS_ERROR_STREAM(args)
size_t numValues() const final
virtual bool initialize(const std::string &name)
initializes this layer plugin
virtual float threshold()
delivers the threshold above which vertices are marked lethal
void reconfigureCallback(mesh_layers::RoughnessLayerConfig &cfg, uint32_t level)
callback for incoming reconfigure configs
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::RoughnessLayerConfig > > reconfigure_server_ptr
DenseVertexMap< float > calcVertexRoughness(const BaseMesh< BaseVecT > &mesh, double radius, const VertexMap< Normal< typename BaseVecT::CoordType >> &normals)
boost::optional< const ValueT & > get(HandleT key) const final
virtual bool writeLayer()
try to write layer to map file
#define ROS_INFO_STREAM(args)
Costmap layer which calculates the roughness of the surface. This is useful to differentiate paths fr...
dynamic_reconfigure::Server< mesh_layers::RoughnessLayerConfig >::CallbackType config_callback
virtual lvr2::VertexMap< float > & costs()
deliver the current costmap
ros::NodeHandle private_nh
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
virtual bool computeLayer()
calculate the values of this layer
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
virtual bool readLayer()
try read layer from map file
PLUGINLIB_EXPORT_CLASS(mesh_layers::InflationLayer, mesh_map::AbstractLayer)
std::set< lvr2::VertexHandle > lethal_vertices
DenseVertexMap< Normal< typename BaseVecT::CoordType > > calcVertexNormals(const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals)
RoughnessLayerConfig config
DenseFaceMap< Normal< typename BaseVecT::CoordType > > calcFaceNormals(const BaseMesh< BaseVecT > &mesh)
lvr2::DenseVertexMap< float > roughness
bool computeLethals()
mark vertices with values above the threshold as lethal
mesh_layers
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:43:03