40 DenseLaserAssembler::DenseLaserAssembler(
const unsigned int cache_size)
58 vector< sensor_msgs::LaserScanConstPtr > scan_vec;
63 start.
toSec(), end.
toSec(), (end-start).toSec());
70 calibration_msgs::DenseLaserSnapshot& snapshot)
72 if (scans.size() == 0)
74 ROS_WARN(
"Trying to build empty cloud") ;
75 snapshot.angle_min = 0.0;
76 snapshot.angle_max = 0.0;
77 snapshot.angle_increment = 0.0;
78 snapshot.time_increment = 0.0;
79 snapshot.range_min = 0.0;
80 snapshot.range_max = 0.0;
81 snapshot.readings_per_scan = 0;
82 snapshot.num_scans = 0;
83 snapshot.ranges.clear();
84 snapshot.intensities.clear();
85 snapshot.scan_start.clear();
90 snapshot.header.stamp = scans[scans.size()-1]->header.stamp;
93 snapshot.header.frame_id = scans[0]->header.frame_id;
94 snapshot.angle_min = scans[0]->angle_min;
95 snapshot.angle_max = scans[0]->angle_max;
96 snapshot.angle_increment = scans[0]->angle_increment;
97 snapshot.time_increment = scans[0]->time_increment;
98 snapshot.range_min = scans[0]->range_min;
99 snapshot.range_max = scans[0]->range_max;
102 snapshot.readings_per_scan = scans[0]->ranges.size();
103 snapshot.num_scans = scans.size();
104 const unsigned int& w = snapshot.readings_per_scan;
105 const unsigned int& h = snapshot.num_scans;
108 for (
unsigned int i=0; i<scans.size(); i++)
112 ROS_WARN(
"Metadata doesn't match. It is likely that someone just changed the laser's configuration");
118 snapshot.scan_start.resize(h) ;
119 snapshot.ranges.resize(w*h) ;
120 snapshot.intensities.resize(w*h) ;
122 const unsigned int range_elem_size =
sizeof(scans[0]->ranges[0]) ;
123 const unsigned int intensity_elem_size =
sizeof(scans[0]->intensities[0]) ;
126 assert(
sizeof(snapshot.ranges[0]) ==
sizeof(scans[0]->ranges[0]));
127 assert(
sizeof(snapshot.intensities[0]) ==
sizeof(scans[0]->intensities[0]));
129 for (
unsigned int i=0; i<h; i++)
131 memcpy(&snapshot.ranges[i*w], &scans[i]->ranges[0], w*range_elem_size) ;
132 memcpy(&snapshot.intensities[i*w], &scans[i]->intensities[0], w*intensity_elem_size) ;
135 snapshot.scan_start[i] = scans[i]->header.stamp ;
138 ROS_DEBUG(
"Done building snapshot that is [%u rows] x [%u cols]", h, w) ;
139 ROS_DEBUG(
" ranges.size = %lu", snapshot.ranges.size());
140 ROS_DEBUG(
" intensities.size = %lu", snapshot.intensities.size());
145 static const double eps = 1e-9 ;
149 if ( (snapshot.a - scan.a < -eps) || (snapshot.a - scan.a > eps)) \ 157 CHECK(angle_increment) ;
158 CHECK(time_increment) ;
162 if (snapshot.header.frame_id.compare(scan.header.frame_id) != 0)
165 if (snapshot.readings_per_scan != scan.ranges.size())
167 if (snapshot.readings_per_scan != scan.intensities.size())
void add(const sensor_msgs::LaserScanConstPtr &laser_scan)
bool flattenScanVec(const std::vector< sensor_msgs::LaserScanConstPtr > &scans, calibration_msgs::DenseLaserSnapshot &snapshot)
Takes a vector of LaserScan messages, and composes them into one larger snapshot. ...
void setMaxSize(unsigned int max_size)
bool verifyMetadata(const calibration_msgs::DenseLaserSnapshot &snapshot, const sensor_msgs::LaserScan &scan)
Internal data consistency check.
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. ...
void setCacheSize(const unsigned int cache_size)
std::vector< M > getInterval(const ros::Time &start, const ros::Time &end)
settlerlib::SortedDeque< sensor_msgs::LaserScanConstPtr > cache_
Stores the history of laser scans.