FilterVoxelSlice.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
15 #include <mrpt/containers/yaml.h>
16 #include <mrpt/maps/COccupancyGridMap2D.h>
17 #include <mrpt/maps/CVoxelMap.h>
18 #include <mrpt/maps/CVoxelMapRGB.h>
19 #include <mrpt/math/TPose3D.h>
20 #include <mrpt/obs/CObservationPointCloud.h>
21 
24 
25 using namespace mp2p_icp_filters;
26 
28  const mrpt::containers::yaml& c, FilterVoxelSlice& parent)
29 {
30  MCP_LOAD_REQ(c, input_layer);
31  MCP_LOAD_REQ(c, output_layer);
32 
35 }
36 
38 {
39  mrpt::system::COutputLogger::setLoggerName("FilterVoxelSlice");
40 }
41 
42 void FilterVoxelSlice::initialize(const mrpt::containers::yaml& c)
43 {
44  MRPT_START
45 
46  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
47  params_.load_from_yaml(c, *this);
48 
49  MRPT_END
50 }
51 
53 {
54  MRPT_START
55 
57 
59 
60  // In:
61  ASSERT_(!params_.input_layer.empty());
62  ASSERTMSG_(
63  inOut.layers.count(params_.input_layer),
64  mrpt::format(
65  "Input layer '%s' was not found.", params_.input_layer.c_str()));
66 
67  const auto in = inOut.layers.at(params_.input_layer);
68  auto inVoxelMap = std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(in);
69  auto inVoxelMapRGB =
70  std::dynamic_pointer_cast<mrpt::maps::CVoxelMapRGB>(in);
71 
72  if (!inVoxelMap && !inVoxelMapRGB)
73  {
74  THROW_EXCEPTION_FMT(
75  "Input layer is of class '%s', expected one of: "
76  "mrpt::maps::CVoxelMap, mrpt::maps::CVoxelMapRGB",
77  in->GetRuntimeClass()->className);
78  }
79 
80  // Out:
81  ASSERT_(!params_.output_layer.empty());
82 
83  auto occGrid = mrpt::maps::COccupancyGridMap2D::Create();
84  inOut.layers[params_.output_layer] = occGrid;
85 
86  // Set the grid "height" (z):
87  occGrid->insertionOptions.mapAltitude =
89 
90  // make the conversion:
91  if (inVoxelMap)
92  {
93  auto& grid =
94  const_cast<Bonxai::VoxelGrid<mrpt::maps::CVoxelMap::voxel_node_t>&>(
95  inVoxelMap->grid());
96 
97  const mrpt::math::TBoundingBoxf bbox = inVoxelMap->boundingBox();
98 
99  occGrid->setSize(
100  bbox.min.x, bbox.max.x, bbox.min.y, bbox.max.y, grid.resolution);
101 
102  const auto zCoordMin = Bonxai::PosToCoord(
103  {0., 0., params_.slice_z_min}, grid.inv_resolution);
104  const auto zCoordMax = Bonxai::PosToCoord(
105  {0., 0., params_.slice_z_max}, grid.inv_resolution);
106 
107  // Go thru all voxels:
108  auto lmbdPerVoxel = [&](mrpt::maps::CVoxelMap::voxel_node_t& data,
109  const Bonxai::CoordT& coord) {
110  // are we at the correct height?
111  if (coord.z < zCoordMin.z || coord.z > zCoordMax.z) return;
112  const auto pt = Bonxai::CoordToPos(coord, grid.resolution);
113 
114  const double freeness = inVoxelMap->l2p(data.occupancy);
115 
116  // Bayesian fuse information:
117  occGrid->updateCell(
118  occGrid->x2idx(pt.x), occGrid->y2idx(pt.y), freeness);
119  }; // end lambda for each voxel
120 
121  grid.forEachCell(lmbdPerVoxel);
122  }
123  else if (inVoxelMapRGB)
124  {
125  // ...
126  }
127 
128  MRPT_END
129 }
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterVoxelSlice, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::FilterVoxelSlice::FilterVoxelSlice
FilterVoxelSlice()
Definition: FilterVoxelSlice.cpp:37
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:138
mp2p_icp_filters::FilterVoxelSlice::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, FilterVoxelSlice &parent)
Definition: FilterVoxelSlice.cpp:27
FilterVoxelSlice.h
Takes an input layer of type CVoxelMap (Bonxai) and extracts one 2D slice as an occupancy gridmap.
mp2p_icp_filters::FilterVoxelSlice::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterVoxelSlice.cpp:52
mp2p_icp_filters::FilterVoxelSlice::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterVoxelSlice.cpp:42
DECLARE_PARAMETER_IN_REQ
#define DECLARE_PARAMETER_IN_REQ(__yaml, __variable, __object)
Definition: Parameterizable.h:167
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterVoxelSlice
Definition: FilterVoxelSlice.h:30
boost::posix_time
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
mp2p_icp_filters::FilterVoxelSlice::Parameters::slice_z_min
double slice_z_min
Definition: FilterVoxelSlice.h:50
mp2p_icp_filters::FilterVoxelSlice::Parameters::output_layer
std::string output_layer
Definition: FilterVoxelSlice.h:48
mp2p_icp_filters::FilterVoxelSlice::params_
Parameters params_
Definition: FilterVoxelSlice.h:55
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterVoxelSlice::Parameters::slice_z_max
double slice_z_max
Definition: FilterVoxelSlice.h:51
mp2p_icp_filters::FilterVoxelSlice::Parameters::input_layer
std::string input_layer
Definition: FilterVoxelSlice.h:47


mp2p_icp
Author(s):
autogenerated on Thu Oct 17 2024 02:45:33