33 #include <gtest/gtest.h> 36 #include <sensor_msgs/PointCloud2.h> 37 #include <sensor_msgs/LaserScan.h> 74 void recv(
const sensor_msgs::LaserScanConstPtr& msg)
103 const uint32_t POINT_STEP = 32;
104 sensor_msgs::PointCloud2 msg;
105 msg.header.frame_id = cloud.
header.frame_id;
106 msg.header.stamp = cloud.
header.stamp;
107 msg.fields.resize(5);
108 msg.fields[0].name =
"x";
109 msg.fields[0].offset = 0;
110 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
111 msg.fields[0].count = 1;
112 msg.fields[1].name =
"y";
113 msg.fields[1].offset = 4;
114 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
115 msg.fields[1].count = 1;
116 msg.fields[2].name =
"z";
117 msg.fields[2].offset = 8;
118 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
119 msg.fields[2].count = 1;
120 msg.fields[3].name =
"intensity";
121 msg.fields[3].offset = 16;
122 msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
123 msg.fields[3].count = 1;
124 msg.fields[4].name =
"ring";
125 msg.fields[4].offset = 20;
126 msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
127 msg.fields[4].count = 1;
128 msg.data.resize(std::max((
size_t)1, cloud.
points.size()) * POINT_STEP, 0x00);
129 msg.point_step = POINT_STEP;
130 msg.row_step = msg.data.size();
132 msg.width = msg.row_step / POINT_STEP;
133 msg.is_bigendian =
false;
135 uint8_t *ptr = msg.data.data();
137 for (
size_t i = 0; i < cloud.
points.size(); i++)
139 *(
reinterpret_cast<float*
>(ptr + 0)) = cloud.
points[i].x;
140 *(
reinterpret_cast<float*
>(ptr + 4)) = cloud.
points[i].y;
141 *(
reinterpret_cast<float*
>(ptr + 8)) = cloud.
points[i].z;
142 *(
reinterpret_cast<float*
>(ptr + 16)) = cloud.
points[i].i;
143 *(
reinterpret_cast<uint16_t*
>(ptr + 20)) = cloud.
points[i].r;
153 const uint32_t POINT_STEP = 19;
154 sensor_msgs::PointCloud2 msg;
155 msg.header.frame_id = cloud.
header.frame_id;
156 msg.header.stamp = cloud.
header.stamp;
157 msg.fields.resize(5);
158 msg.fields[0].name =
"z";
159 msg.fields[0].offset = 4;
160 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
161 msg.fields[0].count = 1;
162 msg.fields[1].name =
"y";
163 msg.fields[1].offset = 8;
164 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
165 msg.fields[1].count = 1;
166 msg.fields[2].name =
"x";
167 msg.fields[2].offset = 12;
168 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
169 msg.fields[2].count = 1;
170 msg.fields[3].name =
"intensity";
171 msg.fields[3].offset = 0;
172 msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
173 msg.fields[3].count = 1;
174 msg.fields[4].name =
"ring";
175 msg.fields[4].offset = 16;
176 msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
177 msg.fields[4].count = 1;
178 msg.data.resize(std::max((
size_t)1, cloud.
points.size()) * POINT_STEP, 0x00);
179 msg.point_step = POINT_STEP;
180 msg.row_step = msg.data.size();
182 msg.width = msg.row_step / POINT_STEP;
183 msg.is_bigendian =
false;
185 uint8_t *ptr = msg.data.data();
187 for (
size_t i = 0; i < cloud.
points.size(); i++)
189 *(
reinterpret_cast<float*
>(ptr + 0)) = cloud.
points[i].i;
190 *(
reinterpret_cast<float*
>(ptr + 4)) = cloud.
points[i].z;
191 *(
reinterpret_cast<float*
>(ptr + 8)) = cloud.
points[i].y;
192 *(
reinterpret_cast<float*
>(ptr + 12)) = cloud.
points[i].x;
193 *(
reinterpret_cast<uint16_t*
>(ptr + 16)) = cloud.
points[i].r;
203 const uint32_t POINT_STEP = 15;
204 sensor_msgs::PointCloud2 msg;
205 msg.header.frame_id = cloud.
header.frame_id;
206 msg.header.stamp = cloud.
header.stamp;
207 msg.fields.resize(4);
208 msg.fields[0].name =
"x";
209 msg.fields[0].offset = 0;
210 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
211 msg.fields[0].count = 1;
212 msg.fields[1].name =
"y";
213 msg.fields[1].offset = 4;
214 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
215 msg.fields[1].count = 1;
216 msg.fields[2].name =
"z";
217 msg.fields[2].offset = 8;
218 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
219 msg.fields[2].count = 1;
220 msg.fields[3].name =
"ring";
221 msg.fields[3].offset = 12;
222 msg.fields[3].datatype = sensor_msgs::PointField::UINT16;
223 msg.fields[3].count = 1;
224 msg.data.resize(std::max((
size_t)1, cloud.
points.size()) * POINT_STEP, 0x00);
225 msg.point_step = POINT_STEP;
226 msg.row_step = msg.data.size();
228 msg.width = msg.row_step / POINT_STEP;
229 msg.is_bigendian =
false;
231 uint8_t *ptr = msg.data.data();
233 for (
size_t i = 0; i < cloud.
points.size(); i++)
235 *(
reinterpret_cast<float*
>(ptr + 0)) = cloud.
points[i].x;
236 *(
reinterpret_cast<float*
>(ptr + 4)) = cloud.
points[i].y;
237 *(
reinterpret_cast<float*
>(ptr + 8)) = cloud.
points[i].z;
238 *(
reinterpret_cast<uint16_t*
>(ptr + 12)) = cloud.
points[i].r;
248 const uint32_t POINT_STEP = 2;
249 sensor_msgs::PointCloud2 msg;
251 msg.fields.resize(1);
252 msg.fields[0].name =
"ring";
253 msg.fields[0].offset = 0;
254 msg.fields[0].datatype = sensor_msgs::PointField::UINT16;
255 msg.fields[0].count = 1;
256 msg.data.resize(std::max((
size_t)1, cloud.
points.size()) * POINT_STEP, 0x00);
257 msg.point_step = POINT_STEP;
258 msg.row_step = msg.data.size();
260 msg.width = msg.row_step / POINT_STEP;
261 uint8_t *ptr = msg.data.data();
263 for (
size_t i = 0; i < cloud.
points.size(); i++)
265 *(
reinterpret_cast<uint16_t*
>(ptr + 0)) = cloud.
points[i].r;
275 const uint32_t POINT_STEP = 16;
276 sensor_msgs::PointCloud2 msg;
277 msg.header.frame_id = cloud.
header.frame_id;
278 msg.header.stamp = cloud.
header.stamp;
279 msg.fields.resize(4);
280 msg.fields[0].name =
"x";
281 msg.fields[0].offset = 0;
282 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
283 msg.fields[0].count = 1;
284 msg.fields[1].name =
"y";
285 msg.fields[1].offset = 4;
286 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
287 msg.fields[1].count = 1;
288 msg.fields[2].name =
"z";
289 msg.fields[2].offset = 8;
290 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
291 msg.fields[2].count = 1;
292 msg.fields[3].name =
"ring";
293 msg.fields[3].offset = 12;
294 msg.fields[3].datatype = sensor_msgs::PointField::UINT32;
295 msg.fields[3].count = 1;
296 msg.data.resize(std::max((
size_t)1, cloud.
points.size()) * POINT_STEP, 0x00);
297 msg.point_step = POINT_STEP;
298 msg.row_step = msg.data.size();
300 msg.width = msg.row_step / POINT_STEP;
301 msg.is_bigendian =
false;
303 uint8_t *ptr = msg.data.data();
305 for (
size_t i = 0; i < cloud.
points.size(); i++)
307 *(
reinterpret_cast<float*
>(ptr + 0)) = cloud.
points[i].x;
308 *(
reinterpret_cast<float*
>(ptr + 4)) = cloud.
points[i].y;
309 *(
reinterpret_cast<float*
>(ptr + 8)) = cloud.
points[i].z;
310 *(
reinterpret_cast<uint32_t*
>(ptr + 12)) = cloud.
points[i].r;
320 const uint32_t POINT_STEP = 12;
321 sensor_msgs::PointCloud2 msg;
323 msg.fields.resize(3);
324 msg.fields[0].name =
"x";
325 msg.fields[0].offset = 0;
326 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
327 msg.fields[0].count = 1;
328 msg.fields[1].name =
"y";
329 msg.fields[1].offset = 4;
330 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
331 msg.fields[1].count = 1;
332 msg.fields[2].name =
"z";
333 msg.fields[2].offset = 8;
334 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
335 msg.fields[2].count = 1;
336 msg.data.resize(std::max((
size_t)1, cloud.
points.size()) * POINT_STEP, 0x00);
337 msg.point_step = POINT_STEP;
338 msg.row_step = msg.data.size();
340 msg.width = msg.row_step / POINT_STEP;
341 uint8_t *ptr = msg.data.data();
343 for (
size_t i = 0; i < cloud.
points.size(); i++)
345 *(
reinterpret_cast<float*
>(ptr + 0)) = cloud.
points[i].x;
346 *(
reinterpret_cast<float*
>(ptr + 4)) = cloud.
points[i].y;
347 *(
reinterpret_cast<float*
>(ptr + 8)) = cloud.
points[i].z;
357 const uint32_t POINT_STEP = 16;
358 sensor_msgs::PointCloud2 msg;
360 msg.data.resize(1 * POINT_STEP, 0x00);
361 msg.point_step = POINT_STEP;
362 msg.row_step = msg.data.size();
364 msg.width = msg.row_step / POINT_STEP;
376 size_t index = SIZE_MAX;
377 float delta = INFINITY;
379 for (
size_t i = 0; i < cloud.
points.size(); i++)
381 if (cloud.
points[i].r == ring)
400 EXPECT_EQ(cloud.
header.frame_id,
g_scan.header.frame_id);
402 for (
size_t i = 0; i <
g_scan.ranges.size(); i++)
404 EXPECT_EQ(INFINITY,
g_scan.ranges[i]);
409 EXPECT_EQ(0,
g_scan.intensities.size());
413 EXPECT_EQ(
g_scan.ranges.size(),
g_scan.intensities.size());
415 for (
size_t i = 0; i <
g_scan.intensities.size(); i++)
417 EXPECT_EQ(0.0,
g_scan.intensities[i]);
426 EXPECT_EQ(cloud.
header.frame_id,
g_scan.header.frame_id);
427 EXPECT_EQ(intensity ?
g_scan.ranges.size() : 0,
g_scan.intensities.size());
430 for (
size_t i = 0; i <
g_scan.ranges.size(); i++)
432 double r =
g_scan.ranges[i];
434 if (std::isfinite(r))
436 float a =
g_scan.angle_min + i *
g_scan.angle_increment;
437 float x =
g_scan.ranges[i] * cosf(a);
438 float y =
g_scan.ranges[i] * sinf(a);
439 float e =
g_scan.ranges[i] *
g_scan.angle_increment +
static_cast<float>(1e-3);
442 if (index < cloud.
points.size())
445 EXPECT_NEAR(cloud.
points[index].x, x, e);
446 EXPECT_NEAR(cloud.
points[index].y, y, e);
448 if (i <
g_scan.intensities.size())
450 EXPECT_EQ(cloud.
points[index].i,
g_scan.intensities[i]);
460 EXPECT_EQ(INFINITY, r);
466 EXPECT_EQ(cloud.
points.size() / ring_count, count);
474 EXPECT_EQ(cloud.
header.frame_id,
g_scan.header.frame_id);
475 EXPECT_EQ(intensity ?
g_scan.ranges.size() : 0,
g_scan.intensities.size());
477 for (
size_t i = 0; i <
g_scan.ranges.size(); i++)
479 double r =
g_scan.ranges[i];
481 if (std::isfinite(r))
483 float a =
g_scan.angle_min + i *
g_scan.angle_increment;
484 float x =
g_scan.ranges[i] * cosf(a);
485 float y =
g_scan.ranges[i] * sinf(a);
486 float e =
g_scan.ranges[i] *
g_scan.angle_increment +
static_cast<float>(1e-3);
489 if (index < cloud.
points.size())
491 EXPECT_NEAR(cloud.
points[index].x, x, e);
492 EXPECT_NEAR(cloud.
points[index].y, y, e);
517 cloud.points[0].x = 0.0;
518 cloud.points[0].y = 0.0;
519 cloud.points[0].z = 0.0;
520 cloud.points[0].i = 0.0;
521 cloud.points[0].r = 15;
544 ASSERT_EQ(cloud.header.stamp,
g_scan.header.stamp);
556 cloud.
header.frame_id =
"abcdefghijklmnopqrstuvwxyz";
557 cloud.points.resize(1);
558 cloud.points[0].x = 0.0;
559 cloud.points[0].y = 0.0;
560 cloud.points[0].z = 0.0;
561 cloud.points[0].i = 0.0;
562 cloud.points[0].r = 15;
586 TEST(System, random_data_sparse)
594 cloud.
header.frame_id =
"velodyne";
595 const size_t RANGE_COUNT = 100;
596 const size_t RING_COUNT = 16;
597 const double RANGE_MAX = 20.0;
598 const double INTENSITY_MAX = 1.0;
600 for (
size_t i = 0; i < RANGE_COUNT; i++)
602 double angle_y = i * 1.99 * M_PI / RANGE_COUNT;
604 for (
size_t j = 0; j < RING_COUNT; j++)
606 double angle_p = j * 0.2 * M_PI / RING_COUNT - 0.1 * M_PI;
607 double range = std::rand() * (RANGE_MAX / RAND_MAX);
609 point.
x = range * cos(angle_p) * cos(angle_y);
610 point.
y = range * cos(angle_p) * sin(angle_y);
611 point.
z = range * sin(angle_p);
612 point.
i = std::rand() * (INTENSITY_MAX / RAND_MAX);
614 cloud.points.push_back(point);
640 TEST(System, random_data_dense)
648 cloud.
header.frame_id =
"velodyne";
649 const size_t RANGE_COUNT = 2500;
650 const size_t RING_COUNT = 16;
651 const double RANGE_MAX = 20.0;
652 const double INTENSITY_MAX = 1.0;
654 for (
size_t i = 0; i < RANGE_COUNT; i++)
656 double angle_y = i * 2.0 * M_PI / RANGE_COUNT;
658 for (
size_t j = 0; j < RING_COUNT; j++)
660 double angle_p = j * 0.2 * M_PI / RING_COUNT - 0.1 * M_PI;
661 double range = std::rand() * (RANGE_MAX / RAND_MAX);
663 point.
x = range * cos(angle_p) * cos(angle_y);
664 point.
y = range * cos(angle_p) * sin(angle_y);
665 point.
z = range * sin(angle_p);
666 point.
i = std::rand() * (INTENSITY_MAX / RAND_MAX);
668 cloud.points.push_back(point);
693 int main(
int argc,
char **argv)
695 testing::InitGoogleTest(&argc, argv);
698 ros::init(argc, argv,
"test_lazy_subscriber");
702 g_pub = nh.
advertise<sensor_msgs::PointCloud2>(
"velodyne_points", 2);
710 return RUN_ALL_TESTS();
TEST(System, missing_fields)
void verifyScanDense(const PointCloud &cloud, uint16_t ring, bool intensity=true)
void verifyScanEmpty(const PointCloud &cloud, bool intensity=true)
void publishXYZ(const PointCloud &cloud)
void publish(const boost::shared_ptr< M > &message) const
void publishXYZIR1(const PointCloud &cloud)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< Point > points
static float SQUARE(float x)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publishXYZIR2(const PointCloud &cloud)
sensor_msgs::LaserScan g_scan
void publishR(const PointCloud &cloud)
uint32_t getNumPublishers() const
static ros::Time rosTime(const ros::WallTime &stamp)
int main(int argc, char **argv)
size_t findClosestIndex(const PointCloud &cloud, uint16_t ring, float x, float y)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
void recv(const sensor_msgs::LaserScanConstPtr &msg)
void publishXYZR32(const PointCloud &cloud)
void verifyScanSparse(const PointCloud &cloud, uint16_t ring, uint16_t ring_count, bool intensity=true)
ROSCPP_DECL void spinOnce()
bool waitForScan(ros::WallDuration dur)
void publishXYZR(const PointCloud &cloud)