dense_laser_assembler.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 
36 
37 using namespace std;
38 using namespace dense_laser_assembler;
39 
40 DenseLaserAssembler::DenseLaserAssembler(const unsigned int cache_size)
41  : cache_(&settlerlib::SortedDeque<sensor_msgs::LaserScanConstPtr>::getPtrStamp, "dense_laser_deque")
42 {
43  setCacheSize(cache_size);
44 }
45 
46 void DenseLaserAssembler::setCacheSize(const unsigned int cache_size)
47 {
48  cache_.setMaxSize(cache_size);
49 }
50 
51 void DenseLaserAssembler::add(const sensor_msgs::LaserScanConstPtr& laser_scan)
52 {
53  cache_.add(laser_scan);
54 }
55 
56 bool DenseLaserAssembler::assembleSnapshot(const ros::Time& start, const ros::Time& end, calibration_msgs::DenseLaserSnapshot& snapshot)
57 {
58  vector< sensor_msgs::LaserScanConstPtr > scan_vec;
59  ROS_DEBUG("Assembling snapshot:\n"
60  " from: %.2f\n"
61  " to: %.2f\n"
62  " duration: %.3f\n",
63  start.toSec(), end.toSec(), (end-start).toSec());
64 
65  scan_vec = cache_.getInterval(start, end);
66  return flattenScanVec(scan_vec, snapshot);
67 }
68 
69 bool DenseLaserAssembler::flattenScanVec(const std::vector< sensor_msgs::LaserScanConstPtr >& scans,
70  calibration_msgs::DenseLaserSnapshot& snapshot)
71 {
72  if (scans.size() == 0)
73  {
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();
86  return true;
87  }
88 
89  // Not really sure what the overall stamp should be. But for now, copy over the stamp from the last scan
90  snapshot.header.stamp = scans[scans.size()-1]->header.stamp;
91 
92  // Fill in all the metadata
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;
100 
101  // Define the data dimensions
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;
106 
107  // Do a consistency check on the metadata
108  for (unsigned int i=0; i<scans.size(); i++)
109  {
110  if (!verifyMetadata(snapshot, *scans[i]))
111  {
112  ROS_WARN("Metadata doesn't match. It is likely that someone just changed the laser's configuration");
113  return false ;
114  }
115  }
116 
117  // Allocate data vectors
118  snapshot.scan_start.resize(h) ;
119  snapshot.ranges.resize(w*h) ;
120  snapshot.intensities.resize(w*h) ;
121 
122  const unsigned int range_elem_size = sizeof(scans[0]->ranges[0]) ;
123  const unsigned int intensity_elem_size = sizeof(scans[0]->intensities[0]) ;
124 
125  // Make sure our sizes match before doing memcpy
126  assert(sizeof(snapshot.ranges[0]) == sizeof(scans[0]->ranges[0]));
127  assert(sizeof(snapshot.intensities[0]) == sizeof(scans[0]->intensities[0]));
128 
129  for (unsigned int i=0; i<h; i++)
130  {
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) ;
133 
134  // Copy time stamp
135  snapshot.scan_start[i] = scans[i]->header.stamp ;
136  }
137 
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());
141 
142  return true ;
143 }
144 
145 static const double eps = 1e-9 ;
146 
147 #define CHECK(a) \
148 { \
149  if ( (snapshot.a - scan.a < -eps) || (snapshot.a - scan.a > eps)) \
150  return false ; \
151 }
152 
153 bool DenseLaserAssembler::verifyMetadata(const calibration_msgs::DenseLaserSnapshot& snapshot, const sensor_msgs::LaserScan& scan)
154 {
155  CHECK(angle_min) ;
156  CHECK(angle_max) ;
157  CHECK(angle_increment) ;
158  CHECK(time_increment) ;
159  CHECK(range_min) ;
160  CHECK(range_max) ;
161 
162  if (snapshot.header.frame_id.compare(scan.header.frame_id) != 0)
163  return false ;
164 
165  if (snapshot.readings_per_scan != scan.ranges.size())
166  return false ;
167  if (snapshot.readings_per_scan != scan.intensities.size())
168  return false ;
169 
170 
171  return true ;
172 }
#define CHECK(a)
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. ...
static const double eps
void setMaxSize(unsigned int max_size)
#define ROS_WARN(...)
bool verifyMetadata(const calibration_msgs::DenseLaserSnapshot &snapshot, const sensor_msgs::LaserScan &scan)
Internal data consistency check.
void add(const M &msg)
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)
#define ROS_DEBUG(...)
std::vector< M > getInterval(const ros::Time &start, const ros::Time &end)
settlerlib::SortedDeque< sensor_msgs::LaserScanConstPtr > cache_
Stores the history of laser scans.


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