Go to the documentation of this file.
38 #ifndef MESH_MAP__INFLATION_LAYER_H
39 #define MESH_MAP__INFLATION_LAYER_H
41 #include <dynamic_reconfigure/server.h>
42 #include <mesh_layers/InflationLayerConfig.h>
96 const float inscribed_radius,
const float inscribed_value,
const float lethal_value);
99 const float& dot,
const float& F);
129 float fading(
const float val);
141 const float inscribed_radius,
const float inscribed_value,
const float lethal_value);
152 const std::array<float, 3>& barycentric_coords);
168 const boost::optional<lvr2::VertexMap<lvr2::BaseVector<float>>&>
vectorMap()
203 virtual std::set<lvr2::VertexHandle>&
lethals()
214 virtual void updateLethal(std::set<lvr2::VertexHandle>& added_lethal, std::set<lvr2::VertexHandle>& removed_lethal);
223 virtual bool initialize(
const std::string& name);
239 dynamic_reconfigure::Server<mesh_layers::InflationLayerConfig>::CallbackType
config_callback;
256 #endif // MESH_MAP__INFLATION_LAYER_H
virtual bool writeLayer()
try to write layer to map file
virtual bool readLayer()
try read layer from map file
const boost::optional< lvr2::VertexMap< lvr2::BaseVector< float > > & > vectorMap()
delivers the current repulsive vectorfield
lvr2::DenseVertexMap< float > riskiness
lvr2::BaseVector< float > vectorAt(const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords)
returns repulsive vector at a given position inside a face
virtual float defaultValue()
delivers the default layer value
lvr2::DenseVertexMap< float > direction
virtual void updateLethal(std::set< lvr2::VertexHandle > &added_lethal, std::set< lvr2::VertexHandle > &removed_lethal)
update set of lethal vertices by adding and removing vertices
bool waveFrontUpdate(lvr2::DenseVertexMap< float > &distances, lvr2::DenseVertexMap< lvr2::VertexHandle > &predecessors, const float &max_distance, const lvr2::DenseEdgeMap< float > &edge_weights, const lvr2::FaceHandle &fh, const lvr2::BaseVector< float > &normal, const lvr2::VertexHandle &v1, const lvr2::VertexHandle &v2, const lvr2::VertexHandle &v3)
updates the wavefront
float fading(const float val)
fade cost value based on lethal and inscribed area
lvr2::DenseVertexMap< float > distances
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::InflationLayerConfig > > reconfigure_server_ptr
virtual bool computeLayer()
calculate the values of this layer
void backToSource(const lvr2::VertexHandle ¤t_vertex, const lvr2::DenseVertexMap< lvr2::VertexHandle > &predecessors, lvr2::DenseVertexMap< lvr2::BaseVector< float >> &vector_map)
adds vector pointing back to source of inflation source
virtual std::set< lvr2::VertexHandle > & lethals()
deliver set containing all vertices marked as lethal
dynamic_reconfigure::Server< mesh_layers::InflationLayerConfig >::CallbackType config_callback
Costmap layer which inflates around existing lethal vertices.
InflationLayerConfig config
std::set< lvr2::VertexHandle > lethal_vertices
lvr2::DenseVertexMap< lvr2::FaceHandle > cutting_faces
lvr2::DenseVertexMap< lvr2::BaseVector< float > > vector_map
void reconfigureCallback(mesh_layers::InflationLayerConfig &cfg, uint32_t level)
callback for incoming reconfigure configs
float computeUpdateSethianMethod(const float &d1, const float &d2, const float &a, const float &b, const float &dot, const float &F)
virtual float threshold()
delivers the threshold above which vertices are marked lethal
virtual bool initialize(const std::string &name)
initializes this layer plugin
void waveCostInflation(const std::set< lvr2::VertexHandle > &lethals, const float inflation_radius, const float inscribed_radius, const float inscribed_value, const float lethal_value)
inflate around lethal vertices by using an wave front propagation and assign riskiness values to vert...
void lethalCostInflation(const std::set< lvr2::VertexHandle > &lethals, const float inflation_radius, const float inscribed_radius, const float inscribed_value, const float lethal_value)
inflate around lethal vertices by inflating to neighbours on mesh and using squared distances and ass...
virtual lvr2::VertexMap< float > & costs()
deliver the current costmap
mesh_layers
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:43:03