inflation_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 #ifndef MESH_MAP__INFLATION_LAYER_H
39 #define MESH_MAP__INFLATION_LAYER_H
40 
41 #include <dynamic_reconfigure/server.h>
42 #include <mesh_layers/InflationLayerConfig.h>
44 
45 namespace mesh_layers
46 {
47 const float EPSILON = 1e-9;
48 
53 {
59  virtual bool readLayer();
60 
66  virtual bool writeLayer();
67 
73  virtual float defaultValue()
74  {
75  return 0;
76  }
77 
83  virtual float threshold();
84 
95  void lethalCostInflation(const std::set<lvr2::VertexHandle>& lethals, const float inflation_radius,
96  const float inscribed_radius, const float inscribed_value, const float lethal_value);
97 
98  inline float computeUpdateSethianMethod(const float& d1, const float& d2, const float& a, const float& b,
99  const float& dot, const float& F);
100 
117  lvr2::DenseVertexMap<lvr2::VertexHandle>& predecessors, const float& max_distance,
118  const lvr2::DenseEdgeMap<float>& edge_weights, const lvr2::FaceHandle& fh,
119  const lvr2::BaseVector<float>& normal, const lvr2::VertexHandle& v1,
120  const lvr2::VertexHandle& v2, const lvr2::VertexHandle& v3);
121 
129  float fading(const float val);
130 
140  void waveCostInflation(const std::set<lvr2::VertexHandle>& lethals, const float inflation_radius,
141  const float inscribed_radius, const float inscribed_value, const float lethal_value);
142 
151  lvr2::BaseVector<float> vectorAt(const std::array<lvr2::VertexHandle, 3>& vertices,
152  const std::array<float, 3>& barycentric_coords);
153 
162 
168  const boost::optional<lvr2::VertexMap<lvr2::BaseVector<float>>&> vectorMap()
169  {
170  return vector_map;
171  }
172 
180  void backToSource(const lvr2::VertexHandle& current_vertex,
181  const lvr2::DenseVertexMap<lvr2::VertexHandle>& predecessors,
183 
189  virtual bool computeLayer();
190 
196  virtual lvr2::VertexMap<float>& costs();
197 
203  virtual std::set<lvr2::VertexHandle>& lethals()
204  {
205  return lethal_vertices;
206  } // TODO remove... layer types
207 
214  virtual void updateLethal(std::set<lvr2::VertexHandle>& added_lethal, std::set<lvr2::VertexHandle>& removed_lethal);
215 
223  virtual bool initialize(const std::string& name);
224 
226 
228 
230 
232 
234 
235  std::set<lvr2::VertexHandle> lethal_vertices;
236 
237  // Server for Reconfiguration
239  dynamic_reconfigure::Server<mesh_layers::InflationLayerConfig>::CallbackType config_callback;
240  // true if the first reconfigure config has been received; else false
242  // current reconfigure config
243  InflationLayerConfig config;
244 
251  void reconfigureCallback(mesh_layers::InflationLayerConfig& cfg, uint32_t level);
252 };
253 
254 } /* namespace mesh_layers */
255 
256 #endif // MESH_MAP__INFLATION_LAYER_H
mesh_layers::InflationLayer::writeLayer
virtual bool writeLayer()
try to write layer to map file
Definition: inflation_layer.cpp:67
mesh_layers::InflationLayer::first_config
bool first_config
Definition: inflation_layer.h:241
lvr2::BaseVector< float >
mesh_layers::InflationLayer::readLayer
virtual bool readLayer()
try read layer from map file
Definition: inflation_layer.cpp:49
mesh_layers::InflationLayer::vectorMap
const boost::optional< lvr2::VertexMap< lvr2::BaseVector< float > > & > vectorMap()
delivers the current repulsive vectorfield
Definition: inflation_layer.h:168
mesh_layers::InflationLayer::riskiness
lvr2::DenseVertexMap< float > riskiness
Definition: inflation_layer.h:225
mesh_layers::InflationLayer::vectorAt
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
Definition: inflation_layer.cpp:423
boost::shared_ptr
mesh_layers::InflationLayer::defaultValue
virtual float defaultValue()
delivers the default layer value
Definition: inflation_layer.h:73
lvr2::FaceHandle
mesh_layers::InflationLayer::direction
lvr2::DenseVertexMap< float > direction
Definition: inflation_layer.h:227
mesh_layers::InflationLayer::updateLethal
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
Definition: inflation_layer.cpp:88
lvr2::AttributeMap
mesh_layers::InflationLayer::waveFrontUpdate
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
Definition: inflation_layer.cpp:157
mesh_layers
Definition: height_diff_layer.h:45
mesh_layers::InflationLayer::fading
float fading(const float val)
fade cost value based on lethal and inscribed area
Definition: inflation_layer.cpp:235
mesh_layers::InflationLayer::distances
lvr2::DenseVertexMap< float > distances
Definition: inflation_layer.h:233
mesh_layers::InflationLayer::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::InflationLayerConfig > > reconfigure_server_ptr
Definition: inflation_layer.h:238
mesh_layers::InflationLayer::computeLayer
virtual bool computeLayer()
calculate the values of this layer
Definition: inflation_layer.cpp:611
lvr2::VectorMap
mesh_layers::InflationLayer::backToSource
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
Definition: inflation_layer.cpp:493
mesh_layers::InflationLayer::lethals
virtual std::set< lvr2::VertexHandle > & lethals()
deliver set containing all vertices marked as lethal
Definition: inflation_layer.h:203
lvr2::VertexHandle
mesh_layers::InflationLayer::config_callback
dynamic_reconfigure::Server< mesh_layers::InflationLayerConfig >::CallbackType config_callback
Definition: inflation_layer.h:239
mesh_layers::InflationLayer
Costmap layer which inflates around existing lethal vertices.
Definition: inflation_layer.h:52
mesh_layers::EPSILON
const float EPSILON
Definition: inflation_layer.h:47
mesh_map::AbstractLayer
mesh_layers::InflationLayer::config
InflationLayerConfig config
Definition: inflation_layer.h:243
abstract_layer.h
mesh_layers::InflationLayer::lethal_vertices
std::set< lvr2::VertexHandle > lethal_vertices
Definition: inflation_layer.h:235
mesh_layers::InflationLayer::cutting_faces
lvr2::DenseVertexMap< lvr2::FaceHandle > cutting_faces
Definition: inflation_layer.h:229
mesh_layers::InflationLayer::vector_map
lvr2::DenseVertexMap< lvr2::BaseVector< float > > vector_map
Definition: inflation_layer.h:231
mesh_layers::InflationLayer::reconfigureCallback
void reconfigureCallback(mesh_layers::InflationLayerConfig &cfg, uint32_t level)
callback for incoming reconfigure configs
Definition: inflation_layer.cpp:629
mesh_layers::InflationLayer::computeUpdateSethianMethod
float computeUpdateSethianMethod(const float &d1, const float &d2, const float &a, const float &b, const float &dot, const float &F)
Definition: inflation_layer.cpp:105
mesh_layers::InflationLayer::threshold
virtual float threshold()
delivers the threshold above which vertices are marked lethal
Definition: inflation_layer.cpp:83
mesh_layers::InflationLayer::initialize
virtual bool initialize(const std::string &name)
initializes this layer plugin
Definition: inflation_layer.cpp:667
mesh_layers::InflationLayer::waveCostInflation
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...
Definition: inflation_layer.cpp:255
mesh_layers::InflationLayer::lethalCostInflation
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...
Definition: inflation_layer.cpp:515
mesh_layers::InflationLayer::costs
virtual lvr2::VertexMap< float > & costs()
deliver the current costmap
Definition: inflation_layer.cpp:624


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