Private Member Functions | Private Attributes | List of all members
mesh_layers::InflationLayer Class Reference

Costmap layer which inflates around existing lethal vertices. More...

#include <inflation_layer.h>

Inheritance diagram for mesh_layers::InflationLayer:
Inheritance graph
[legend]

Private Member Functions

void backToSource (const lvr2::VertexHandle &current_vertex, const lvr2::DenseVertexMap< lvr2::VertexHandle > &predecessors, lvr2::DenseVertexMap< lvr2::BaseVector< float >> &vector_map)
 adds vector pointing back to source of inflation source More...
 
virtual bool computeLayer ()
 calculate the values of this layer More...
 
float computeUpdateSethianMethod (const float &d1, const float &d2, const float &a, const float &b, const float &dot, const float &F)
 
virtual lvr2::VertexMap< float > & costs ()
 deliver the current costmap More...
 
virtual float defaultValue ()
 delivers the default layer value More...
 
float fading (const float val)
 fade cost value based on lethal and inscribed area More...
 
virtual bool initialize (const std::string &name)
 initializes this layer plugin More...
 
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 assign riskiness values to vertices More...
 
virtual std::set< lvr2::VertexHandle > & lethals ()
 deliver set containing all vertices marked as lethal More...
 
virtual bool readLayer ()
 try read layer from map file More...
 
void reconfigureCallback (mesh_layers::InflationLayerConfig &cfg, uint32_t level)
 callback for incoming reconfigure configs More...
 
virtual float threshold ()
 delivers the threshold above which vertices are marked lethal More...
 
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 More...
 
lvr2::BaseVector< float > vectorAt (const lvr2::VertexHandle &vertex)
 returns the repulsive vector at a given vertex More...
 
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 More...
 
const boost::optional< lvr2::VertexMap< lvr2::BaseVector< float > > & > vectorMap ()
 delivers the current repulsive vectorfield More...
 
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 vertices More...
 
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 More...
 
virtual bool writeLayer ()
 try to write layer to map file More...
 

Private Attributes

InflationLayerConfig config
 
dynamic_reconfigure::Server< mesh_layers::InflationLayerConfig >::CallbackType config_callback
 
lvr2::DenseVertexMap< lvr2::FaceHandlecutting_faces
 
lvr2::DenseVertexMap< float > direction
 
lvr2::DenseVertexMap< float > distances
 
bool first_config
 
std::set< lvr2::VertexHandlelethal_vertices
 
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::InflationLayerConfig > > reconfigure_server_ptr
 
lvr2::DenseVertexMap< float > riskiness
 
lvr2::DenseVertexMap< lvr2::BaseVector< float > > vector_map
 

Additional Inherited Members

- Public Types inherited from mesh_map::AbstractLayer
typedef boost::shared_ptr< mesh_map::AbstractLayerPtr
 
- Public Member Functions inherited from mesh_map::AbstractLayer
virtual bool initialize (const std::string &name, const notify_func notify_update, std::shared_ptr< mesh_map::MeshMap > &map, std::shared_ptr< lvr2::HalfEdgeMesh< Vector >> &mesh, std::shared_ptr< lvr2::AttributeMeshIOBase > &io)
 
void notifyChange ()
 
- Protected Attributes inherited from mesh_map::AbstractLayer
std::string layer_name
 
std::shared_ptr< mesh_map::MeshMapmap_ptr
 
std::shared_ptr< lvr2::AttributeMeshIOBasemesh_io_ptr
 
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
 
ros::NodeHandle private_nh
 

Detailed Description

Costmap layer which inflates around existing lethal vertices.

Definition at line 52 of file inflation_layer.h.

Member Function Documentation

◆ backToSource()

void mesh_layers::InflationLayer::backToSource ( const lvr2::VertexHandle current_vertex,
const lvr2::DenseVertexMap< lvr2::VertexHandle > &  predecessors,
lvr2::DenseVertexMap< lvr2::BaseVector< float >> &  vector_map 
)
private

adds vector pointing back to source of inflation source

Parameters
current_vertexvertex to calculate vector for
predecessorscurrent predecessor map
[out]vector_mapresulting vectorfield

Definition at line 493 of file inflation_layer.cpp.

◆ computeLayer()

bool mesh_layers::InflationLayer::computeLayer ( )
privatevirtual

calculate the values of this layer

Returns
true if successfull; else false

Implements mesh_map::AbstractLayer.

Definition at line 611 of file inflation_layer.cpp.

◆ computeUpdateSethianMethod()

float mesh_layers::InflationLayer::computeUpdateSethianMethod ( const float &  d1,
const float &  d2,
const float &  a,
const float &  b,
const float &  dot,
const float &  F 
)
inlineprivate

Definition at line 105 of file inflation_layer.cpp.

◆ costs()

lvr2::VertexMap< float > & mesh_layers::InflationLayer::costs ( )
privatevirtual

deliver the current costmap

Returns
calculated costmap

Implements mesh_map::AbstractLayer.

Definition at line 624 of file inflation_layer.cpp.

◆ defaultValue()

virtual float mesh_layers::InflationLayer::defaultValue ( )
inlineprivatevirtual

delivers the default layer value

Returns
default value used for this layer

Implements mesh_map::AbstractLayer.

Definition at line 73 of file inflation_layer.h.

◆ fading()

float mesh_layers::InflationLayer::fading ( const float  val)
private

fade cost value based on lethal and inscribed area

Parameters
valinput cost value
Returns
resulting cost value

Definition at line 235 of file inflation_layer.cpp.

◆ initialize()

bool mesh_layers::InflationLayer::initialize ( const std::string &  name)
privatevirtual

initializes this layer plugin

Parameters
namename of this plugin
Returns
true if initialization was successfull; else false

Implements mesh_map::AbstractLayer.

Definition at line 667 of file inflation_layer.cpp.

◆ lethalCostInflation()

void mesh_layers::InflationLayer::lethalCostInflation ( const std::set< lvr2::VertexHandle > &  lethals,
const float  inflation_radius,
const float  inscribed_radius,
const float  inscribed_value,
const float  lethal_value 
)
private

inflate around lethal vertices by inflating to neighbours on mesh and using squared distances and assign riskiness values to vertices

Parameters
lethalsset of current lethal vertices
inflation_radiusradius of the inflation
inscribed_radiusradius of the inscribed area
inscribed_valuevalue assigned to vertices in inscribed area
lethal_valuevalue assigned to lethal vertices

Definition at line 515 of file inflation_layer.cpp.

◆ lethals()

virtual std::set<lvr2::VertexHandle>& mesh_layers::InflationLayer::lethals ( )
inlineprivatevirtual

deliver set containing all vertices marked as lethal

Returns
lethal vertices

Implements mesh_map::AbstractLayer.

Definition at line 203 of file inflation_layer.h.

◆ readLayer()

bool mesh_layers::InflationLayer::readLayer ( )
privatevirtual

try read layer from map file

Returns
true if successul; else false

Implements mesh_map::AbstractLayer.

Definition at line 49 of file inflation_layer.cpp.

◆ reconfigureCallback()

void mesh_layers::InflationLayer::reconfigureCallback ( mesh_layers::InflationLayerConfig &  cfg,
uint32_t  level 
)
private

callback for incoming reconfigure configs

Parameters
cfgnew config
levellevel

Definition at line 629 of file inflation_layer.cpp.

◆ threshold()

float mesh_layers::InflationLayer::threshold ( )
privatevirtual

delivers the threshold above which vertices are marked lethal

Returns
lethal threshold

Implements mesh_map::AbstractLayer.

Definition at line 83 of file inflation_layer.cpp.

◆ updateLethal()

void mesh_layers::InflationLayer::updateLethal ( std::set< lvr2::VertexHandle > &  added_lethal,
std::set< lvr2::VertexHandle > &  removed_lethal 
)
privatevirtual

update set of lethal vertices by adding and removing vertices

Parameters
added_lethalvertices to be marked as lethal
removed_lethalvertices to be removed from the set of lethal vertices

Implements mesh_map::AbstractLayer.

Definition at line 88 of file inflation_layer.cpp.

◆ vectorAt() [1/2]

lvr2::BaseVector< float > mesh_layers::InflationLayer::vectorAt ( const lvr2::VertexHandle vertex)
privatevirtual

returns the repulsive vector at a given vertex

Parameters
vertexrequested vertex
Returns
vector of vectorfield at requested vertex

Reimplemented from mesh_map::AbstractLayer.

Definition at line 453 of file inflation_layer.cpp.

◆ vectorAt() [2/2]

lvr2::BaseVector< float > mesh_layers::InflationLayer::vectorAt ( const std::array< lvr2::VertexHandle, 3 > &  vertices,
const std::array< float, 3 > &  barycentric_coords 
)
privatevirtual

returns repulsive vector at a given position inside a face

Parameters
verticesvertices of the face
barycentric_coordsbarycentric coordinates of the requested point inside the face
Returns
vector of the current vectorfield

Reimplemented from mesh_map::AbstractLayer.

Definition at line 423 of file inflation_layer.cpp.

◆ vectorMap()

const boost::optional<lvr2::VertexMap<lvr2::BaseVector<float> >&> mesh_layers::InflationLayer::vectorMap ( )
inlineprivatevirtual

delivers the current repulsive vectorfield

Returns
repulsive vectorfield

Reimplemented from mesh_map::AbstractLayer.

Definition at line 168 of file inflation_layer.h.

◆ waveCostInflation()

void mesh_layers::InflationLayer::waveCostInflation ( const std::set< lvr2::VertexHandle > &  lethals,
const float  inflation_radius,
const float  inscribed_radius,
const float  inscribed_value,
const float  lethal_value 
)
private

inflate around lethal vertices by using an wave front propagation and assign riskiness values to vertices

Parameters
lethalsset of current lethal vertices
inflation_radiusradius of inflation
inscribed_radiusrarius of inscribed area
inscribed_valuevalue assigned to inscribed vertices
lethal_valuevalue of lethal vertices

Definition at line 255 of file inflation_layer.cpp.

◆ waveFrontUpdate()

bool mesh_layers::InflationLayer::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 
)
inlineprivate

updates the wavefront

Parameters
distancescurrent distances from the start vertices
predecessorscurrent predecessors of vertices visited during the wave front propagation
max_distancemax distance of propagation
edge_weightsweights of the edges
fhcurrent face
normalnormal of the current face
v1first vertex of the current face
v2second vertex of the current face
v3third vertex of the current face
Returns
true if successful; else false

Definition at line 157 of file inflation_layer.cpp.

◆ writeLayer()

bool mesh_layers::InflationLayer::writeLayer ( )
privatevirtual

try to write layer to map file

Returns
true if successfull; else false

Implements mesh_map::AbstractLayer.

Definition at line 67 of file inflation_layer.cpp.

Member Data Documentation

◆ config

InflationLayerConfig mesh_layers::InflationLayer::config
private

Definition at line 243 of file inflation_layer.h.

◆ config_callback

dynamic_reconfigure::Server<mesh_layers::InflationLayerConfig>::CallbackType mesh_layers::InflationLayer::config_callback
private

Definition at line 239 of file inflation_layer.h.

◆ cutting_faces

lvr2::DenseVertexMap<lvr2::FaceHandle> mesh_layers::InflationLayer::cutting_faces
private

Definition at line 229 of file inflation_layer.h.

◆ direction

lvr2::DenseVertexMap<float> mesh_layers::InflationLayer::direction
private

Definition at line 227 of file inflation_layer.h.

◆ distances

lvr2::DenseVertexMap<float> mesh_layers::InflationLayer::distances
private

Definition at line 233 of file inflation_layer.h.

◆ first_config

bool mesh_layers::InflationLayer::first_config
private

Definition at line 241 of file inflation_layer.h.

◆ lethal_vertices

std::set<lvr2::VertexHandle> mesh_layers::InflationLayer::lethal_vertices
private

Definition at line 235 of file inflation_layer.h.

◆ reconfigure_server_ptr

boost::shared_ptr<dynamic_reconfigure::Server<mesh_layers::InflationLayerConfig> > mesh_layers::InflationLayer::reconfigure_server_ptr
private

Definition at line 238 of file inflation_layer.h.

◆ riskiness

lvr2::DenseVertexMap<float> mesh_layers::InflationLayer::riskiness
private

Definition at line 225 of file inflation_layer.h.

◆ vector_map

lvr2::DenseVertexMap<lvr2::BaseVector<float> > mesh_layers::InflationLayer::vector_map
private

Definition at line 231 of file inflation_layer.h.


The documentation for this class was generated from the following files:


mesh_layers
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:43:03