#include <abstract_layer.h>
Public Types | |
typedef boost::shared_ptr< mesh_map::AbstractLayer > | Ptr |
Public Member Functions | |
virtual bool | computeLayer ()=0 |
Function which is called to compute the layer costs. It is called if the layer information could not be loaded or if another layer triggered an update. More... | |
virtual lvr2::VertexMap< float > & | costs ()=0 |
Returns a vertex map, which associates a cost to each vertex handle. If a vertex handle is not associated with a cost value, i.e. there is no value in the map, the mesh_map will use the default value from threshold(). More... | |
virtual float | defaultValue ()=0 |
Defines the default value for all vertex costs which are not set in the layer. More... | |
virtual bool | initialize (const std::string &name)=0 |
Initializes the layer plugin with the giben name. More... | |
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) |
Initializes the layer plugin under the mesh_map namespace ans sets some basic attributes. More... | |
virtual std::set< lvr2::VertexHandle > & | lethals ()=0 |
Returns a set of vertex handles which are associated with "lethal" obstacles. More... | |
void | notifyChange () |
virtual bool | readLayer ()=0 |
reads the layer data, e.g. from a file, or a database More... | |
virtual float | threshold ()=0 |
Defines the threshold value to consider vertices as a "lethal" obstacle. All vertices with cost values in the layer which a greater than the threshold value are marked as "lethal obstacle". More... | |
virtual void | updateLethal (std::set< lvr2::VertexHandle > &added_lethal, std::set< lvr2::VertexHandle > &removed_lethal)=0 |
Called by the mesh map if another previously processed layer triggers an update. More... | |
virtual lvr2::BaseVector< float > | vectorAt (const std::array< lvr2::VertexHandle, 3 > &vertices, const std::array< float, 3 > &barycentric_coords) |
Optional method if the layer computes vectors. Computes a vector within a triangle using barycentric coordinates. More... | |
virtual lvr2::BaseVector< float > | vectorAt (const lvr2::VertexHandle &vertex) |
Optional method if the layer computes vectors. Computes a vector for a given vertex handle. More... | |
virtual const boost::optional< lvr2::VertexMap< lvr2::BaseVector< float > > & > | vectorMap () |
Optional vector map. Can be implemented if the layer should also compute vectors. If the implmented layer computes a vector field, this method is used to inject the vector field into the mesh map. More... | |
virtual bool | writeLayer ()=0 |
Writes the layer data, e.g. to a file, or a database. More... | |
Protected Attributes | |
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 |
Private Attributes | |
notify_func | notify |
Definition at line 56 of file abstract_layer.h.
Definition at line 59 of file abstract_layer.h.
|
pure virtual |
Function which is called to compute the layer costs. It is called if the layer information could not be loaded or if another layer triggered an update.
|
pure virtual |
Returns a vertex map, which associates a cost to each vertex handle. If a vertex handle is not associated with a cost value, i.e. there is no value in the map, the mesh_map will use the default value from threshold().
|
pure virtual |
Defines the default value for all vertex costs which are not set in the layer.
|
pure virtual |
Initializes the layer plugin with the giben name.
|
inlinevirtual |
Initializes the layer plugin under the mesh_map namespace ans sets some basic attributes.
Definition at line 156 of file abstract_layer.h.
|
pure virtual |
Returns a set of vertex handles which are associated with "lethal" obstacles.
|
inline |
Definition at line 169 of file abstract_layer.h.
|
pure virtual |
reads the layer data, e.g. from a file, or a database
|
pure virtual |
Defines the threshold value to consider vertices as a "lethal" obstacle. All vertices with cost values in the layer which a greater than the threshold value are marked as "lethal obstacle".
|
pure virtual |
Called by the mesh map if another previously processed layer triggers an update.
added_lethal | The "lethal" obstacle vertex handles which are new with respect to the previous call. |
removed_lethal | Old "lethal" obstacle vertex handles, i.e. vertices which are no "lethal" obstacles anymore. |
|
inlinevirtual |
Optional method if the layer computes vectors. Computes a vector within a triangle using barycentric coordinates.
vertices | The three triangle vertices. |
barycentric_coords | The thee barycentric coordinates. |
Definition at line 122 of file abstract_layer.h.
|
inlinevirtual |
Optional method if the layer computes vectors. Computes a vector for a given vertex handle.
Definition at line 143 of file abstract_layer.h.
|
inlinevirtual |
Optional vector map. Can be implemented if the layer should also compute vectors. If the implmented layer computes a vector field, this method is used to inject the vector field into the mesh map.
Definition at line 134 of file abstract_layer.h.
|
pure virtual |
Writes the layer data, e.g. to a file, or a database.
|
protected |
Definition at line 175 of file abstract_layer.h.
|
protected |
Definition at line 178 of file abstract_layer.h.
|
protected |
Definition at line 176 of file abstract_layer.h.
|
protected |
Definition at line 177 of file abstract_layer.h.
|
private |
Definition at line 183 of file abstract_layer.h.
|
protected |
Definition at line 180 of file abstract_layer.h.