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
00033 #ifndef _READ_VELODYNE_CPP_
00034 #define _READ_VELODYNE_CPP_
00035
00036 #include "read_velodyne.h"
00037
00038 class c_polygon_representation
00039 {
00040 public:
00041
00043 c_polygon_representation()
00044 {
00045 coefficients = pcl::ModelCoefficients::Ptr(new pcl::ModelCoefficients);
00046 indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
00047
00048 }
00049
00051 ~c_polygon_representation()
00052 {
00053 delete &coefficients;
00054 delete &indices;
00055 }
00056
00057
00059 pcl::ModelCoefficients::Ptr coefficients;
00060 pcl::PointIndices::Ptr indices;
00061 pcl::PointCloud<PointT> cloud;
00062
00063
00064
00065 private:
00066
00067
00068
00069 };
00070
00071 void signal_handler(int sig)
00072 {
00073 printf("%d %d %d\n",sig,SIGSEGV,SIGINT);
00074
00075 if(sig==SIGSEGV)
00076 {
00077
00078 signal(SIGSEGV, SIG_DFL);
00079
00080 ROS_WARN("System segfaulted");
00081
00082 ros::shutdown();
00083
00084 exit(0);
00085 }
00086 else if(sig==SIGINT)
00087 {
00088 ROS_WARN("Ctrl-c pressed");
00089
00090 ros::shutdown();
00091
00092 exit(0);
00093 }
00094 }
00095
00100
00101 int main(int argc, char **argv)
00102 {
00103 if(argc < 4) {
00104 fprintf(stderr,
00105 "usage: example4-velodyne <logfile> <start_time> <end time>\n"
00106 "\n"
00107 "start_time and end_time are given in seconds from the\n"
00108 "start of the log file\n");
00109 return 1;
00110 }
00111
00112 lcm_eventlog_t *log = lcm_eventlog_create(argv[1], "r");
00113 if(!log) {
00114 fprintf(stderr, "error opening log file\n");
00115 return 1;
00116 }
00117
00118 double start_time = strtod(argv[2], NULL);
00119 double end_time = strtod(argv[3], NULL);
00120
00121 Config *config = config_parse_default();
00122 if(!config) {
00123 fprintf(stderr, "couldn't find config file\n");
00124 return 1;
00125 }
00126
00127
00128 velodyne_calib_t *vcalib = velodyne_calib_create();
00129
00130
00131 lcm_eventlog_event_t *event = lcm_eventlog_read_next_event(log);
00132 int64_t first_timestamp = event->timestamp;
00133
00134
00135 int64_t start_utime = first_timestamp + (int64_t)(start_time * 1000000);
00136 int64_t end_utime = first_timestamp + (int64_t)(end_time * 1000000);
00137
00138 lcmtypes_pose_t last_pose;
00139 memset(&last_pose, 0, sizeof(last_pose));
00140
00141
00143 t_flags.debug=false;
00144
00146 ros::init(argc, argv, "point_cloud_publisher");
00147
00148 ros::NodeHandle n;
00149 ros::Publisher cloud_pub = n.advertise<sensor_msgs::PointCloud2>("cloud", 1);
00150
00151 ros::Publisher pub[10];
00152
00153 for (int i=0; i< _NUM_POLYGONS_; i ++)
00154 {
00155 char str[256];
00156 sprintf(str, "plg_%d",i);
00157 pub[i] = n.advertise<sensor_msgs::PointCloud2>(str, 1);
00158 }
00159
00161 ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 10);
00162
00163
00164 ros::Rate r(0.5);
00165
00166
00167 pcl::PointCloud<PointT> cloud;
00168 sensor_msgs::PointCloud2 cloud_msg;
00169 cloud.header.frame_id = "/sensor_frame";
00170 cloud.height = 1;
00171 cloud.is_dense=0;
00172
00173 while(1)
00174 {
00175
00176 lcm_eventlog_free_event(event);
00177
00178
00179 event = lcm_eventlog_read_next_event(log);
00180
00181 if(!event)
00182 break;
00183
00184
00185 if(!strcmp(event->channel, "POSE")) {
00186 if(last_pose.utime)
00187 lcmtypes_pose_t_decode_cleanup(&last_pose);
00188
00189 lcmtypes_pose_t_decode(event->data, 0, event->datalen, &last_pose);
00190 }
00191
00192
00193 if(event->timestamp < start_utime) {
00194 continue;
00195 }
00196
00197
00198 if(event->timestamp >= end_utime) {
00199 break;
00200 }
00201
00202 if(!strcmp(event->channel, "VELODYNE")) {
00203
00204 lcmtypes_velodyne_t vel;
00205 lcmtypes_velodyne_t_decode(event->data, 0, event->datalen,
00206 &vel);
00207
00208
00209
00210
00211
00212
00213 double velodyne_to_local[16];
00214 config_util_sensor_to_local_with_pose (config, "VELODYNE",
00215 velodyne_to_local, &last_pose);
00216
00217
00218 velodyne_decoder_t vdecoder;
00219 velodyne_decoder_init(vcalib, &vdecoder, vel.data, vel.datalen);
00220
00221
00222
00223 velodyne_sample_t vsample;
00224
00225 while (!velodyne_decoder_next(vcalib, &vdecoder, &vsample))
00226 {
00227 if (vsample.range < 0.01)
00228 {
00229 continue;
00230 }
00231
00232 double sensor_xyz[4] = {vsample.xyz[0], vsample.xyz[1], vsample.xyz[2], 1 };
00233 double local_xyz[4];
00234
00235 matrix_vector_multiply_4x4_4d(velodyne_to_local, sensor_xyz, local_xyz);
00236
00237
00238
00239
00240 PointT Pt;
00241 Pt.x = local_xyz[0];
00242 Pt.y = local_xyz[1];
00243 Pt.z = local_xyz[2];
00244
00245
00246
00247
00248 cloud.push_back(Pt);
00249
00250 }
00251
00252 cloud.width = cloud.size();
00253 lcmtypes_velodyne_t_decode_cleanup(&vel);
00254 }
00255 }
00256
00257 while(n.ok())
00258 {
00259
00260 visualization_msgs::Marker markers;
00261 markers.header.frame_id = "/sensor_frame";
00262 markers.header.stamp = ros::Time::now();
00263 markers.ns = "triangles";
00264 markers.action = visualization_msgs::Marker::ADD;
00265 markers.pose.orientation.w = 1.0;
00266 markers.type = visualization_msgs::Marker::TRIANGLE_LIST;
00267
00268 markers.scale.x = 1;
00269 markers.scale.y = 1;
00270 markers.scale.z = 1;
00271
00272 markers.color.r = 1;
00273 markers.color.g = 1;
00274 markers.color.b = 1;
00275 markers.color.a = 1;
00276
00277 geometry_msgs::Point p;
00278 std_msgs::ColorRGBA color;
00279 p.x = 0;
00280 p.y = 0;
00281 p.z = 0;
00282 markers.points.push_back(p);
00283 color.r = 1.0f;
00284 color.g = 0.2f;
00285 color.b = 1.0f;
00286 color.a = 1.0;
00287 markers.colors.push_back(color);
00288
00289 p.x = 10;
00290 p.y = 10;
00291 p.z = 0;
00292 markers.points.push_back(p);
00293 color.r = 1.0f;
00294 color.g = 0.2f;
00295 color.b = 0.5f;
00296 color.a = 1.0;
00297 markers.colors.push_back(color);
00298
00299 p.x = 10;
00300 p.y = -10;
00301 p.z = 0;
00302 markers.points.push_back(p);
00303 color.r = 0.8f;
00304 color.g = 0.2f;
00305 color.b = 1.0f;
00306 color.a = 1.0;
00307 markers.colors.push_back(color);
00308
00309 marker_pub.publish(markers);
00310
00311 printf("num pts = %d\n",(int)markers.points.size());
00312 printf("num colors = %d\n",(int)markers.colors.size());
00313
00314 cloud.header.stamp = ros::Time::now();
00315 ROS_INFO("publishing cloud with %d points",(int)cloud.size());
00316
00317 pcl::toROSMsg(cloud, cloud_msg);
00318 cloud_pub.publish(cloud_msg);
00319
00320 c_polygon_representation *plg[10];
00321
00323
00324
00325
00326
00328 sensor_msgs::PointCloud2 cloud_model_msg;
00329
00330
00332 pcl::SACSegmentation<PointT> seg;
00333 seg.setOptimizeCoefficients(true);
00334 seg.setModelType(pcl::SACMODEL_PLANE);
00335 seg.setMethodType (pcl::SAC_RANSAC);
00336 seg.setDistanceThreshold (0.3);
00337 seg.setMaxIterations (1000);
00338
00340 pcl::ExtractIndices<PointT> extract;
00341
00342
00343 pcl::PointCloud<PointT> cloud_tmp;
00344 cloud_tmp = cloud;
00345
00347 for (int i=0; i<_NUM_POLYGONS_;i++)
00348 {
00349
00350 plg[i] = new c_polygon_representation;
00352 seg.setInputCloud(cloud_tmp.makeShared());
00353 seg.segment(*plg[i]->indices, *plg[i]->coefficients);
00354
00355 if (plg[i]->indices->indices.size () == 0)
00356 {
00357 ROS_ERROR("Could not estimate a planar model for the given dataset."); return (-1);
00358 }
00359
00360
00361
00363 extract.setInputCloud(cloud_tmp.makeShared());
00364 extract.setIndices(plg[i]->indices);
00365 extract.setNegative(false);
00366 extract.filter(plg[i]->cloud);
00367 extract.setNegative(true);
00368 extract.filter(cloud_tmp);
00369 }
00370
00372 for (int i=0; i<_NUM_POLYGONS_;i++)
00373 {
00374
00376 plg[i]->cloud.header.frame_id = "/sensor_frame";
00377 plg[i]->cloud.height = 1;
00378 plg[i]->cloud.is_dense=0;
00379 plg[i]->cloud.width = plg[i]->cloud.size();
00380 ROS_INFO("publishing cloud_model[%d] with %d points",i,(int)plg[i]->cloud.size());
00381 pcl::toROSMsg(plg[i]->cloud, cloud_model_msg);
00382 pub[i].publish(cloud_model_msg);
00383 }
00384
00385
00386
00387
00388
00389
00390
00391
00392
00393
00394
00395
00396
00397
00398
00399
00402
00403
00404
00405
00406
00407
00408
00409
00410
00411
00412
00413
00414
00415
00416
00417
00418
00419 r.sleep();
00420
00421
00422 }
00423 lcm_eventlog_free_event(event);
00424
00425 lcm_eventlog_destroy(log);
00426
00427
00428 return 0;
00429 }
00430
00431 #endif
00432