Skip to content

Commit

Permalink
Fix unit tests due to lambda lack supprot for constexpr params
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Oct 17, 2023
1 parent 02b89c3 commit 7ee3989
Show file tree
Hide file tree
Showing 3 changed files with 130 additions and 144 deletions.
5 changes: 2 additions & 3 deletions ouster-ros/src/point_meta_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,8 @@ inline auto& point_element_get<2, pcl::PointXYZI>(pcl::PointXYZI& point) { retur
template <>
inline auto& point_element_get<3, pcl::PointXYZI>(pcl::PointXYZI& point) { return point.intensity; }


template <std::size_t Index, std::size_t N, typename PointT, typename UnaryOp>
void iterate_point(PointT& point, UnaryOp unary_op) {
constexpr void iterate_point(PointT& point, UnaryOp unary_op) {
if constexpr (Index < N) {
unary_op(point_element_get<Index>(point));
iterate_point<Index + 1, N, PointT, UnaryOp>(point, unary_op);
Expand All @@ -64,7 +63,7 @@ void iterate_point(PointT& point, UnaryOp unary_op) {
}

template <std::size_t Index, std::size_t N, typename PointT, typename EnumOp>
void enumerate_point(PointT& point, EnumOp enum_op) {
constexpr void enumerate_point(PointT& point, EnumOp enum_op) {
if constexpr (Index < N) {
enum_op(Index, point_element_get<Index>(point));
enumerate_point<Index + 1, N, PointT, EnumOp>(point, enum_op);
Expand Down
40 changes: 23 additions & 17 deletions ouster-ros/test/point_accessor_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,13 +77,16 @@ TEST_F(PointAccessorTest, ElementCount) {
EXPECT_EQ(point_element_count(pt_os_point), 9U);
}

template <typename PointT>
void expect_element_equals_index(PointT& pt) {
enumerate_point<0, point_element_count(pt)>(pt, [](auto index, auto value) {
EXPECT_EQ(value, static_cast<decltype(value)>(index));
});
}


TEST_F(PointAccessorTest, ExpectElementValueSameAsIndex) {

auto expect_element_equals_index = [](auto& pt) {
enumerate_point<0, point_element_count(pt)>(pt, [](auto index, auto value) {
EXPECT_EQ(value, static_cast<decltype(value)>(index));
});
};

// pcl + velodyne point types
expect_element_equals_index(pt_xyz);
Expand All @@ -98,19 +101,22 @@ TEST_F(PointAccessorTest, ExpectElementValueSameAsIndex) {
expect_element_equals_index(pt_os_point);
}

TEST_F(PointAccessorTest, ExpectPointElementValueIncrementedByValue) {
template <typename PointT>
void increment_by_value(PointT& pt, int increment) {
iterate_point<0, point_element_count(pt)>(pt, [increment](auto& value) {
value += increment;
});
}

auto increment_by_value = [](auto& pt, auto increment) {
iterate_point<0, point_element_count(pt)>(pt, [increment](auto& value) {
value += increment;
});
};

auto expect_value_increased_by_value = [](auto& pt, auto increment) {
enumerate_point<0, point_element_count(pt)>(pt, [increment](auto index, auto value) {
EXPECT_EQ(value, static_cast<decltype(value)>(index + increment));
});
};
template <typename PointT>
void expect_value_increased_by_value(PointT& pt, int increment) {
enumerate_point<0, point_element_count(pt)>(pt, [increment](auto index, auto value) {
EXPECT_EQ(value, static_cast<decltype(value)>(index + increment));
});
};


TEST_F(PointAccessorTest, ExpectPointElementValueIncrementedByValue) {

auto inc = 1;

Expand Down
229 changes: 105 additions & 124 deletions ouster-ros/test/point_transform_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,18 @@ using namespace ouster_ros;
using namespace std;

class PointTransformTest : public ::testing::Test {
protected:
void SetUp() override {

auto initialize_point_elements_with_randoms = [](auto& pt) {

std::default_random_engine g;
// choose a random value between 0 and 128.
std::uniform_real_distribution<double> d(0.0, 128.0);

iterate_point<0, point_element_count(pt)>(pt, [&g, &d](auto& value) {
using value_type = std::remove_reference_t<decltype(value)>;
value = static_cast<value_type>(d(g));
});
};
template <typename PointT>
void initialize_point_elements_with_randoms(PointT& pt) {
std::default_random_engine g;
std::uniform_real_distribution<double> d(0.0, 128.0);
iterate_point<0, point_element_count(pt)>(pt, [&g, &d](auto& value) {
using value_type = std::remove_reference_t<decltype(value)>;
value = static_cast<value_type>(d(g));
});
};

protected:
void SetUp() override {
// pcl + velodyne point types
initialize_point_elements_with_randoms(pt_xyz);
initialize_point_elements_with_randoms(pt_xyzi);
Expand All @@ -40,8 +37,7 @@ class PointTransformTest : public ::testing::Test {
initialize_point_elements_with_randoms(pt_os_point);
}

void TearDown() override {
}
void TearDown() override {}

// pcl & velodyne point types
pcl::PointXYZ pt_xyz;
Expand All @@ -56,133 +52,120 @@ class PointTransformTest : public ::testing::Test {
ouster_ros::Point pt_os_point;
};


template <typename PointT, typename PointU>
void expect_points_xyz_equal(PointT& point1, PointU& point2) {
EXPECT_EQ(point1.x, point2.x);
EXPECT_EQ(point1.y, point2.y);
EXPECT_EQ(point1.z, point2.z);
EXPECT_EQ(point1.x, point2.x);
EXPECT_EQ(point1.y, point2.y);
EXPECT_EQ(point1.z, point2.z);
}

template <typename PointTGT, typename PointSRC>
void verify_point_transform(PointTGT& tgt_pt, const PointSRC& src_pt) {
// t: timestamp
CondBinaryOp<has_t_v<PointTGT> && has_t_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.t, src_pt.t);
});

// t: timestamp
CondBinaryOp<has_t_v<PointTGT> && has_t_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.t, src_pt.t);
}
);
CondBinaryOp<has_t_v<PointTGT> && !has_t_v<PointSRC>>::run(
tgt_pt, src_pt,
[](const auto& tgt_pt, const auto&) { EXPECT_EQ(tgt_pt.t, 0U); });

CondBinaryOp<has_t_v<PointTGT> && !has_t_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.t, 0U);
}
);
// ring
CondBinaryOp<has_ring_v<PointTGT> && has_ring_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.ring, src_pt.ring);
});

// ring
CondBinaryOp<has_ring_v<PointTGT> && has_ring_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.ring, src_pt.ring);
}
);
CondBinaryOp<has_ring_v<PointTGT> && !has_ring_v<PointSRC>>::run(
tgt_pt, src_pt,
[](const auto& tgt_pt, const auto&) { EXPECT_EQ(tgt_pt.ring, 0U); });

CondBinaryOp<has_ring_v<PointTGT> && !has_ring_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.ring, 0U);
}
);
// range
CondBinaryOp<has_range_v<PointTGT> && has_range_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.range, src_pt.range);
});

// range
CondBinaryOp<has_range_v<PointTGT> && has_range_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.range, src_pt.range);
}
);
CondBinaryOp<has_range_v<PointTGT> && !has_range_v<PointSRC>>::run(
tgt_pt, src_pt,
[](const auto& tgt_pt, const auto&) { EXPECT_EQ(tgt_pt.range, 0U); });

CondBinaryOp<has_range_v<PointTGT> && !has_range_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) { EXPECT_EQ(tgt_pt.range, 0U); }
);
// signal
CondBinaryOp<has_signal_v<PointTGT> && has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.signal, src_pt.signal);
});

// signal
CondBinaryOp<has_signal_v<PointTGT> && has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.signal, src_pt.signal);
}
);
CondBinaryOp<has_signal_v<PointTGT> && !has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.signal, static_cast<decltype(tgt_pt.signal)>(0));
});

CondBinaryOp<has_signal_v<PointTGT> && !has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.signal, static_cast<decltype(tgt_pt.signal)>(0));
}
);

// intensity <- signal
CondBinaryOp<has_intensity_v<PointTGT> && has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.intensity, static_cast<decltype(tgt_pt.intensity)>(src_pt.signal));
}
);

CondBinaryOp<has_intensity_v<PointTGT> && !has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.intensity, static_cast<decltype(tgt_pt.intensity)>(0));
}
);

// reflectivity
CondBinaryOp<has_reflectivity_v<PointTGT> && has_reflectivity_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.reflectivity, src_pt.reflectivity);
}
);
// intensity <- signal
CondBinaryOp<has_intensity_v<PointTGT> && has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.intensity,
static_cast<decltype(tgt_pt.intensity)>(src_pt.signal));
});

CondBinaryOp<has_reflectivity_v<PointTGT> && !has_reflectivity_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.reflectivity, static_cast<decltype(tgt_pt.reflectivity)>(0));
}
);
CondBinaryOp<has_intensity_v<PointTGT> && !has_signal_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.intensity,
static_cast<decltype(tgt_pt.intensity)>(0));
});

// near_ir
CondBinaryOp<has_near_ir_v<PointTGT> && has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.near_ir, src_pt.near_ir);
}
);
// reflectivity
CondBinaryOp<has_reflectivity_v<PointTGT> && has_reflectivity_v<PointSRC>>::
run(tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.reflectivity, src_pt.reflectivity);
});

CondBinaryOp<has_near_ir_v<PointTGT> && has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.near_ir, static_cast<decltype(tgt_pt.near_ir)>(0));
}
);

// ambient <- near_ir
CondBinaryOp<has_ambient_v<PointTGT> && has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.ambient, static_cast<decltype(tgt_pt.ambient)>(src_pt.near_ir));
}
);

CondBinaryOp<has_ambient_v<PointTGT> && !has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.ambient, static_cast<decltype(tgt_pt.ambient)>(0));
}
);
}
CondBinaryOp<has_reflectivity_v<PointTGT> &&
!has_reflectivity_v<PointSRC>>::
run(tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.reflectivity,
static_cast<decltype(tgt_pt.reflectivity)>(0));
});

TEST_F(PointTransformTest, ExpectPointFieldZeroed) {
// near_ir
CondBinaryOp<has_near_ir_v<PointTGT> && has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.near_ir, src_pt.near_ir);
});

// lambda function to check that point elements other than xyz have been zeroed
auto expect_point_fields_zeros = [](auto& pt) {
// starting at 3 to skip xyz
iterate_point<3, point_element_count(pt)>(pt, [](auto value) {
EXPECT_EQ(value, static_cast<decltype(value)>(0));
CondBinaryOp<has_near_ir_v<PointTGT> && has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.near_ir, static_cast<decltype(tgt_pt.near_ir)>(0));
});
};

// ambient <- near_ir
CondBinaryOp<has_ambient_v<PointTGT> && has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto& src_pt) {
EXPECT_EQ(tgt_pt.ambient,
static_cast<decltype(tgt_pt.ambient)>(src_pt.near_ir));
});

CondBinaryOp<has_ambient_v<PointTGT> && !has_near_ir_v<PointSRC>>::run(
tgt_pt, src_pt, [](const auto& tgt_pt, const auto&) {
EXPECT_EQ(tgt_pt.ambient, static_cast<decltype(tgt_pt.ambient)>(0));
});
}

// lambda function to check that point elements other than xyz have been zeroed
template <typename PointT>
void expect_point_fields_zeros(PointT& pt) {
// starting at 3 to skip xyz
iterate_point<3, point_element_count(pt)>(pt, [](auto value) {
EXPECT_EQ(value, static_cast<decltype(value)>(0));
});
};

TEST_F(PointTransformTest, ExpectPointFieldZeroed) {
transform_point(pt_xyzi, pt_xyz);
expect_points_xyz_equal(pt_xyzi, pt_xyz);
expect_point_fields_zeros(pt_xyzi); // equivalent to EXPECT_EQ(pt_xyzi.intensity, 0.0f);
expect_point_fields_zeros(
pt_xyzi); // equivalent to EXPECT_EQ(pt_xyzi.intensity, 0.0f);

transform_point(pt_xyzir, pt_xyz);
expect_points_xyz_equal(pt_xyzir, pt_xyz);
Expand Down Expand Up @@ -238,7 +221,6 @@ TEST_F(PointTransformTest, TestTransformReduce_RNG19_RFL8_SIG16_NIR16_DUAL) {
}

TEST_F(PointTransformTest, TestTransformReduce_RNG19_RFL8_SIG16_NIR16) {

transform_point(pt_xyz, pt_rg19_rf8_sg16_nr16);
expect_points_xyz_equal(pt_xyz, pt_rg19_rf8_sg16_nr16);
verify_point_transform(pt_xyz, pt_rg19_rf8_sg16_nr16);
Expand Down Expand Up @@ -266,8 +248,8 @@ TEST_F(PointTransformTest, TestTransformReduce_RNG15_RFL8_NIR8) {
verify_point_transform(pt_xyzir, pt_rg15_rfl8_nr8);
}

TEST_F(PointTransformTest, TestTransform_SensorNativePoints_2_ouster_ros_Point) {

TEST_F(PointTransformTest,
TestTransform_SensorNativePoints_2_ouster_ros_Point) {
transform_point(pt_os_point, pt_legacy);
expect_points_xyz_equal(pt_os_point, pt_legacy);
verify_point_transform(pt_os_point, pt_legacy);
Expand All @@ -283,5 +265,4 @@ TEST_F(PointTransformTest, TestTransform_SensorNativePoints_2_ouster_ros_Point)
transform_point(pt_os_point, pt_rg15_rfl8_nr8);
expect_points_xyz_equal(pt_os_point, pt_rg15_rfl8_nr8);
verify_point_transform(pt_os_point, pt_rg15_rfl8_nr8);

}

0 comments on commit 7ee3989

Please sign in to comment.