40 nh_(nh), srv_(nh_priv), ring_count_(0)
43 pub_ = nh.
advertise<sensor_msgs::LaserScan>(
"scan", 10, connect_cb, connect_cb);
68 for (
size_t i = 0; i < msg->fields.size(); i++)
70 if (msg->fields[i].datatype == sensor_msgs::PointField::UINT16)
72 if (msg->fields[i].name ==
"ring")
81 ROS_ERROR(
"VelodyneLaserScan: Field 'ring' of type 'UINT16' not present in PointCloud2");
86 const uint16_t ring = *it;
99 ROS_ERROR(
"VelodyneLaserScan: Field 'ring' of type 'UINT16' not present in PointCloud2");
128 ROS_INFO_ONCE(
"VelodyneLaserScan: Extracting ring %u", ring);
137 for (
size_t i = 0; i < msg->fields.size(); i++)
139 if (msg->fields[i].datatype == sensor_msgs::PointField::FLOAT32)
141 if (msg->fields[i].name ==
"x")
143 offset_x = msg->fields[i].offset;
145 else if (msg->fields[i].name ==
"y")
147 offset_y = msg->fields[i].offset;
149 else if (msg->fields[i].name ==
"z")
151 offset_z = msg->fields[i].offset;
153 else if (msg->fields[i].name ==
"intensity")
155 offset_i = msg->fields[i].offset;
158 else if (msg->fields[i].datatype == sensor_msgs::PointField::UINT16)
160 if (msg->fields[i].name ==
"ring")
162 offset_r = msg->fields[i].offset;
168 if ((offset_x >= 0) && (offset_y >= 0) && (offset_r >= 0))
170 const float RESOLUTION = std::abs(
cfg_.resolution);
171 const size_t SIZE = 2.0 * M_PI / RESOLUTION;
172 sensor_msgs::LaserScanPtr scan(
new sensor_msgs::LaserScan());
173 scan->header = msg->header;
174 scan->angle_increment = RESOLUTION;
175 scan->angle_min = -M_PI;
176 scan->angle_max = M_PI;
177 scan->range_min = 0.0;
178 scan->range_max = 200.0;
179 scan->time_increment = 0.0;
180 scan->ranges.resize(SIZE, INFINITY);
182 if ((offset_x == 0) &&
188 scan->intensities.resize(SIZE);
192 const uint16_t r = *((
const uint16_t*)(&it[5]));
196 const float x = it[0];
197 const float y = it[1];
198 const float i = it[4];
199 const int bin = (atan2f(y, x) +
static_cast<float>(M_PI)) / RESOLUTION;
201 if ((bin >= 0) && (bin < static_cast<int>(SIZE)))
203 scan->ranges[bin] = sqrtf(x * x + y * y);
204 scan->intensities[bin] = i;
211 ROS_WARN_ONCE(
"VelodyneLaserScan: PointCloud2 fields in unexpected order. Using slower generic method.");
215 scan->intensities.resize(SIZE);
220 for ( ; iter_r != iter_r.
end(); ++iter_x, ++iter_y, ++iter_r, ++iter_i)
222 const uint16_t r = *iter_r;
226 const float x = *iter_x;
227 const float y = *iter_y;
228 const float i = *iter_i;
229 const int bin = (atan2f(y, x) +
static_cast<float>(M_PI)) / RESOLUTION;
231 if ((bin >= 0) && (bin < static_cast<int>(SIZE)))
233 scan->ranges[bin] = sqrtf(x * x + y * y);
234 scan->intensities[bin] = i;
245 for (; iter_r != iter_r.
end(); ++iter_x, ++iter_y, ++iter_r)
247 const uint16_t r = *iter_r;
251 const float x = *iter_x;
252 const float y = *iter_y;
253 const int bin = (atan2f(y, x) +
static_cast<float>(M_PI)) / RESOLUTION;
255 if ((bin >= 0) && (bin < static_cast<int>(SIZE)))
257 scan->ranges[bin] = sqrtf(x * x + y * y);
268 ROS_ERROR(
"VelodyneLaserScan: PointCloud2 missing one or more required fields! (x,y,ring)");
boost::mutex connect_mutex_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO_ONCE(...)
VelodyneLaserScanConfig cfg_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
dynamic_reconfigure::Server< VelodyneLaserScanConfig > srv_
#define ROS_WARN_ONCE(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
PointCloud2ConstIterator< T > end() const
VelodyneLaserScan(ros::NodeHandle &nh, ros::NodeHandle &nh_priv)
void recvCallback(const sensor_msgs::PointCloud2ConstPtr &msg)
void reconfig(VelodyneLaserScanConfig &config, uint32_t level)