Skip to content

Commit 2919f30

Browse files
committed
Fix usage of some deprecated cloud types
1 parent 0791151 commit 2919f30

2 files changed

Lines changed: 22 additions & 26 deletions

File tree

tests/test-mp2p_FilterDecimateVoxels.cpp

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020

2121
#include <mp2p_icp/metricmap.h>
2222
#include <mp2p_icp_filters/FilterDecimateVoxels.h>
23-
#include <mrpt/maps/CPointsMapXYZI.h>
23+
#include <mrpt/maps/CGenericPointsMap.h>
2424
#include <mrpt/math/ops_containers.h>
2525
#include <mrpt/system/filesystem.h>
2626
#include <mrpt/version.h>
@@ -31,7 +31,9 @@ using namespace mp2p_icp;
3131
// Helper to create a consistent point map for testing
3232
mrpt::maps::CPointsMap::Ptr createTestPoints(size_t n_x, size_t n_y)
3333
{
34-
auto pc = mrpt::maps::CPointsMapXYZI::Create();
34+
auto pc = mrpt::maps::CGenericPointsMap::Create();
35+
pc->registerField_float(mrpt::maps::CPointsMap::POINT_FIELD_INTENSITY);
36+
3537
// Create a 2D grid of points, 10x10. Each point has a small, known Z-offset.
3638
for (size_t i = 0; i < n_x; ++i)
3739
{
@@ -43,12 +45,7 @@ mrpt::maps::CPointsMap::Ptr createTestPoints(size_t n_x, size_t n_y)
4345
float intensity = static_cast<float>(i * n_y + j);
4446

4547
pc->insertPointFast(x, y, z);
46-
#if MRPT_VERSION >= 0x020f00
47-
pc->insertPointField_float(
48-
mrpt::maps::CPointsMapXYZI::POINT_FIELD_INTENSITY, intensity);
49-
#else
50-
pc->insertPointField_Intensity(intensity);
51-
#endif
48+
pc->insertPointField_float(mrpt::maps::CPointsMap::POINT_FIELD_INTENSITY, intensity);
5249
}
5350
}
5451
return pc;
@@ -196,10 +193,8 @@ void test_decimate_method(
196193
ASSERT_NEAR_(bb.min.z, 0.0f, 0.2f);
197194
}
198195

199-
// Since we created CPointsMapXYZI, the output should also have intensity.
200-
#if MRPT_VERSION >= 0x020f00
201-
ASSERT_(output_pc->hasPointField(mrpt::maps::CPointsMapXYZI::POINT_FIELD_INTENSITY));
202-
#endif
196+
// The output should also have intensity.
197+
ASSERT_(output_pc->hasPointField(mrpt::maps::CPointsMap::POINT_FIELD_INTENSITY));
203198
std::cout << " Success ✅." << std::endl;
204199
}
205200

tests/test-mp2p_deskew.cpp

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
#include <mp2p_icp/metricmap.h>
2323
#include <mp2p_icp_filters/FilterDeskew.h>
2424
#include <mp2p_icp_filters/sm2mm.h>
25-
#include <mrpt/maps/CPointsMapXYZIRT.h>
25+
#include <mrpt/maps/CGenericPointsMap.h>
2626
#include <mrpt/maps/CSimplePointsMap.h>
2727
#include <mrpt/math/TPoint3D.h>
2828
#include <mrpt/math/TTwist3D.h>
@@ -47,7 +47,7 @@ struct SimulationParams
4747
mp2p_icp_filters::MotionCompensationMethod deskew_method =
4848
mp2p_icp_filters::MotionCompensationMethod::None;
4949

50-
std::string outputMapClass = "mrpt::maps::CPointsMapXYZIRT";
50+
std::string outputMapClass = "mrpt::maps::CGenericPointsMap";
5151
};
5252

5353
struct SimulationResult
@@ -238,11 +238,13 @@ Scenario simulate_scenario(const SimulationParams& p)
238238
return s;
239239
}
240240

241-
mrpt::maps::CPointsMapXYZIRT::Ptr simulate_skewed_points(
241+
mrpt::maps::CGenericPointsMap::Ptr simulate_skewed_points(
242242
const mrpt::Clock::time_point& stamp, const mrpt::poses::CPose3DInterpolator& gtKeyframes,
243243
const std::vector<mrpt::math::TPoint3D>& gtPoints, const double lidar_scan_period)
244244
{
245-
auto pts = mrpt::maps::CPointsMapXYZIRT::Create();
245+
auto pts = mrpt::maps::CGenericPointsMap::Create();
246+
pts->registerField_float(mrpt::maps::CPointsMap::POINT_FIELD_TIMESTAMP);
247+
pts->registerField_float(mrpt::maps::CPointsMap::POINT_FIELD_INTENSITY);
246248

247249
// Simulate a scan where each point is acquired at a different time during the scan period.
248250
// Assume points are acquired sequentially over [stamp, stamp + lidar_scan_period)
@@ -269,11 +271,9 @@ mrpt::maps::CPointsMapXYZIRT::Ptr simulate_skewed_points(
269271
// Add to map, with time offset
270272
pts->insertPointFast(pt_local.x, pt_local.y, pt_local.z);
271273

272-
#if MRPT_VERSION >= 0x020f00 // 2.15.0
273-
pts->insertPointField_float("t", static_cast<float>(rel_time));
274-
#else
275-
pts->insertPointField_Timestamp(static_cast<float>(rel_time));
276-
#endif
274+
pts->insertPointField_float(
275+
mrpt::maps::CPointsMap::POINT_FIELD_TIMESTAMP, static_cast<float>(rel_time));
276+
pts->insertPointField_float(mrpt::maps::CPointsMap::POINT_FIELD_INTENSITY, 1.0f);
277277

278278
#if 0
279279
std::cout << "PT[" << i << "] x: " << pt_local.x << ", y: " << pt_local.y
@@ -556,8 +556,9 @@ mrpt::maps::CSimplePointsMap simulate_gt_local_points(
556556
} // end for each timestep
557557

558558
// Now, reconstruct the points within the SM:
559-
const auto sm2mmPipeline = mrpt::containers::yaml::FromText(mrpt::format(
560-
R"yaml(
559+
const auto sm2mmPipeline = mrpt::containers::yaml::FromText(
560+
mrpt::format(
561+
R"yaml(
561562
# --------------------------------------------------------
562563
# 1) Generator (observation -> local frame metric maps)
563564
# --------------------------------------------------------
@@ -594,7 +595,7 @@ mrpt::maps::CSimplePointsMap simulate_gt_local_points(
594595
# one or more layers to remove
595596
pointcloud_layer_to_remove: ["raw"]
596597
)yaml",
597-
mrpt::typemeta::enum2str(p.deskew_method).c_str(), p.outputMapClass.c_str()));
598+
mrpt::typemeta::enum2str(p.deskew_method).c_str(), p.outputMapClass.c_str()));
598599

599600
mp2p_icp::metric_map_t mm;
600601
mp2p_icp_filters::sm2mm_options_t sm2mm_opts;
@@ -619,8 +620,8 @@ mrpt::maps::CSimplePointsMap simulate_gt_local_points(
619620
return fields;
620621
}();
621622

622-
ASSERT_EQUAL_(outFields.count("intensity"), 1);
623-
ASSERT_EQUAL_(outFields.count("t"), 1);
623+
ASSERT_EQUAL_(outFields.count(std::string(mrpt::maps::CPointsMap::POINT_FIELD_INTENSITY)), 1);
624+
ASSERT_EQUAL_(outFields.count(std::string(mrpt::maps::CPointsMap::POINT_FIELD_TIMESTAMP)), 1);
624625

625626
for (size_t i = 0; i < deskewedPts->size(); i++)
626627
{

0 commit comments

Comments
 (0)