dense_laser_assembler_unittest.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <gtest/gtest.h>
36 
37 #include <sensor_msgs/LaserScan.h>
39 
40 using namespace std;
41 using namespace dense_laser_assembler;
42 
43 sensor_msgs::LaserScanConstPtr buildScan(const ros::Time& stamp, double start_angle, double start_range, double start_intensity, const unsigned int N)
44 {
45  sensor_msgs::LaserScanPtr scan(new sensor_msgs::LaserScan);
46 
47  scan->header.stamp = stamp;
48 
49  scan->angle_increment = 1.0;
50  scan->angle_min = start_angle;
51  scan->angle_max = start_angle + (N-1)*scan->angle_increment;
52  scan->time_increment = 1.0;
53  scan->scan_time = 0.0;
54  scan->range_min = 0.0;
55  scan->range_max = 1000.0;
56  scan->ranges.resize(N);
57  scan->intensities.resize(N);
58  for (unsigned int i=0; i<N; i++)
59  {
60  scan->ranges[i] = start_range + 1.0*i;
61  scan->intensities[i] = start_intensity + 1.0*i;
62  //printf("%.3f ", scan->ranges[i]);
63  }
64  //printf("\n");
65  return scan;
66 }
67 
68 static const unsigned int NUM_SCANS = 20;
69 static const unsigned int RAYS_PER_SCAN = 50;
70 static const double eps = 1e-8;
71 
72 void addScans1(const ros::Time& start_stamp, double start_angle, DenseLaserAssembler& assembler)
73 {
74 
75  for (unsigned int i=0; i<NUM_SCANS; i++)
76  {
77  sensor_msgs::LaserScanConstPtr scan = buildScan(start_stamp + ros::Duration(i,0), start_angle, 100*i, 1000*i, RAYS_PER_SCAN);
78  assembler.add(scan);
79  }
80 }
81 
83 {
84  DenseLaserAssembler assembler;
85  addScans1(ros::Time(10,0), 0.0, assembler);
86 
87  calibration_msgs::DenseLaserSnapshot snapshot;
88  bool result;
89  result = assembler.assembleSnapshot(ros::Time(9,0), ros::Time(31,0), snapshot);
90  ASSERT_TRUE(result);
91  ASSERT_EQ(snapshot.ranges.size(), NUM_SCANS * RAYS_PER_SCAN);
92  ASSERT_EQ(snapshot.intensities.size(), NUM_SCANS * RAYS_PER_SCAN);
93  ASSERT_EQ(snapshot.readings_per_scan, RAYS_PER_SCAN);
94  ASSERT_EQ(snapshot.num_scans, NUM_SCANS);
95  ASSERT_EQ(snapshot.scan_start.size(), NUM_SCANS);
96 
97  // Check start time
98  EXPECT_EQ(snapshot.scan_start[0], ros::Time(10,0));
99  EXPECT_EQ(snapshot.scan_start[5], ros::Time(15,0));
100  EXPECT_EQ(snapshot.scan_start[19], ros::Time(29,0));
101 
102  // Check ranges
103  EXPECT_NEAR(snapshot.ranges[0], 0, eps);
104  EXPECT_NEAR(snapshot.ranges[70], 120, eps);
105  EXPECT_NEAR(snapshot.ranges[999], 1949, eps);
106 
107  // Check intensities
108  EXPECT_NEAR(snapshot.intensities[0], 0, eps);
109  EXPECT_NEAR(snapshot.intensities[70], 1020, eps);
110  EXPECT_NEAR(snapshot.intensities[999], 19049, eps);
111 }
112 
113 TEST(DenseLaserAssembler, mismatchedMetadata)
114 {
115  DenseLaserAssembler assembler;
116  addScans1(ros::Time( 10,0), 0.0, assembler);
117  addScans1(ros::Time(110,0), 1.0, assembler);
118 
119  calibration_msgs::DenseLaserSnapshot snapshot;
120  bool result;
121  result = assembler.assembleSnapshot(ros::Time(9,0), ros::Time(31,0), snapshot);
122  EXPECT_TRUE(result);
123  EXPECT_EQ(snapshot.ranges.size(), NUM_SCANS * RAYS_PER_SCAN);
124 
125  result = assembler.assembleSnapshot(ros::Time(109,0), ros::Time(131,0), snapshot);
126  EXPECT_TRUE(result);
127  EXPECT_EQ(snapshot.ranges.size(), NUM_SCANS * RAYS_PER_SCAN);
128 
129  result = assembler.assembleSnapshot(ros::Time(9,0), ros::Time(131,0), snapshot);
130  EXPECT_FALSE(result);
131 }
132 
133 
134 int main(int argc, char **argv){
135  testing::InitGoogleTest(&argc, argv);
136  return RUN_ALL_TESTS();
137 }
static const unsigned int NUM_SCANS
void addScans1(const ros::Time &start_stamp, double start_angle, DenseLaserAssembler &assembler)
sensor_msgs::LaserScanConstPtr buildScan(const ros::Time &stamp, double start_angle, double start_range, double start_intensity, const unsigned int N)
void add(const sensor_msgs::LaserScanConstPtr &laser_scan)
static const unsigned int RAYS_PER_SCAN
TEST(DenseLaserAssembler, easy)
bool assembleSnapshot(const ros::Time &start, const ros::Time &end, calibration_msgs::DenseLaserSnapshot &snapshot)
Takes a vector of LaserScan messages, and composes them into one larger snapshot. ...
static const double eps
int main(int argc, char **argv)


dense_laser_assembler
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:54