Go to the documentation of this file.
103 if (face_normals_opt)
105 face_normals = face_normals_opt.
get();
110 ROS_INFO_STREAM(
"No face normals found in the given map file, computing them...");
113 if (
mesh_io_ptr->addDenseAttributeMap(face_normals,
"face_normals"))
127 if (vertex_normals_opt)
129 vertex_normals = vertex_normals_opt.
get();
134 ROS_INFO_STREAM(
"No vertex normals found in the given map file, computing them...");
136 if (
mesh_io_ptr->addDenseAttributeMap(vertex_normals,
"vertex_normals"))
149 for (
size_t i = 0; i <
mesh_ptr->nextVertexIndex(); i++)
157 steepness.insert(vH, acos(vertex_normals[vH].z));
172 ROS_INFO_STREAM(
"New steepness layer config through dynamic reconfigure.");
180 if (
config.threshold != cfg.threshold)
196 new dynamic_reconfigure::Server<mesh_layers::SteepnessLayerConfig>(
private_nh));
#define ROS_ERROR_STREAM(args)
size_t numValues() const final
bool computeLethals()
mark vertices with values above the threshold as lethal
virtual bool writeLayer()
try to write layer to map file
void reconfigureCallback(mesh_layers::SteepnessLayerConfig &cfg, uint32_t level)
callback for incoming reconfigure configs
virtual bool initialize(const std::string &name)
initializes this layer plugin
dynamic_reconfigure::Server< mesh_layers::SteepnessLayerConfig >::CallbackType config_callback
std::set< lvr2::VertexHandle > lethal_vertices
boost::optional< const ValueT & > get(HandleT key) const final
lvr2::DenseVertexMap< float > steepness
#define ROS_INFO_STREAM(args)
virtual bool computeLayer()
calculate the values of this layer
Costmap layer which calculates the steepness of the vertices. This is useful to avoid stairs.
ros::NodeHandle private_nh
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
virtual float threshold()
delivers the threshold above which vertices are marked lethal
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
PLUGINLIB_EXPORT_CLASS(mesh_layers::InflationLayer, mesh_map::AbstractLayer)
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::SteepnessLayerConfig > > reconfigure_server_ptr
DenseVertexMap< Normal< typename BaseVecT::CoordType > > calcVertexNormals(const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals)
SteepnessLayerConfig config
virtual lvr2::VertexMap< float > & costs()
deliver the current costmap
DenseFaceMap< Normal< typename BaseVecT::CoordType > > calcFaceNormals(const BaseMesh< BaseVecT > &mesh)
virtual bool readLayer()
try read layer from map file
mesh_layers
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:43:03