35 #include <gtest/gtest.h> 37 #include <sensor_msgs/LaserScan.h> 43 sensor_msgs::LaserScanConstPtr
buildScan(
const ros::Time& stamp,
double start_angle,
double start_range,
double start_intensity,
const unsigned int N)
45 sensor_msgs::LaserScanPtr scan(
new sensor_msgs::LaserScan);
47 scan->header.stamp = stamp;
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++)
60 scan->ranges[i] = start_range + 1.0*i;
61 scan->intensities[i] = start_intensity + 1.0*i;
70 static const double eps = 1e-8;
87 calibration_msgs::DenseLaserSnapshot snapshot;
95 ASSERT_EQ(snapshot.scan_start.size(),
NUM_SCANS);
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));
103 EXPECT_NEAR(snapshot.ranges[0], 0,
eps);
104 EXPECT_NEAR(snapshot.ranges[70], 120,
eps);
105 EXPECT_NEAR(snapshot.ranges[999], 1949,
eps);
108 EXPECT_NEAR(snapshot.intensities[0], 0,
eps);
109 EXPECT_NEAR(snapshot.intensities[70], 1020,
eps);
110 EXPECT_NEAR(snapshot.intensities[999], 19049,
eps);
119 calibration_msgs::DenseLaserSnapshot snapshot;
130 EXPECT_FALSE(result);
134 int main(
int argc,
char **argv){
135 testing::InitGoogleTest(&argc, argv);
136 return RUN_ALL_TESTS();
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. ...
int main(int argc, char **argv)