Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include "velodyne_laserscan/velodyne_laserscan.h"
00034 #include <sensor_msgs/point_cloud2_iterator.h>
00035
00036 namespace velodyne_laserscan
00037 {
00038
00039 VelodyneLaserScan::VelodyneLaserScan(ros::NodeHandle &nh, ros::NodeHandle &nh_priv) :
00040 nh_(nh), srv_(nh_priv), ring_count_(0)
00041 {
00042 ros::SubscriberStatusCallback connect_cb = boost::bind(&VelodyneLaserScan::connectCb, this);
00043 pub_ = nh.advertise<sensor_msgs::LaserScan>("scan", 10, connect_cb, connect_cb);
00044
00045 srv_.setCallback(boost::bind(&VelodyneLaserScan::reconfig, this, _1, _2));
00046 }
00047
00048 void VelodyneLaserScan::connectCb()
00049 {
00050 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00051 if (!pub_.getNumSubscribers())
00052 {
00053 sub_.shutdown();
00054 }
00055 else if (!sub_)
00056 {
00057 sub_ = nh_.subscribe("velodyne_points", 10, &VelodyneLaserScan::recvCallback, this);
00058 }
00059 }
00060
00061 void VelodyneLaserScan::recvCallback(const sensor_msgs::PointCloud2ConstPtr& msg)
00062 {
00063
00064 if (!ring_count_)
00065 {
00066
00067 bool found = false;
00068 for (size_t i = 0; i < msg->fields.size(); i++)
00069 {
00070 if (msg->fields[i].datatype == sensor_msgs::PointField::UINT16)
00071 {
00072 if (msg->fields[i].name == "ring")
00073 {
00074 found = true;
00075 break;
00076 }
00077 }
00078 }
00079 if (!found)
00080 {
00081 ROS_ERROR("VelodyneLaserScan: Field 'ring' of type 'UINT16' not present in PointCloud2");
00082 return;
00083 }
00084 for (sensor_msgs::PointCloud2ConstIterator<uint16_t> it(*msg, "ring"); it != it.end(); ++it)
00085 {
00086 const uint16_t ring = *it;
00087
00088 if (ring + 1 > ring_count_)
00089 {
00090 ring_count_ = ring + 1;
00091 }
00092 }
00093 if (ring_count_)
00094 {
00095 ROS_INFO("VelodyneLaserScan: Latched ring count of %u", ring_count_);
00096 }
00097 else
00098 {
00099 ROS_ERROR("VelodyneLaserScan: Field 'ring' of type 'UINT16' not present in PointCloud2");
00100 return;
00101 }
00102 }
00103
00104
00105 uint16_t ring;
00106
00107 if ((cfg_.ring < 0) || (cfg_.ring >= ring_count_))
00108 {
00109
00110 if (ring_count_ > 32)
00111 {
00112 ring = 57;
00113 }
00114 else if (ring_count_ > 16)
00115 {
00116 ring = 23;
00117 }
00118 else
00119 {
00120 ring = 8;
00121 }
00122 }
00123 else
00124 {
00125 ring = cfg_.ring;
00126 }
00127
00128 ROS_INFO_ONCE("VelodyneLaserScan: Extracting ring %u", ring);
00129
00130
00131 int offset_x = -1;
00132 int offset_y = -1;
00133 int offset_z = -1;
00134 int offset_i = -1;
00135 int offset_r = -1;
00136
00137 for (size_t i = 0; i < msg->fields.size(); i++)
00138 {
00139 if (msg->fields[i].datatype == sensor_msgs::PointField::FLOAT32)
00140 {
00141 if (msg->fields[i].name == "x")
00142 {
00143 offset_x = msg->fields[i].offset;
00144 }
00145 else if (msg->fields[i].name == "y")
00146 {
00147 offset_y = msg->fields[i].offset;
00148 }
00149 else if (msg->fields[i].name == "z")
00150 {
00151 offset_z = msg->fields[i].offset;
00152 }
00153 else if (msg->fields[i].name == "intensity")
00154 {
00155 offset_i = msg->fields[i].offset;
00156 }
00157 }
00158 else if (msg->fields[i].datatype == sensor_msgs::PointField::UINT16)
00159 {
00160 if (msg->fields[i].name == "ring")
00161 {
00162 offset_r = msg->fields[i].offset;
00163 }
00164 }
00165 }
00166
00167
00168 if ((offset_x >= 0) && (offset_y >= 0) && (offset_r >= 0))
00169 {
00170 const float RESOLUTION = std::abs(cfg_.resolution);
00171 const size_t SIZE = 2.0 * M_PI / RESOLUTION;
00172 sensor_msgs::LaserScanPtr scan(new sensor_msgs::LaserScan());
00173 scan->header = msg->header;
00174 scan->angle_increment = RESOLUTION;
00175 scan->angle_min = -M_PI;
00176 scan->angle_max = M_PI;
00177 scan->range_min = 0.0;
00178 scan->range_max = 200.0;
00179 scan->time_increment = 0.0;
00180 scan->ranges.resize(SIZE, INFINITY);
00181
00182 if ((offset_x == 0) &&
00183 (offset_y == 4) &&
00184 (offset_z == 8) &&
00185 (offset_i == 16) &&
00186 (offset_r == 20))
00187 {
00188 scan->intensities.resize(SIZE);
00189
00190 for (sensor_msgs::PointCloud2ConstIterator<float> it(*msg, "x"); it != it.end(); ++it)
00191 {
00192 const uint16_t r = *((const uint16_t*)(&it[5]));
00193
00194 if (r == ring)
00195 {
00196 const float x = it[0];
00197 const float y = it[1];
00198 const float i = it[4];
00199 const int bin = (atan2f(y, x) + static_cast<float>(M_PI)) / RESOLUTION;
00200
00201 if ((bin >= 0) && (bin < static_cast<int>(SIZE)))
00202 {
00203 scan->ranges[bin] = sqrtf(x * x + y * y);
00204 scan->intensities[bin] = i;
00205 }
00206 }
00207 }
00208 }
00209 else
00210 {
00211 ROS_WARN_ONCE("VelodyneLaserScan: PointCloud2 fields in unexpected order. Using slower generic method.");
00212
00213 if (offset_i >= 0)
00214 {
00215 scan->intensities.resize(SIZE);
00216 sensor_msgs::PointCloud2ConstIterator<uint16_t> iter_r(*msg, "ring");
00217 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*msg, "x");
00218 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*msg, "y");
00219 sensor_msgs::PointCloud2ConstIterator<float> iter_i(*msg, "intensity");
00220 for ( ; iter_r != iter_r.end(); ++iter_x, ++iter_y, ++iter_r, ++iter_i)
00221 {
00222 const uint16_t r = *iter_r;
00223
00224 if (r == ring)
00225 {
00226 const float x = *iter_x;
00227 const float y = *iter_y;
00228 const float i = *iter_i;
00229 const int bin = (atan2f(y, x) + static_cast<float>(M_PI)) / RESOLUTION;
00230
00231 if ((bin >= 0) && (bin < static_cast<int>(SIZE)))
00232 {
00233 scan->ranges[bin] = sqrtf(x * x + y * y);
00234 scan->intensities[bin] = i;
00235 }
00236 }
00237 }
00238 }
00239 else
00240 {
00241 sensor_msgs::PointCloud2ConstIterator<uint16_t> iter_r(*msg, "ring");
00242 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*msg, "x");
00243 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*msg, "y");
00244
00245 for (; iter_r != iter_r.end(); ++iter_x, ++iter_y, ++iter_r)
00246 {
00247 const uint16_t r = *iter_r;
00248
00249 if (r == ring)
00250 {
00251 const float x = *iter_x;
00252 const float y = *iter_y;
00253 const int bin = (atan2f(y, x) + static_cast<float>(M_PI)) / RESOLUTION;
00254
00255 if ((bin >= 0) && (bin < static_cast<int>(SIZE)))
00256 {
00257 scan->ranges[bin] = sqrtf(x * x + y * y);
00258 }
00259 }
00260 }
00261 }
00262 }
00263
00264 pub_.publish(scan);
00265 }
00266 else
00267 {
00268 ROS_ERROR("VelodyneLaserScan: PointCloud2 missing one or more required fields! (x,y,ring)");
00269 }
00270 }
00271
00272 void VelodyneLaserScan::reconfig(VelodyneLaserScanConfig& config, uint32_t level)
00273 {
00274 cfg_ = config;
00275 }
00276
00277 }