steepness_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 
43 #include <math.h>
44 
46 
47 namespace mesh_layers
48 {
50 {
51  ROS_INFO_STREAM("Try to read steepness from map file...");
52  auto steepness_opt = mesh_io_ptr->getDenseAttributeMap<lvr2::DenseVertexMap<float>>("steepness");
53  if (steepness_opt)
54  {
55  ROS_INFO_STREAM("Successfully read steepness from map file.");
56  steepness = steepness_opt.get();
57  return computeLethals();
58  }
59 
60  return false;
61 }
62 
64 {
65  if (mesh_io_ptr->addDenseAttributeMap(steepness, "steepness"))
66  {
67  ROS_INFO_STREAM("Saved steepness to map file.");
68  return true;
69  }
70  else
71  {
72  ROS_ERROR_STREAM("Could not save steepness to map file!");
73  return false;
74  }
75 }
76 
78 {
79  ROS_INFO_STREAM("Compute lethals for \"" << layer_name << "\" (Steepness Layer) with threshold " << config.threshold);
80  lethal_vertices.clear();
81  for (auto vH : steepness)
82  {
83  if (steepness[vH] > config.threshold)
84  lethal_vertices.insert(vH);
85  }
86  ROS_INFO_STREAM("Found " << lethal_vertices.size() << " lethal vertices.");
87  return true;
88 }
89 
91 {
92  return config.threshold;
93 }
94 
96 {
97  ROS_INFO_STREAM("Computing steepness...");
98 
100 
101  auto face_normals_opt = mesh_io_ptr->getDenseAttributeMap<lvr2::DenseFaceMap<mesh_map::Normal>>("face_normals");
102 
103  if (face_normals_opt)
104  {
105  face_normals = face_normals_opt.get();
106  ROS_INFO_STREAM("Found " << face_normals.numValues() << " face normals in map file.");
107  }
108  else
109  {
110  ROS_INFO_STREAM("No face normals found in the given map file, computing them...");
111  face_normals = lvr2::calcFaceNormals(*mesh_ptr);
112  ROS_INFO_STREAM("Computed " << face_normals.numValues() << " face normals.");
113  if (mesh_io_ptr->addDenseAttributeMap(face_normals, "face_normals"))
114  {
115  ROS_INFO_STREAM("Saved face normals to map file.");
116  }
117  else
118  {
119  ROS_ERROR_STREAM("Could not save face normals to map file!");
120  return false;
121  }
122  }
123 
125  auto vertex_normals_opt = mesh_io_ptr->getDenseAttributeMap<lvr2::DenseVertexMap<mesh_map::Normal>>("vertex_normals");
126 
127  if (vertex_normals_opt)
128  {
129  vertex_normals = vertex_normals_opt.get();
130  ROS_INFO_STREAM("Found " << vertex_normals.numValues() << " vertex normals in map file!");
131  }
132  else
133  {
134  ROS_INFO_STREAM("No vertex normals found in the given map file, computing them...");
135  vertex_normals = lvr2::calcVertexNormals(*mesh_ptr, face_normals);
136  if (mesh_io_ptr->addDenseAttributeMap(vertex_normals, "vertex_normals"))
137  {
138  ROS_INFO_STREAM("Saved vertex normals to map file.");
139  }
140  else
141  {
142  ROS_ERROR_STREAM("Could not save vertex normals to map file!");
143  return false;
144  }
145  }
146 
147  steepness.reserve(mesh_ptr->nextVertexIndex());
148 
149  for (size_t i = 0; i < mesh_ptr->nextVertexIndex(); i++)
150  {
151  auto vH = lvr2::VertexHandle(i);
152  if (!mesh_ptr->containsVertex(vH))
153  {
154  continue;
155  }
156 
157  steepness.insert(vH, acos(vertex_normals[vH].z));
158  }
159 
160  return computeLethals();
161 }
162 
164 {
165  return steepness;
166 }
167 
168 void SteepnessLayer::reconfigureCallback(mesh_layers::SteepnessLayerConfig& cfg, uint32_t level)
169 {
170  bool notify = false;
171 
172  ROS_INFO_STREAM("New steepness layer config through dynamic reconfigure.");
173  if (first_config)
174  {
175  config = cfg;
176  first_config = false;
177  return;
178  }
179 
180  if (config.threshold != cfg.threshold)
181  {
182  computeLethals();
183  notify = true;
184  }
185 
186  if (notify)
187  notifyChange();
188 
189  config = cfg;
190 }
191 
192 bool SteepnessLayer::initialize(const std::string& name)
193 {
194  first_config = true;
196  new dynamic_reconfigure::Server<mesh_layers::SteepnessLayerConfig>(private_nh));
197 
198  config_callback = boost::bind(&SteepnessLayer::reconfigureCallback, this, _1, _2);
200  return true;
201 }
202 
203 } /* namespace mesh_layers */
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::SteepnessLayer::computeLethals
bool computeLethals()
mark vertices with values above the threshold as lethal
Definition: steepness_layer.cpp:77
lvr2::AttributeMap
mesh_layers::SteepnessLayer::writeLayer
virtual bool writeLayer()
try to write layer to map file
Definition: steepness_layer.cpp:63
NormalAlgorithms.hpp
mesh_layers
Definition: height_diff_layer.h:45
mesh_layers::SteepnessLayer::reconfigureCallback
void reconfigureCallback(mesh_layers::SteepnessLayerConfig &cfg, uint32_t level)
callback for incoming reconfigure configs
Definition: steepness_layer.cpp:168
mesh_map::AbstractLayer::layer_name
std::string layer_name
mesh_layers::SteepnessLayer::initialize
virtual bool initialize(const std::string &name)
initializes this layer plugin
Definition: steepness_layer.cpp:192
mesh_layers::SteepnessLayer::config_callback
dynamic_reconfigure::Server< mesh_layers::SteepnessLayerConfig >::CallbackType config_callback
Definition: steepness_layer.h:138
class_list_macros.h
lvr2::VectorMap
mesh_layers::SteepnessLayer::lethal_vertices
std::set< lvr2::VertexHandle > lethal_vertices
Definition: steepness_layer.h:134
lvr2::VertexHandle
mesh_map::AbstractLayer
lvr2::VectorMap::get
boost::optional< const ValueT & > get(HandleT key) const final
mesh_layers::SteepnessLayer::steepness
lvr2::DenseVertexMap< float > steepness
Definition: steepness_layer.h:132
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
GeometryAlgorithms.hpp
steepness_layer.h
mesh_layers::SteepnessLayer::computeLayer
virtual bool computeLayer()
calculate the values of this layer
Definition: steepness_layer.cpp:95
mesh_layers::SteepnessLayer
Costmap layer which calculates the steepness of the vertices. This is useful to avoid stairs.
Definition: steepness_layer.h:50
mesh_map::AbstractLayer::private_nh
ros::NodeHandle private_nh
mesh_map::AbstractLayer::mesh_io_ptr
std::shared_ptr< lvr2::AttributeMeshIOBase > mesh_io_ptr
mesh_layers::SteepnessLayer::threshold
virtual float threshold()
delivers the threshold above which vertices are marked lethal
Definition: steepness_layer.cpp:90
mesh_map::AbstractLayer::notify
notify_func notify
mesh_map::AbstractLayer::mesh_ptr
std::shared_ptr< lvr2::HalfEdgeMesh< Vector > > mesh_ptr
mesh_layers::SteepnessLayer::first_config
bool first_config
Definition: steepness_layer.h:140
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(mesh_layers::InflationLayer, mesh_map::AbstractLayer)
mesh_layers::SteepnessLayer::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< mesh_layers::SteepnessLayerConfig > > reconfigure_server_ptr
Definition: steepness_layer.h:137
lvr2::calcVertexNormals
DenseVertexMap< Normal< typename BaseVecT::CoordType > > calcVertexNormals(const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals)
mesh_layers::SteepnessLayer::config
SteepnessLayerConfig config
Definition: steepness_layer.h:142
mesh_layers::SteepnessLayer::costs
virtual lvr2::VertexMap< float > & costs()
deliver the current costmap
Definition: steepness_layer.cpp:163
lvr2::calcFaceNormals
DenseFaceMap< Normal< typename BaseVecT::CoordType > > calcFaceNormals(const BaseMesh< BaseVecT > &mesh)
mesh_layers::SteepnessLayer::readLayer
virtual bool readLayer()
try read layer from map file
Definition: steepness_layer.cpp:49


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