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
00036 #ifndef _extract_polygon_primitives_AUXILIARY_CPP_
00037 #define _extract_polygon_primitives_AUXILIARY_CPP_
00038
00039
00040 #include "extract_polygon_primitives.h"
00041
00049 int get_vehicle_position(ros::NodeHandle *pn, tf::TransformListener* listener, tf::StampedTransform* vehicle_tf, ros::Time* t)
00050 {
00051 ros::spinOnce();
00052 bool cont=true;
00053
00054 while(cont && pn->ok())
00055 {
00056 cont=false;
00057
00058 try
00059 {
00060
00061 listener->lookupTransform("/world", "/tf_vehicle", ros::Time(0), *vehicle_tf);
00062 }
00063 catch (tf::TransformException ex)
00064 {
00065 ROS_ERROR("%s",ex.what());
00066 cont = true;
00067 ros::Duration(0.1).sleep();
00068 }
00069 }
00070
00071 return 1;
00072 }
00073
00081 int save_pc_PointNormal_to_pcd(pcl::PointCloud<pcl::PointXYZ>* pc_in, pcl::PointCloud<pcl::Normal>* normals_in, std::string name)
00082 {
00083 pcl::PointCloud<pcl::PointNormal> pc;
00084 pcl::concatenateFields (*pc_in, *normals_in, pc);
00085 sensor_msgs::PointCloud2 msg;
00086 pcl::toROSMsg(pc, msg);
00087 pcl::io::savePCDFile(name.c_str(), msg);
00088 return 1;
00089 }
00090
00103 int compute_normals(pcl::PointCloud<pcl::PointXYZ>* pc_in, float vx, float vy, float vz, float radius, int K, pcl::PointCloud<pcl::Normal>* pc_out)
00104 {
00105 ros::Time t = ros::Time::now();
00106
00107 pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
00108
00109
00110 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00111
00112 ne.setSearchMethod(tree);
00113 ne.setViewPoint(vx,vy,vz);
00114 ne.setInputCloud(pc_in->makeShared());
00115
00116 if (K==0)
00117 ne.setRadiusSearch(radius);
00118 else if (radius==0)
00119 ne.setKSearch(K);
00120 else
00121 {
00122 ROS_ERROR("Cannot compute normals. Either radius=%f or K=%d must be 0, so that one is selected", radius, K);
00123 return 0;
00124 }
00125
00126 ne.compute(*pc_out);
00127
00128 for (size_t i=0; i<pc_out->points.size(); ++i)
00129 {
00130 pcl::flipNormalTowardsViewpoint( pc_in->points[i], vx,vy,vz,pc_out->points[i].normal[0], pc_out->points[i].normal[1],pc_out->points[i].normal[2]);
00131 }
00132
00133 ROS_INFO("Estimated normals in %f secs. pc_in with %ld points. radius=%f K=%d", (ros::Time::now() -t).toSec(), pc_in->points.size(), radius, K);
00134 return 1;
00135 }
00136
00137 void filter_uncoherent_points(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ> *pcout, pcl::PointCloud<pcl::PointXYZ>* pcelim, pcl::PointCloud<pcl::Normal>::Ptr n ,double radius, float vx, float vy, float vz)
00138 {
00139 pcl::PointCloud<pcl::PointNormal>::Ptr tmp_in = pcl::PointCloud<pcl::PointNormal>::Ptr(new pcl::PointCloud<pcl::PointNormal>) ;
00140 pcl::concatenateFields(*pcin, *n, *tmp_in);
00141 pcl::PointCloud<pcl::PointNormal>::Ptr tmp_out = pcl::PointCloud<pcl::PointNormal>::Ptr(new pcl::PointCloud<pcl::PointNormal>);
00142 pcl::PointCloud<pcl::PointNormal>::Ptr tmp_elim = pcl::PointCloud<pcl::PointNormal>::Ptr(new pcl::PointCloud<pcl::PointNormal>);
00143
00144 ros::Time t = ros::Time::now();
00145 filter_uncoherent_points(tmp_in, radius, tmp_out, tmp_elim, vx, vy, vz);
00146
00147 pcout->points.erase(pcout->points.begin(), pcout->points.end());
00148 for (size_t i=0; i< tmp_out->points.size(); i++)
00149 {
00150 pcl::PointXYZ pt(tmp_out->points[i].x, tmp_out->points[i].y, tmp_out->points[i].z);
00151 pcout->points.push_back(pt);
00152 }
00153
00154 pcout->height = 1;
00155 pcout->is_dense=0;
00156 pcout->header.frame_id = pcin->header.frame_id;
00157 pcout->width = pcout->points.size();
00158
00159 pcelim->points.erase(pcelim->points.begin(), pcelim->points.end());
00160 for (size_t i=0; i< tmp_elim->points.size(); i++)
00161 {
00162 pcl::PointXYZ pt(tmp_elim->points[i].x, tmp_elim->points[i].y, tmp_elim->points[i].z);
00163 pcelim->points.push_back(pt);
00164 }
00165
00166 pcelim->height = 1;
00167 pcelim->is_dense=0;
00168 pcelim->header.frame_id = pcin->header.frame_id;
00169 pcelim->width = pcelim->points.size();
00170
00171
00172 ROS_INFO("Normal orientation entropy filter: pts in %ld pts out %ld removed %ld, (in %f secs)",pcin->points.size(), pcout->points.size(), pcelim->points.size(), (ros::Time::now() -t).toSec());
00173 tmp_in.reset();
00174 tmp_out.reset();
00175 tmp_elim.reset();
00176 }
00177
00178 void get_limits(double mean, double std, double factor, double *high, double *low)
00179 {
00180 (*high) = mean + factor*std;
00181 (*low) = mean - factor*std;
00182 }
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227
00228
00229
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00250
00251
00252
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298 void filter_uncoherent_points(pcl::PointCloud<pcl::PointNormal>::Ptr pc, double radius, pcl::PointCloud<pcl::PointNormal>::Ptr pcout, pcl::PointCloud<pcl::PointNormal>::Ptr pcelim, float vx, float vy, float vz)
00299 {
00300 bool cont=true;
00301
00302 pcl::KdTreeFLANN<pcl::PointNormal> kdtree;
00303 kdtree.setInputCloud(pc);
00304
00305
00306 pcout->points.erase(pcout->points.begin(), pcout->points.end());
00307 pcelim->points.erase(pcelim->points.begin(), pcelim->points.end());
00308
00309
00310 for (int k=0; k< (int)pc->points.size(); k++)
00311 {
00312 std::vector<int> pointIdxRadiusSearch;
00313 std::vector<float> pointRadiusSquaredDistance;
00314 std::vector<Eigen::Vector4f> ev_v;
00315 Eigen::Vector4f ev_k;
00316 std::vector<float> angle_to_avg_v;
00317 double mean, std;
00318
00319
00320 if( kdtree.radiusSearch(pc->points[k], radius, pointIdxRadiusSearch, pointRadiusSquaredDistance) <= 0)
00321 {
00322 ROS_INFO("pt %d error in kdtree",k);
00323 }
00324 else
00325 {
00326
00327 ev_k[0] = pc->points[k].normal[0];
00328 ev_k[1] = pc->points[k].normal[1];
00329 ev_k[2] = pc->points[k].normal[2];
00330 ev_k[3] = 0;
00331
00332
00333 for (size_t i = 0; i < pointIdxRadiusSearch.size (); ++i)
00334 {
00335 pcl::flipNormalTowardsViewpoint(pc->points[k], vx, vy, vz, pc->points[pointIdxRadiusSearch[i]].normal[0], pc->points[pointIdxRadiusSearch[i]].normal[1], pc->points[pointIdxRadiusSearch[i]].normal[2]);
00336 Eigen::Vector4f ev;
00337 ev[0] = pc->points[pointIdxRadiusSearch[i]].normal[0];
00338 ev[1] = pc->points[pointIdxRadiusSearch[i]].normal[1];
00339 ev[2] = pc->points[pointIdxRadiusSearch[i]].normal[2];
00340 ev[3] = 0;
00341 ev_v.push_back(ev);
00342 }
00343
00344
00345 Eigen::Vector4f ev_avg;
00346 float x_acc=0, y_acc=0, z_acc=0;
00347 for (size_t i = 0; i<ev_v.size(); i++)
00348 {
00349 x_acc += ev_v[i][0];
00350 y_acc += ev_v[i][1];
00351 z_acc += ev_v[i][2];
00352 }
00353
00354 ev_avg[0] = x_acc/(double)ev_v.size();
00355 ev_avg[1] = y_acc/(double)ev_v.size();
00356 ev_avg[2] = z_acc/(double)ev_v.size();
00357 ev_avg[3] = 0;
00358
00359 double norm = sqrt(ev_avg[0]*ev_avg[0] + ev_avg[1]*ev_avg[1] + ev_avg[2]*ev_avg[2]);
00360 ev_avg[0] = ev_avg[0]/norm;
00361 ev_avg[1] = ev_avg[1]/norm;
00362 ev_avg[2] = ev_avg[2]/norm;
00363
00364
00365
00366 std::vector<Eigen::Vector4f> ev_v2;
00367 std::vector<bool> ev_is_fliped;
00368
00369 for (size_t i = 0; i<ev_v.size(); i++)
00370 {
00371 double angle_straight = ((float)(pcl::getAngle3D(ev_avg, ev_v[i])*180.0/M_PI));
00372 Eigen::Vector4f ev_fliped;
00373 ev_fliped[0] = -ev_v[i][0];
00374 ev_fliped[1] = -ev_v[i][1];
00375 ev_fliped[2] = -ev_v[i][2];
00376 ev_fliped[3] = -ev_v[i][3];
00377 double angle_fliped = ((float)(pcl::getAngle3D(ev_avg, ev_fliped)*180.0/M_PI));
00378
00379 if (fabs(angle_straight) < fabs(angle_fliped))
00380 {
00381 ev_v2.push_back(ev_v[i]);
00382 ev_is_fliped.push_back(false);
00383 }
00384 else
00385 {
00386 ev_v2.push_back(ev_fliped);
00387 ev_is_fliped.push_back(true);
00388 }
00389
00390 }
00391
00392
00393
00394 Eigen::Vector4f ev2_avg;
00395 x_acc=0, y_acc=0, z_acc=0;
00396 for (size_t i = 0; i<ev_v2.size(); i++)
00397 {
00398 x_acc += ev_v2[i][0];
00399 y_acc += ev_v2[i][1];
00400 z_acc += ev_v2[i][2];
00401 }
00402
00403 ev2_avg[0] = x_acc/(double)ev_v2.size();
00404 ev2_avg[1] = y_acc/(double)ev_v2.size();
00405 ev2_avg[2] = z_acc/(double)ev_v2.size();
00406 ev2_avg[3] = 0;
00407
00408 norm = sqrt(ev2_avg[0]*ev2_avg[0] + ev2_avg[1]*ev2_avg[1] + ev2_avg[2]*ev2_avg[2]);
00409 ev2_avg[0] = ev2_avg[0]/norm;
00410 ev2_avg[1] = ev2_avg[1]/norm;
00411 ev2_avg[2] = ev2_avg[2]/norm;
00412
00413
00414
00415 for (size_t i = 0; i<ev_v2.size(); i++)
00416 {
00417 angle_to_avg_v.push_back((float)(pcl::getAngle3D(ev2_avg, ev_v2[i])*180.0/M_PI));
00418 }
00419
00420
00421
00422 pcl::getMeanStd(angle_to_avg_v, mean, std);
00423
00424
00425 if(std>25 || mean>35)
00426 {
00427 pcelim->points.push_back(pc->points[k]);
00428 }
00429 else
00430 {
00431 pcout->points.push_back(pc->points[k]);
00432 }
00433
00434
00435
00436
00437
00438 if(k%1100==0 && cont &&0)
00439 {
00440
00441
00442 ROS_INFO("Point %d has %ld neighbors",k,ev_v.size());
00443 for (size_t i = 0; i<ev_v.size(); i++)
00444 {
00445 ROS_INFO("Neighbor %ld has %f (degrees)", i, angle_to_avg_v[i]);
00446 }
00447 ROS_INFO("Angle to Average Mean = %f std = %f",mean, std);
00448
00449 draw_markers(k, &ev2_avg, &ev_v2, pc, &pointIdxRadiusSearch, &ev_avg, &ev_is_fliped);
00450
00451 printf("olaolaola!\n");
00452 char ola[1024];
00453 int ret = scanf("%s",ola); ret++;
00454 if (ola[0]=='q') exit(0);
00455 else if (ola[0]=='c') cont=false;
00456
00457
00458 }
00459
00460
00461
00462 }
00463 }
00464
00465 ROS_INFO("pcin =%d points", (int) pc->points.size());
00466 ROS_INFO("pcout =%d points", (int) pcout->points.size());
00467 }
00468
00469 void draw_markers(int k, Eigen::Vector4f* q_avg, std::vector<Eigen::Vector4f>* qv, pcl::PointCloud<pcl::PointNormal>::Ptr pc, std::vector<int>* pointIdxRadiusSearch, Eigen::Vector4f* q_avg0, std::vector<bool>* is_fliped)
00470 {
00471 static ros::Publisher markerarray_pub = pn->advertise<visualization_msgs::MarkerArray>("/Marker_neighbours", 1);
00472
00473 static size_t total_normals=0;
00474
00475 geometry_msgs::Point p;
00476 std_msgs::ColorRGBA color;
00477 visualization_msgs::Marker msg;
00478 visualization_msgs::MarkerArray marker_vec;
00479
00480
00481
00482 msg.header.frame_id = std::string("/world");
00483 msg.header.stamp = ros::Time::now();
00484 msg.ns = "K"; msg.id = 0;
00485 msg.action = visualization_msgs::Marker::ADD;
00486 msg.pose.orientation.w = 1.0;
00487 msg.type = visualization_msgs::Marker::SPHERE;
00488 msg.pose.position.x = pc->points[k].x;
00489 msg.pose.position.y = pc->points[k].y;
00490 msg.pose.position.z = pc->points[k].z;
00491 msg.scale.x = 5; msg.scale.y = 5; msg.scale.z = 5;
00492 msg.color.r = 0; msg.color.g = 0; msg.color.b = 0.3; msg.color.a = 0.2;
00493 marker_vec.markers.push_back(msg);
00494
00495
00496 msg.header.frame_id = std::string("/world");
00497 msg.header.stamp = ros::Time::now();
00498 msg.ns = "neighbors"; msg.id = 0;
00499 msg.action = visualization_msgs::Marker::ADD;
00500 msg.pose.position.x = 0; msg.pose.position.y = 0; msg.pose.position.z = 0;
00501 msg.pose.orientation.x = 0; msg.pose.orientation.y = 0; msg.pose.orientation.z = 0; msg.pose.orientation.w = 1.0;
00502 msg.type = visualization_msgs::Marker::POINTS;
00503 msg.scale.x = 0.03; msg.scale.y = 0.03; msg.scale.z = 0.03;
00504 msg.color.r = 0; msg.color.g = 0; msg.color.b = 1; msg.color.a = 1;
00505
00506 msg.points.erase(msg.points.begin(), msg.points.end());
00507 for (size_t i = 0; i<qv->size(); i++)
00508 {
00509 p.x = pc->points[pointIdxRadiusSearch->at(i)].x;
00510 p.y = pc->points[pointIdxRadiusSearch->at(i)].y;
00511 p.z = pc->points[pointIdxRadiusSearch->at(i)].z;
00512 msg.points.push_back(p);
00513 }
00514 marker_vec.markers.push_back(msg);
00515
00516
00517 msg.header.frame_id = std::string("/world");
00518 msg.header.stamp = ros::Time::now();
00519 msg.ns = "it0_mean";
00520 msg.action = visualization_msgs::Marker::ADD;
00521 msg.pose.position.x = 0; msg.pose.position.y = 0; msg.pose.position.z = 0;
00522 msg.pose.orientation.x = 0; msg.pose.orientation.y = 0; msg.pose.orientation.z = 0; msg.pose.orientation.w = 1.0;
00523 msg.type = visualization_msgs::Marker::ARROW;
00524 msg.id = 0;
00525 msg.scale.x = 0.08; msg.scale.y = 0.2;
00526 msg.color.r = 0; msg.color.g = 0.2; msg.color.b = 0.7; msg.color.a = 0.6;
00527 msg.points.erase(msg.points.begin(), msg.points.end());
00528
00529 p.x = pc->points[k].x; p.y = pc->points[k].y; p.z = pc->points[k].z;
00530 msg.points.push_back(p);
00531 p.x = pc->points[k].x + (*q_avg0)[0]; p.y = pc->points[k].y + (*q_avg0)[1]; p.z = pc->points[k].z + (*q_avg0)[2];
00532 msg.points.push_back(p);
00533 marker_vec.markers.push_back(msg);
00534
00535
00536 msg.header.frame_id = std::string("/world");
00537 msg.header.stamp = ros::Time::now();
00538 msg.ns = "mean";
00539 msg.action = visualization_msgs::Marker::ADD;
00540 msg.pose.position.x = 0; msg.pose.position.y = 0; msg.pose.position.z = 0;
00541 msg.pose.orientation.x = 0; msg.pose.orientation.y = 0; msg.pose.orientation.z = 0; msg.pose.orientation.w = 1.0;
00542 msg.type = visualization_msgs::Marker::ARROW;
00543 msg.id = 0;
00544 msg.scale.x = 0.08; msg.scale.y = 0.2;
00545 msg.color.r = 1; msg.color.g = 0; msg.color.b = 0.3; msg.color.a = 0.6;
00546 msg.points.erase(msg.points.begin(), msg.points.end());
00547
00548 p.x = pc->points[k].x; p.y = pc->points[k].y; p.z = pc->points[k].z;
00549 msg.points.push_back(p);
00550 p.x = pc->points[k].x + (*q_avg)[0]; p.y = pc->points[k].y + (*q_avg)[1]; p.z = pc->points[k].z + (*q_avg)[2];
00551 msg.points.push_back(p);
00552 marker_vec.markers.push_back(msg);
00553
00554
00555 msg.header.frame_id = std::string("/world");
00556 msg.header.stamp = ros::Time::now();
00557 msg.ns = "n_normals";
00558 msg.action = visualization_msgs::Marker::ADD;
00559 msg.pose.position.x = 0; msg.pose.position.y = 0; msg.pose.position.z = 0;
00560 msg.pose.orientation.x = 0; msg.pose.orientation.y = 0; msg.pose.orientation.z = 0; msg.pose.orientation.w = 1.0;
00561 msg.type = visualization_msgs::Marker::ARROW;
00562 msg.scale.x = 0.01;
00563 msg.scale.y = 0.05;
00564
00565 for (size_t i = 0; i < qv->size (); ++i)
00566 {
00567 if ((*is_fliped)[i]==true)
00568 {
00569 msg.color.r = 9; msg.color.g = 0; msg.color.b = 0.0; msg.color.a = 0.3;
00570 }
00571 else
00572 {
00573 msg.color.r = 0; msg.color.g = 1; msg.color.b = 0.3; msg.color.a = 0.3;
00574 }
00575
00576 msg.points.erase(msg.points.begin(), msg.points.end());
00577 msg.id = i;
00578 p.x = pc->points[k].x;
00579 p.y = pc->points[k].y;
00580 p.z = pc->points[k].z;
00581 msg.points.push_back(p);
00582
00583 p.x = pc->points[k].x + (*qv)[i][0];
00584 p.y = pc->points[k].y + (*qv)[i][1];
00585 p.z = pc->points[k].z + (*qv)[i][2];
00586 msg.points.push_back(p);
00587 marker_vec.markers.push_back(msg);
00588 }
00589
00590
00591 for (size_t i = qv->size(); i <total_normals; ++i)
00592 {
00593 msg.type = visualization_msgs::Marker::ARROW;
00594 msg.id = i;
00595 msg.ns = "n_normals";
00596 msg.action = visualization_msgs::Marker::DELETE;
00597 marker_vec.markers.push_back(msg);
00598 }
00599 total_normals = qv->size();
00600
00601
00602 markerarray_pub.publish(marker_vec);
00603 ros::spinOnce();
00604
00605
00606 }
00607
00608
00609
00611
00612
00613
00614
00616
00617
00618
00619
00622
00623
00624
00625
00626
00627
00628
00629
00630
00631
00632
00633
00634
00635
00636
00639
00640
00641
00642
00643
00646
00647
00648
00649
00650
00651
00652
00653
00654
00657
00658
00659
00660
00661
00662
00663
00664
00665
00666
00667
00668
00669
00670
00671
00672
00673
00674
00675
00676
00677
00678
00679
00680
00681
00682
00683
00686
00687
00688
00689
00690
00691
00692
00693
00694
00695
00698
00699
00700
00702
00703
00704
00705
00706
00707
00708
00709
00710
00711
00712
00713
00715
00716
00717
00718
00719
00720
00721
00722
00723
00724
00725
00726
00731
00732
00733
00734
00735
00736
00737
00738
00739
00740
00741
00742
00743
00744
00745
00746
00747
00748
00749
00750
00751
00752
00753
00754
00759
00765
00766
00767
00768
00769
00770
00771
00772
00773
00774
00775
00776
00777
00778
00779
00780
00781
00782
00783
00784
00785
00786
00787
00788
00789
00790 #endif
00791