abstract_layer.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
37 
38 #include <functional>
40 #include <mesh_map/MeshMapConfig.h>
41 #include <mesh_map/mesh_map.h>
42 #include <boost/optional.hpp>
43 
44 #ifndef MESH_MAP__ABSTRACT_LAYER_H
45 #define MESH_MAP__ABSTRACT_LAYER_H
46 
47 namespace mesh_map
48 {
49 class MeshMap;
50 
53 
54 typedef std::function<void(const std::string&)> notify_func;
55 
57 {
58 public:
60 
65  virtual bool readLayer() = 0;
66 
71  virtual bool writeLayer() = 0;
72 
77  virtual float defaultValue() = 0;
78 
85  virtual float threshold() = 0;
86 
92  virtual bool computeLayer() = 0;
93 
100  virtual lvr2::VertexMap<float>& costs() = 0;
101 
106  virtual std::set<lvr2::VertexHandle>& lethals() = 0;
107 
113  virtual void updateLethal(std::set<lvr2::VertexHandle>& added_lethal,
114  std::set<lvr2::VertexHandle>& removed_lethal) = 0;
115 
122  virtual lvr2::BaseVector<float> vectorAt(const std::array<lvr2::VertexHandle, 3>& vertices,
123  const std::array<float, 3>& barycentric_coords)
124  {
125  return lvr2::BaseVector<float>();
126  }
127 
134  virtual const boost::optional<lvr2::VertexMap<lvr2::BaseVector<float>>&> vectorMap()
135  {
136  return boost::none;
137  }
138 
144  {
145  return lvr2::BaseVector<float>();
146  }
147 
151  virtual bool initialize(const std::string& name) = 0;
152 
156  virtual bool initialize(const std::string& name, const notify_func notify_update,
157  std::shared_ptr<mesh_map::MeshMap>& map, std::shared_ptr<lvr2::HalfEdgeMesh<Vector>>& mesh,
158  std::shared_ptr<lvr2::AttributeMeshIOBase>& io)
159  {
160  layer_name = name;
161  private_nh = ros::NodeHandle("~/mesh_map/" + name);
162  notify = notify_update;
163  mesh_ptr = mesh;
164  map_ptr = map;
165  mesh_io_ptr = io;
166  return initialize(name);
167  }
168 
170  {
171  this->notify(layer_name);
172  }
173 
174 protected:
175  std::string layer_name;
176  std::shared_ptr<lvr2::AttributeMeshIOBase> mesh_io_ptr;
177  std::shared_ptr<lvr2::HalfEdgeMesh<Vector>> mesh_ptr;
178  std::shared_ptr<mesh_map::MeshMap> map_ptr;
179 
181 
182 private:
184 };
185 
186 } /* namespace mesh_map */
187 
188 #endif // MESH_MAP__ABSTRACT_LAYER_H
mesh_map::AbstractLayer::threshold
virtual float threshold()=0
Defines the threshold value to consider vertices as a "lethal" obstacle. All vertices with cost value...
lvr2::BaseVector< float >
boost::shared_ptr
mesh_map::AbstractLayer::notifyChange
void notifyChange()
Definition: abstract_layer.h:169
mesh_map::AbstractLayer::vectorAt
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 ...
Definition: abstract_layer.h:122
mesh_map
Definition: abstract_layer.h:47
mesh_map::AbstractLayer::map_ptr
std::shared_ptr< mesh_map::MeshMap > map_ptr
Definition: abstract_layer.h:178
mesh_map::AbstractLayer::writeLayer
virtual bool writeLayer()=0
Writes the layer data, e.g. to a file, or a database.
lvr2::AttributeMap
mesh_map::AbstractLayer::readLayer
virtual bool readLayer()=0
reads the layer data, e.g. from a file, or a database
mesh_map::notify_func
std::function< void(const std::string &)> notify_func
Definition: abstract_layer.h:54
mesh_map::AbstractLayer::Ptr
boost::shared_ptr< mesh_map::AbstractLayer > Ptr
Definition: abstract_layer.h:59
mesh_map::AbstractLayer::layer_name
std::string layer_name
Definition: abstract_layer.h:175
mesh_map::Vector
lvr2::BaseVector< float > Vector
use vectors with datatype folat
Definition: abstract_layer.h:49
mesh_map::AbstractLayer::initialize
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.
Definition: abstract_layer.h:156
lvr2::Normal< float >
map
OutMapT< typename InMapT::HandleType, std::result_of_t< MapF(typename InMapT::ValueType)> > map(const InMapT &mapIn, MapF func)
AttributeMeshIOBase.hpp
mesh_map::AbstractLayer::computeLayer
virtual bool computeLayer()=0
Function which is called to compute the layer costs. It is called if the layer information could not ...
lvr2::VertexHandle
mesh_map::AbstractLayer
Definition: abstract_layer.h:56
mesh_map::AbstractLayer::private_nh
ros::NodeHandle private_nh
Definition: abstract_layer.h:180
mesh_map::AbstractLayer::mesh_io_ptr
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
Definition: abstract_layer.h:176
mesh_map.h
mesh_map::AbstractLayer::notify
notify_func notify
Definition: abstract_layer.h:183
mesh_map::AbstractLayer::mesh_ptr
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
Definition: abstract_layer.h:177
mesh_map::MeshMap
Definition: mesh_map.h:60
mesh_map::Normal
lvr2::Normal< float > Normal
use normals with datatype float
Definition: abstract_layer.h:52
mesh_map::AbstractLayer::vectorAt
virtual lvr2::BaseVector< float > vectorAt(const lvr2::VertexHandle &vertex)
Optional method if the layer computes vectors. Computes a vector for a given vertex handle.
Definition: abstract_layer.h:143
mesh_map::AbstractLayer::initialize
virtual bool initialize(const std::string &name)=0
Initializes the layer plugin with the giben name.
mesh
HalfEdgeMesh< Vec > mesh
mesh_map::AbstractLayer::vectorMap
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 l...
Definition: abstract_layer.h:134
mesh_map::AbstractLayer::defaultValue
virtual float defaultValue()=0
Defines the default value for all vertex costs which are not set in the layer.
mesh_map::AbstractLayer::lethals
virtual std::set< lvr2::VertexHandle > & lethals()=0
Returns a set of vertex handles which are associated with "lethal" obstacles.
mesh_map::AbstractLayer::updateLethal
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.
mesh_map::AbstractLayer::costs
virtual lvr2::VertexMap< float > & costs()=0
Returns a vertex map, which associates a cost to each vertex handle. If a vertex handle is not associ...
ros::NodeHandle
lvr2::HalfEdgeMesh


mesh_map
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:45