21 #include "gtest/gtest.h" 22 #include "sensor_msgs/LaserScan.h" 27 TEST(MsgConversion, LaserScanToPointCloud) {
28 sensor_msgs::LaserScan laser_scan;
29 for (
int i = 0; i < 8; ++i) {
30 laser_scan.ranges.push_back(1.f);
32 laser_scan.angle_min = 0.f;
33 laser_scan.angle_max = 8.f *
static_cast<float>(M_PI_4);
34 laser_scan.angle_increment =
static_cast<float>(M_PI_4);
35 laser_scan.range_min = 0.f;
36 laser_scan.range_max = 10.f;
39 EXPECT_TRUE(point_cloud[0].isApprox(Eigen::Vector3f(1.f, 0.f, 0.f), 1e-6));
40 EXPECT_TRUE(point_cloud[1].isApprox(
41 Eigen::Vector3f(1.f / std::sqrt(2.f), 1.f / std::sqrt(2.f), 0.f), 1e-6));
42 EXPECT_TRUE(point_cloud[2].isApprox(Eigen::Vector3f(0.f, 1.f, 0.f), 1e-6));
43 EXPECT_TRUE(point_cloud[3].isApprox(
44 Eigen::Vector3f(-1.f / std::sqrt(2.f), 1.f / std::sqrt(2.f), 0.f), 1e-6));
45 EXPECT_TRUE(point_cloud[4].isApprox(Eigen::Vector3f(-1.f, 0.f, 0.f), 1e-6));
46 EXPECT_TRUE(point_cloud[5].isApprox(
47 Eigen::Vector3f(-1.f / std::sqrt(2.f), -1.f / std::sqrt(2.f), 0.f),
49 EXPECT_TRUE(point_cloud[6].isApprox(Eigen::Vector3f(0.f, -1.f, 0.f), 1e-6));
50 EXPECT_TRUE(point_cloud[7].isApprox(
51 Eigen::Vector3f(1.f / std::sqrt(2.f), -1.f / std::sqrt(2.f), 0.f), 1e-6));
54 TEST(MsgConversion, LaserScanToPointCloudWithInfinityAndNaN) {
55 sensor_msgs::LaserScan laser_scan;
56 laser_scan.ranges.push_back(1.f);
57 laser_scan.ranges.push_back(std::numeric_limits<float>::infinity());
58 laser_scan.ranges.push_back(2.f);
59 laser_scan.ranges.push_back(std::numeric_limits<float>::quiet_NaN());
60 laser_scan.ranges.push_back(3.f);
61 laser_scan.angle_min = 0.f;
62 laser_scan.angle_max = 3.f *
static_cast<float>(M_PI_4);
63 laser_scan.angle_increment =
static_cast<float>(M_PI_4);
64 laser_scan.range_min = 2.f;
65 laser_scan.range_max = 10.f;
68 ASSERT_EQ(2, point_cloud.size());
69 EXPECT_TRUE(point_cloud[0].isApprox(Eigen::Vector3f(0.f, 2.f, 0.f), 1e-6));
70 EXPECT_TRUE(point_cloud[1].isApprox(Eigen::Vector3f(-3.f, 0.f, 0.f), 1e-6));
PointCloudWithIntensities ToPointCloudWithIntensities(const sensor_msgs::LaserScan &msg)
TEST(ActionClientDestruction, persistent_goal_handles_1)