ridge_layer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020, The authors
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  * Malte kl. Piening <malte@klpiening.com>
35  *
36  */
37 
39 
44 #include <math.h>
45 
47 
48 namespace mesh_layers
49 {
51 {
52  ROS_INFO_STREAM("Try to read ridge from map file...");
53  auto ridge_opt = mesh_io_ptr->getDenseAttributeMap<lvr2::DenseVertexMap<float>>("ridge");
54  if (ridge_opt)
55  {
56  ROS_INFO_STREAM("Successfully read ridge from map file.");
57  ridge = ridge_opt.get();
58  return computeLethals();
59  }
60 
61  return false;
62 }
63 
65 {
66  if (mesh_io_ptr->addDenseAttributeMap(ridge, "ridge"))
67  {
68  ROS_INFO_STREAM("Saved ridge to map file.");
69  return true;
70  }
71  else
72  {
73  ROS_ERROR_STREAM("Could not save ridge to map file!");
74  return false;
75  }
76 }
77 
79 {
80  ROS_INFO_STREAM("Compute lethals for \"" << layer_name << "\" (Ridge Layer) with threshold " << config.threshold);
81  lethal_vertices.clear();
82  for (auto vH : ridge)
83  {
84  if (ridge[vH] > config.threshold)
85  lethal_vertices.insert(vH);
86  }
87  ROS_INFO_STREAM("Found " << lethal_vertices.size() << " lethal vertices.");
88  return true;
89 }
90 
92 {
93  return config.threshold;
94 }
95 
97 {
98  ROS_INFO_STREAM("Computing ridge...");
99 
101 
102  auto face_normals_opt = mesh_io_ptr->getDenseAttributeMap<lvr2::DenseFaceMap<mesh_map::Normal>>("face_normals");
103 
104  if (face_normals_opt)
105  {
106  face_normals = face_normals_opt.get();
107  ROS_INFO_STREAM("Found " << face_normals.numValues() << " face normals in map file.");
108  }
109  else
110  {
111  ROS_INFO_STREAM("No face normals found in the given map file, computing them...");
112  face_normals = lvr2::calcFaceNormals(*mesh_ptr);
113  ROS_INFO_STREAM("Computed " << face_normals.numValues() << " face normals.");
114  if (mesh_io_ptr->addDenseAttributeMap(face_normals, "face_normals"))
115  {
116  ROS_INFO_STREAM("Saved face normals to map file.");
117  }
118  else
119  {
120  ROS_ERROR_STREAM("Could not save face normals to map file!");
121  return false;
122  }
123  }
124 
126  auto vertex_normals_opt = mesh_io_ptr->getDenseAttributeMap<lvr2::DenseVertexMap<mesh_map::Normal>>("vertex_normals");
127 
128  if (vertex_normals_opt)
129  {
130  vertex_normals = vertex_normals_opt.get();
131  ROS_INFO_STREAM("Found " << vertex_normals.numValues() << " vertex normals in map file!");
132  }
133  else
134  {
135  ROS_INFO_STREAM("No vertex normals found in the given map file, computing them...");
136  vertex_normals = lvr2::calcVertexNormals(*mesh_ptr, face_normals);
137  if (mesh_io_ptr->addDenseAttributeMap(vertex_normals, "vertex_normals"))
138  {
139  ROS_INFO_STREAM("Saved vertex normals to map file.");
140  }
141  else
142  {
143  ROS_ERROR_STREAM("Could not save vertex normals to map file!");
144  return false;
145  }
146  }
147 
148  ridge.reserve(mesh_ptr->nextVertexIndex());
149 
150  for (size_t i = 0; i < mesh_ptr->nextVertexIndex(); i++)
151  {
152  auto vH = lvr2::VertexHandle(i);
153  if (!mesh_ptr->containsVertex(vH))
154  {
155  ridge.insert(vH, config.threshold + 0.1);
156  continue;
157  }
158 
159  std::set<lvr2::VertexHandle> invalid;
160 
161  float value = 0.0;
162  int num_neighbours = 0;
163  lvr2::BaseVector<float> reference = mesh_ptr->getVertexPosition(vH) + vertex_normals[vH];
164  visitLocalVertexNeighborhood(*mesh_ptr.get(), invalid, vH, config.radius, [&](auto vertex) {
165  lvr2::BaseVector<float> current_point = mesh_ptr->getVertexPosition(vertex) + vertex_normals[vertex];
166  value += (current_point - reference).length();
167  num_neighbours++;
168  });
169 
170  if (num_neighbours == 0)
171  {
172  ridge.insert(vH, config.threshold + 0.1);
173  continue;
174  }
175 
176  ridge.insert(vH, value / num_neighbours);
177  }
178 
179  return computeLethals();
180 }
181 
183 {
184  return ridge;
185 }
186 
187 void RidgeLayer::reconfigureCallback(mesh_layers::RidgeLayerConfig& cfg, uint32_t level)
188 {
189  bool notify = false;
190 
191  ROS_INFO_STREAM("New ridge layer config through dynamic reconfigure.");
192  if (first_config)
193  {
194  config = cfg;
195  first_config = false;
196  return;
197  }
198 
199  if (config.threshold != cfg.threshold)
200  {
201  computeLethals();
202  notify = true;
203  }
204 
205  if (config.radius != cfg.radius)
206  {
207  computeLayer();
208  notify = true;
209  }
210 
211  if (notify)
212  notifyChange();
213 
214  config = cfg;
215 }
216 
217 bool RidgeLayer::initialize(const std::string& name)
218 {
219  first_config = true;
221  new dynamic_reconfigure::Server<mesh_layers::RidgeLayerConfig>(private_nh));
222 
223  config_callback = boost::bind(&RidgeLayer::reconfigureCallback, this, _1, _2);
225  return true;
226 }
227 
228 } /* namespace mesh_layers */
mesh_layers::RidgeLayer::reconfigureCallback
void reconfigureCallback(mesh_layers::RidgeLayerConfig &cfg, uint32_t level)
callback for incoming reconfigure configs
Definition: ridge_layer.cpp:187
mesh_layers::RidgeLayer::lethal_vertices
std::set< lvr2::VertexHandle > lethal_vertices
Definition: ridge_layer.h:135
mesh_layers::RidgeLayer::writeLayer
virtual bool writeLayer()
try to write layer to map file
Definition: ridge_layer.cpp:64
lvr2::BaseVector< float >
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
mesh_map::AbstractLayer::notifyChange
void notifyChange()
lvr2::VectorMap::numValues
size_t numValues() const final
mesh_layers::RidgeLayer::threshold
virtual float threshold()
delivers the threshold above which vertices are marked lethal
Definition: ridge_layer.cpp:91
mesh_layers::RidgeLayer::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::RidgeLayerConfig > > reconfigure_server_ptr
Definition: ridge_layer.h:138
lvr2::AttributeMap
NormalAlgorithms.hpp
visitLocalVertexNeighborhood
void visitLocalVertexNeighborhood(const BaseMesh< BaseVecT > &mesh, VertexHandle vH, double radius, VisitorF visitor)
mesh_layers::RidgeLayer::config
RidgeLayerConfig config
Definition: ridge_layer.h:143
mesh_layers::RidgeLayer::config_callback
dynamic_reconfigure::Server< mesh_layers::RidgeLayerConfig >::CallbackType config_callback
Definition: ridge_layer.h:139
mesh_layers
Definition: height_diff_layer.h:45
mesh_layers::RidgeLayer
Costmap layer which assigns high costs to ridges. This is useful for dam avoidance in agricultural ap...
Definition: ridge_layer.h:51
mesh_map::AbstractLayer::layer_name
std::string layer_name
mesh_layers::RidgeLayer::computeLayer
virtual bool computeLayer()
calculate the values of this layer
Definition: ridge_layer.cpp:96
class_list_macros.h
BaseVector.hpp
lvr2::VectorMap
mesh_layers::RidgeLayer::first_config
bool first_config
Definition: ridge_layer.h:141
lvr2::VertexHandle
mesh_layers::RidgeLayer::costs
virtual lvr2::VertexMap< float > & costs()
deliver the current costmap
Definition: ridge_layer.cpp:182
mesh_layers::RidgeLayer::initialize
virtual bool initialize(const std::string &name)
initializes this layer plugin
Definition: ridge_layer.cpp:217
mesh_layers::RidgeLayer::readLayer
virtual bool readLayer()
try read layer from map file
Definition: ridge_layer.cpp:50
mesh_map::AbstractLayer
lvr2::VectorMap::get
boost::optional< const ValueT & > get(HandleT key) const final
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
GeometryAlgorithms.hpp
mesh_layers::RidgeLayer::ridge
lvr2::DenseVertexMap< float > ridge
Definition: ridge_layer.h:133
mesh_map::AbstractLayer::private_nh
ros::NodeHandle private_nh
mesh_map::AbstractLayer::mesh_io_ptr
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
mesh_map::AbstractLayer::notify
notify_func notify
mesh_map::AbstractLayer::mesh_ptr
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(mesh_layers::InflationLayer, mesh_map::AbstractLayer)
ridge_layer.h
lvr2::calcVertexNormals
DenseVertexMap< Normal< typename BaseVecT::CoordType > > calcVertexNormals(const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals)
mesh_layers::RidgeLayer::computeLethals
bool computeLethals()
mark vertices with values above the threshold as lethal
Definition: ridge_layer.cpp:78
lvr2::calcFaceNormals
DenseFaceMap< Normal< typename BaseVecT::CoordType > > calcFaceNormals(const BaseMesh< BaseVecT > &mesh)


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