Costmap layer which inflates around existing lethal vertices. More...
#include <inflation_layer.h>

Private Member Functions | |
| 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 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::FaceHandle > | cutting_faces |
| lvr2::DenseVertexMap< float > | direction |
| lvr2::DenseVertexMap< float > | distances |
| bool | first_config |
| std::set< lvr2::VertexHandle > | lethal_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::AbstractLayer > | Ptr |
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::MeshMap > | map_ptr |
| std::shared_ptr< lvr2::AttributeMeshIOBase > | mesh_io_ptr |
| std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > | mesh_ptr |
| ros::NodeHandle | private_nh |
Costmap layer which inflates around existing lethal vertices.
Definition at line 52 of file inflation_layer.h.
|
private |
adds vector pointing back to source of inflation source
| current_vertex | vertex to calculate vector for | |
| predecessors | current predecessor map | |
| [out] | vector_map | resulting vectorfield |
Definition at line 493 of file inflation_layer.cpp.
|
privatevirtual |
calculate the values of this layer
Implements mesh_map::AbstractLayer.
Definition at line 611 of file inflation_layer.cpp.
|
inlineprivate |
Definition at line 105 of file inflation_layer.cpp.
|
privatevirtual |
deliver the current costmap
Implements mesh_map::AbstractLayer.
Definition at line 624 of file inflation_layer.cpp.
|
inlineprivatevirtual |
delivers the default layer value
Implements mesh_map::AbstractLayer.
Definition at line 73 of file inflation_layer.h.
|
private |
fade cost value based on lethal and inscribed area
| val | input cost value |
Definition at line 235 of file inflation_layer.cpp.
|
privatevirtual |
initializes this layer plugin
| name | name of this plugin |
Implements mesh_map::AbstractLayer.
Definition at line 667 of file inflation_layer.cpp.
|
private |
inflate around lethal vertices by inflating to neighbours on mesh and using squared distances and assign riskiness values to vertices
| lethals | set of current lethal vertices |
| inflation_radius | radius of the inflation |
| inscribed_radius | radius of the inscribed area |
| inscribed_value | value assigned to vertices in inscribed area |
| lethal_value | value assigned to lethal vertices |
Definition at line 515 of file inflation_layer.cpp.
|
inlineprivatevirtual |
deliver set containing all vertices marked as lethal
Implements mesh_map::AbstractLayer.
Definition at line 203 of file inflation_layer.h.
|
privatevirtual |
try read layer from map file
Implements mesh_map::AbstractLayer.
Definition at line 49 of file inflation_layer.cpp.
|
private |
callback for incoming reconfigure configs
| cfg | new config |
| level | level |
Definition at line 629 of file inflation_layer.cpp.
|
privatevirtual |
delivers the threshold above which vertices are marked lethal
Implements mesh_map::AbstractLayer.
Definition at line 83 of file inflation_layer.cpp.
|
privatevirtual |
update set of lethal vertices by adding and removing vertices
| added_lethal | vertices to be marked as lethal |
| removed_lethal | vertices to be removed from the set of lethal vertices |
Implements mesh_map::AbstractLayer.
Definition at line 88 of file inflation_layer.cpp.
|
privatevirtual |
returns the repulsive vector at a given vertex
| vertex | requested vertex |
Reimplemented from mesh_map::AbstractLayer.
Definition at line 453 of file inflation_layer.cpp.
|
privatevirtual |
returns repulsive vector at a given position inside a face
| vertices | vertices of the face |
| barycentric_coords | barycentric coordinates of the requested point inside the face |
Reimplemented from mesh_map::AbstractLayer.
Definition at line 423 of file inflation_layer.cpp.
|
inlineprivatevirtual |
delivers the current repulsive vectorfield
Reimplemented from mesh_map::AbstractLayer.
Definition at line 168 of file inflation_layer.h.
|
private |
inflate around lethal vertices by using an wave front propagation and assign riskiness values to vertices
| lethals | set of current lethal vertices |
| inflation_radius | radius of inflation |
| inscribed_radius | rarius of inscribed area |
| inscribed_value | value assigned to inscribed vertices |
| lethal_value | value of lethal vertices |
Definition at line 255 of file inflation_layer.cpp.
|
inlineprivate |
updates the wavefront
| distances | current distances from the start vertices |
| predecessors | current predecessors of vertices visited during the wave front propagation |
| max_distance | max distance of propagation |
| edge_weights | weights of the edges |
| fh | current face |
| normal | normal of the current face |
| v1 | first vertex of the current face |
| v2 | second vertex of the current face |
| v3 | third vertex of the current face |
Definition at line 157 of file inflation_layer.cpp.
|
privatevirtual |
try to write layer to map file
Implements mesh_map::AbstractLayer.
Definition at line 67 of file inflation_layer.cpp.
|
private |
Definition at line 243 of file inflation_layer.h.
|
private |
Definition at line 239 of file inflation_layer.h.
|
private |
Definition at line 229 of file inflation_layer.h.
|
private |
Definition at line 227 of file inflation_layer.h.
|
private |
Definition at line 233 of file inflation_layer.h.
|
private |
Definition at line 241 of file inflation_layer.h.
|
private |
Definition at line 235 of file inflation_layer.h.
|
private |
Definition at line 238 of file inflation_layer.h.
|
private |
Definition at line 225 of file inflation_layer.h.
|
private |
Definition at line 231 of file inflation_layer.h.