00001
00063 #include <pcl/features/integral_image_normal.h>
00064
00065 #ifdef PCL_MINOR_VERSION
00066 #if PCL_MINOR_VERSION >= 6
00067 #include <pcl/segmentation/organized_multi_plane_segmentation.h>
00068 #include <pcl/segmentation/edge_aware_plane_comparator.h>
00069 #endif
00070 #endif
00071
00072 #include "cob_3d_mapping_common/label_defines.h"
00073 #include "cob_3d_mapping_common/polygon.h"
00074 #include "cob_3d_segmentation/plane_extraction.h"
00075 #include "cob_3d_segmentation/polygon_extraction/polygon_types.h"
00076 #include "cob_3d_segmentation/polygon_extraction/polygon_extraction.h"
00077 #include "cob_3d_mapping_common/io.h"
00078 #include "cob_3d_mapping_tools/gui/impl/core.hpp"
00079
00080
00081
00082 #include <pcl/filters/voxel_grid.h>
00083 #include <pcl/common/eigen.h>
00084 #include <boost/bind.hpp>
00085 #include <iomanip>
00086 #include <set>
00087
00088 typedef pcl::PointXYZRGB PT;
00089 typedef pcl::PointCloud<PT> PointCloud;
00090
00091 class Cluster;
00092 typedef std::map<int,Cluster> ClusterMap;
00093
00094 class Cluster
00095 {
00096 public:
00097 Cluster(int id_)
00098 : id(id_)
00099 , centroid(Eigen::Vector3f::Zero())
00100 , comp1(Eigen::Vector3f::Zero())
00101 , comp2(Eigen::Vector3f::Zero())
00102 , comp3(Eigen::Vector3f::Zero())
00103 , values(Eigen::Vector3f::Zero())
00104 , poly(new cob_3d_mapping::Polygon)
00105 { }
00106
00107 inline void addBorder(int x, int y) { borders.push_back(cob_3d_segmentation::PolygonPoint(x,y)); }
00108 inline void addPoint(int idx) { indices.push_back(idx); }
00109
00110 friend std::ostream& operator<<( std::ostream& out, Cluster& c);
00111
00112 int id;
00113 std::vector<int> indices;
00114 std::vector<cob_3d_segmentation::PolygonPoint> borders;
00115
00116 Eigen::Vector3f centroid;
00117 Eigen::Vector3f comp1;
00118 Eigen::Vector3f comp2;
00119 Eigen::Vector3f comp3;
00120 Eigen::Vector3f values;
00121 cob_3d_mapping::Polygon::Ptr poly;
00122 };
00123
00124 std::string colorHumanReadable(int id)
00125 {
00126 std::stringstream ss;
00127 ss << "0x" << std::setfill('0') << std::setw(6) << std::right << std::hex << id << std::dec;
00128 return ss.str();
00129 }
00130
00131 std::ostream& operator<< (std::ostream& out, Cluster& c)
00132 {
00133 out << colorHumanReadable(c.id) << " {";
00134
00135
00136 out << "Size: " << std::setw(6) << std::right << c.indices.size();
00137 out << " N: " << std::setiosflags(std::ios::fixed) << std::setprecision(6)
00138 << std::setw(9) << std::right << c.comp3(0) <<","
00139 << std::setw(9) << std::right << c.comp3(1) <<","
00140 << std::setw(9) << std::right << c.comp3(2);
00141
00142
00143
00144 out<<"}";
00145 return out;
00146 }
00147
00148 void printForFile(ClusterMap& exp, ClusterMap& pred)
00149 {
00150 int count_no = 0;
00151
00152
00153 const int padding = 3;
00154 std::stringstream ss;
00155 ss << exp.begin()->second;
00156 int col = ss.str().length() + padding;
00157 std::string sep = "| ";
00158 std::cout <<" - \t"<<" - \t"<<"labeled\t"<<" - \t"<<" - \t"<<"-\t"<<" - \t\t"
00159 <<"plane extraction" << std::endl;
00160 std::cout <<"color\t"<<"size\t"<<" n_x\t"<<"n_y\t"<<"n_z\t"<<"d\t"<<"area\t\t"
00161 <<" n_x\t"<<"n_y\t"<<"n_z\t"<<"d\t"<<"area\t"<<"A_diff\t"<<"dot"<<std::endl;
00162 for(ClusterMap::iterator it=exp.begin(); it!= exp.end(); ++it)
00163 {
00164 cob_3d_mapping::Polygon::Ptr p1 = it->second.poly;
00165 float area1 = p1->computeArea3d();
00166 std::cout << colorHumanReadable(it->second.id) << "\t"
00167 << it->second.indices.size() << "\t"
00168 << it->second.comp3[0] << "\t"
00169 << it->second.comp3[1] << "\t"
00170 << it->second.comp3[2] << "\t"
00171 << it->second.centroid.dot(it->second.comp3) << "\t"
00172 << area1 << "\t\t";
00173 ClusterMap::iterator match = pred.find(it->first);
00174 if (match == pred.end())
00175 {
00176 std::cout << "no match" << std::endl;
00177 ++count_no;
00178 continue;
00179 }
00180 float alpha = it->second.comp3.dot(match->second.comp3);
00181 cob_3d_mapping::Polygon::Ptr p2 = match->second.poly;
00182 float area2 = p2->computeArea3d();
00183 float area_diff = 0;
00184 gpc_polygon gpc_a, gpc_b, gpc_diff;
00185 p1->getGpcStructure(&gpc_a);
00186 p2->getGpcStructure(&gpc_b);
00187 gpc_polygon_clip(GPC_XOR, &gpc_a, &gpc_b, &gpc_diff);
00188
00189
00190 if(gpc_diff.num_contours != 0)
00191 {
00192 p1->applyGpcStructure(&gpc_diff);
00193 area_diff = p1->computeArea3d();
00194 }
00195
00196 std::cout << match->second.comp3[0] << "\t"
00197 << match->second.comp3[1] << "\t"
00198 << match->second.comp3[2] << "\t"
00199 << match->second.centroid.dot(match->second.comp3) << "\t"
00200 << area2 << "\t"
00201 << area_diff << "\t"
00202 << alpha << std::endl;
00203 }
00204 }
00205
00206 void compare(ClusterMap& exp, ClusterMap& pred)
00207 {
00208 int count_no = 0;
00209
00210
00211 const int padding = 3;
00212 std::stringstream ss;
00213 ss << exp.begin()->second;
00214 int col = ss.str().length() + padding;
00215 std::string sep = "| ";
00216
00217 for(ClusterMap::iterator it=exp.begin(); it!= exp.end(); ++it)
00218 {
00219 ClusterMap::iterator match = pred.find(it->first);
00220 if (match == pred.end())
00221 {
00222 std::stringstream ss1;
00223 ss1 << it->second;
00224 std::cout << std::setw(col) << std::left << ss1.str() << sep
00225 << std::setw(round(0.3*col)) << " "
00226 << std::setw(round(0.7*col)) << std::left << "--- No Match ---" << sep << std::endl;
00227 ++count_no;
00228 continue;
00229 }
00230 float alpha = it->second.comp3.dot(match->second.comp3);
00231
00232 cob_3d_mapping::Polygon::Ptr p1 = it->second.poly;
00233 cob_3d_mapping::Polygon::Ptr p2 = match->second.poly;
00234 float area1 = p1->computeArea3d();
00235 float area2 = p2->computeArea3d();
00236 float area_diff = 0;
00237 gpc_polygon gpc_a, gpc_b, gpc_diff;
00238 p1->getGpcStructure(&gpc_a);
00239 p2->getGpcStructure(&gpc_b);
00240 gpc_polygon_clip(GPC_XOR, &gpc_a, &gpc_b, &gpc_diff);
00241
00242
00243 if(gpc_diff.num_contours != 0)
00244 {
00245 p1->applyGpcStructure(&gpc_diff);
00246 area_diff = p1->computeArea3d();
00247 }
00248
00249 std::stringstream ss1, ss2;
00250 ss1 << it->second;
00251 ss2 << match->second;
00252 std::cout << std::setw(col) << std::left << ss1.str() << sep
00253 << std::setw(col) << std::left << ss2.str() << sep
00254 << "Dot: " << std::setw(9) << std::left << std::setiosflags(std::ios::fixed) << std::setprecision(6) << alpha
00255 << " A1: "<< area1 << " A2: "<< area2 << " A_Diff: " << area_diff << std::endl;
00256 }
00257 count_no = exp.size() - count_no;
00258 std::cout << "Results:" << std::endl
00259 << std::setw(30) << std::left << "Matching Accuracy"<<"= ("<<count_no<<"/"<<exp.size()<<") "
00260 << std::setiosflags(std::ios::fixed)<<std::setprecision(2)<<(float)count_no/(float)exp.size()*100.0f << "%" << std::endl;
00261 }
00262
00263 void pca(PointCloud::Ptr cloud, Cluster& c)
00264 {
00265 for(std::vector<int>::iterator it=c.indices.begin(); it!=c.indices.end(); ++it)
00266 c.centroid += (*cloud)[*it].getVector3fMap();
00267 c.centroid /= c.indices.size();
00268
00269 Eigen::Matrix3f cov(Eigen::Matrix3f::Zero());
00270 for(std::vector<int>::iterator it=c.indices.begin(); it!=c.indices.end(); ++it)
00271 {
00272 Eigen::Vector3f demean = (*cloud)[*it].getVector3fMap() - c.centroid;
00273 cov += demean * demean.transpose();
00274 }
00275
00276 Eigen::Matrix3f eigenvectors;
00277 pcl::eigen33(cov, eigenvectors, c.values);
00278 c.values /= c.indices.size();
00279 c.comp1 = eigenvectors.col(2);
00280 c.comp2 = eigenvectors.col(1);
00281 c.comp3 = eigenvectors.col(0);
00282 }
00283
00284 void fillPolygonPtr(Cluster& c, cob_3d_segmentation::PolygonContours<cob_3d_segmentation::PolygonPoint>& contour, PointCloud::Ptr cloud)
00285 {
00286 c.poly->centroid << c.centroid, 0;
00287 c.poly->computeAttributes(c.comp3, c.poly->centroid);
00288 int max_points = -1, max_idx = -1;
00289 for (size_t i=0; i<contour.polys_.size(); ++i)
00290 {
00291 if ((int)contour.polys_[i].size() > max_points) { max_points = contour.polys_[i].size(); max_idx = i; }
00292 }
00293
00294 for (size_t i=0; i<contour.polys_.size(); ++i)
00295 {
00296 c.poly->contours.push_back(std::vector<Eigen::Vector3f>());
00297 if ((int)i == max_idx)
00298 {
00299 c.poly->holes.push_back(false);
00300 std::vector<cob_3d_segmentation::PolygonPoint>::iterator it = contour.polys_[i].begin();
00301 for( ; it != contour.polys_[i].end(); ++it)
00302 c.poly->contours.back().push_back( (*cloud)[cob_3d_segmentation::PolygonPoint::getInd(it->x, it->y)].getVector3fMap() );
00303 }
00304 else
00305 {
00306 c.poly->holes.push_back(true);
00307 std::vector<cob_3d_segmentation::PolygonPoint>::reverse_iterator it = contour.polys_[i].rbegin();
00308 for( ; it != contour.polys_[i].rend(); ++it)
00309 c.poly->contours.back().push_back( (*cloud)[cob_3d_segmentation::PolygonPoint::getInd(it->x, it->y)].getVector3fMap() );
00310 }
00311 }
00312 }
00313
00314 void createClusters(PointCloud::Ptr cloud, ClusterMap& cmap)
00315 {
00316 int w = cloud->width, h = cloud->height, s = cloud->size();
00317 int mask[] = { -w, 1, w, -1 };
00318 int mask_size = 4;
00319
00320 for(int idx=0; idx < s; ++idx)
00321 {
00322 int id = (*cloud)[idx].rgba;
00323 int x = idx % w;
00324 int y = idx / w;
00325 int count = 0;
00326
00327 ClusterMap::iterator it = cmap.find(id);
00328 if (it == cmap.end())
00329 {
00330
00331 it = cmap.insert( std::pair<int,Cluster>(id, Cluster(id)) ).first;
00332 }
00333 if (y == 0 || y == h-1 || x == 0 || x == w-1)
00334 {
00335 it->second.addBorder(x,y);
00336 }
00337 else
00338 {
00339
00340 for(int i=0;i<mask_size;++i)
00341 {
00342 if (id != (*cloud)[idx+mask[i]].rgba) { ++count; }
00343
00344 }
00345
00346 if (count < 1) { it->second.addPoint(idx); }
00347 else { it->second.addBorder(x,y); }
00348 }
00349 }
00350
00351 cob_3d_segmentation::PolygonExtraction pe;
00352 ClusterMap::iterator it=cmap.begin();
00353 while(it!=cmap.end())
00354 {
00355 std::cout << it->second.indices.size() << std::endl;
00356 if (it->first == 0xFFFFFF || it->first == LBL_UNDEF || it->second.indices.size() <= 5)
00357 {
00358
00359 cmap.erase(it++);
00360 }
00361 else
00362 {
00363
00364 cob_3d_segmentation::PolygonContours<cob_3d_segmentation::PolygonPoint> poly;
00365 pe.outline(w, h, it->second.borders, poly);
00366 pca(cloud, it->second);
00367 fillPolygonPtr(it->second, poly, cloud);
00368 ++it;
00369 }
00370 }
00371 }
00372
00373 void createClustersUsingPlaneExtraction(PointCloud::Ptr cloud, ClusterMap& cmap)
00374 {
00375 PointCloud::Ptr pc_copy(new PointCloud);
00376 *pc_copy = *cloud;
00377 pcl::VoxelGrid<PT> voxel;
00378 voxel.setSaveLeafLayout(true);
00379 voxel.setInputCloud(cloud);
00380 voxel.setLeafSize(0.03,0.03,0.03);
00381 voxel.filter(*pc_copy);
00382 for(PointCloud::iterator it = pc_copy->begin(); it != pc_copy->end(); ++it) { it->rgba = LBL_UNDEF; }
00383
00384 std::vector<PointCloud, Eigen::aligned_allocator<PointCloud> > v_hull_pc;
00385 std::vector<std::vector<pcl::Vertices> > v_hull_poly;
00386 std::vector<pcl::ModelCoefficients> v_coef;
00387 PlaneExtraction pe;
00388 pe.setSaveToFile(false);
00389 pe.setClusterTolerance(0.06);
00390 pe.setMinPlaneSize(150);
00391 pe.setAlpha(0.2);
00392 pe.extractPlanes(pc_copy, v_hull_pc, v_hull_poly, v_coef);
00393
00394 std::vector<int> temp_ids;
00395 const float rand_max_inv = 1.0f/ RAND_MAX;
00396 std::cout << "Sizes: idx="<<pe.extracted_planes_indices_.size()
00397 << " coef="<<v_coef.size()<<std::endl;
00398 for (int i=0;i<pe.extracted_planes_indices_.size();++i)
00399 {
00400 int r = (float)rand() * rand_max_inv * 255;
00401 int g = (float)rand() * rand_max_inv * 255;
00402 int b = (float)rand() * rand_max_inv * 255;
00403 int color = ( r << 16 | g << 8 | b );
00404 for(std::vector<int>::iterator idx=pe.extracted_planes_indices_[i].begin();idx!=pe.extracted_planes_indices_[i].end();++idx)
00405 {
00406 (*pc_copy)[*idx].rgba = color;
00407 }
00408 temp_ids.push_back(color);
00409 }
00410 for(pcl::PointCloud<PT>::iterator it = cloud->begin(); it!=cloud->end(); ++it)
00411 {
00412 if (it->z != it->z) { it->rgba = LBL_UNDEF; }
00413 else { it->rgba = (*pc_copy)[voxel.getCentroidIndex(*it)].rgba; }
00414 }
00415
00416 for(int i=0;i<v_hull_pc.size();++i)
00417 {
00418 ClusterMap::iterator it = cmap.insert( std::pair<int,Cluster>(temp_ids[i], Cluster(temp_ids[i])) ).first;
00419 it->second.comp3 = Eigen::Vector3f(v_coef[i].values[0], v_coef[i].values[1], v_coef[i].values[2]);
00420 cob_3d_mapping::Polygon& p = *it->second.poly;
00421 for(int c=0; c<3; c++) p.normal_[c] = v_coef[i].values[c];
00422 p.d_ = v_coef[i].values[3];
00423 it->second.centroid = it->second.comp3 * p.d_;
00424 std::vector<Eigen::Vector3f> pts;
00425 for(int j=0; j<v_hull_pc[i].size(); j++)
00426 pts.push_back(v_hull_pc[i].points[j].getVector3fMap());
00427
00428 p.contours_.push_back(pts);
00429 p.holes_.push_back(false);
00430 p.computeCentroid();
00431 p.computeAttributes(it->second.comp3, p.centroid);
00432 }
00433 }
00434
00435
00436 #ifdef PCL_MINOR_VERSION
00437 #if PCL_MINOR_VERSION >= 6
00438 void createClustersUsingMultiPlaneSegmentation(PointCloud::Ptr cloud, ClusterMap& cmap)
00439 {
00440 pcl::PointCloud<pcl::Normal>::Ptr n(new pcl::PointCloud<pcl::Normal>);
00441 pcl::PointCloud<pcl::Label>::Ptr l(new pcl::PointCloud<pcl::Label>);
00442 float* distance_map;
00443
00444 pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal> ne;
00445 ne.setNormalEstimationMethod(ne.COVARIANCE_MATRIX);
00446 ne.setMaxDepthChangeFactor(0.02f);
00447 ne.setNormalSmoothingSize(40.0f);
00448 ne.setInputCloud(cloud);
00449 ne.compute(*n);
00450 distance_map = ne.getDistanceMap();
00451
00452 std::vector<pcl::PlanarRegion<pcl::PointXYZRGB>, Eigen::aligned_allocator<pcl::PlanarRegion<pcl::PointXYZRGB> > > regions;
00453 std::vector<pcl::ModelCoefficients> coef;
00454 std::vector<pcl::PointIndices> inlier_indices, label_indices, boundary_indices;
00455 pcl::OrganizedMultiPlaneSegmentation<pcl::PointXYZRGB, pcl::Normal, pcl::Label> omps;
00456 pcl::EdgeAwarePlaneComparator<pcl::PointXYZRGB, pcl::Normal>::Ptr comparator(new pcl::EdgeAwarePlaneComparator<pcl::PointXYZRGB, pcl::Normal>(distance_map));
00457 omps.setComparator(comparator);
00458 omps.setInputCloud(cloud);
00459 omps.setInputNormals(n);
00460 omps.setMinInliers(100);
00461 omps.setAngularThreshold(5.0f/180.0f*M_PI);
00462 omps.setMaximumCurvature(0.1);
00463 omps.setDistanceThreshold(0.02f);
00464 omps.segmentAndRefine(regions, coef, inlier_indices, l, label_indices, boundary_indices);
00465
00466 for(pcl::PointCloud<PT>::iterator it = cloud->begin(); it!=cloud->end(); ++it)
00467 it->rgba = LBL_UNDEF;
00468
00469 const float rand_max_inv = 1.0f/ RAND_MAX;
00470 std::vector<int> temp_ids;
00471 for (size_t i = 0; i < inlier_indices.size(); ++i)
00472 {
00473 int r = (float)rand() * rand_max_inv * 255;
00474 int g = (float)rand() * rand_max_inv * 255;
00475 int b = (float)rand() * rand_max_inv * 255;
00476 int color = (r << 16 | b << 8 | b);
00477 for (size_t j=0; j<inlier_indices[i].indices.size(); ++j)
00478 {
00479 (*cloud)[ inlier_indices[i].indices[j] ].rgba = color;
00480 }
00481 temp_ids.push_back(color);
00482 }
00483
00484 for(int i=0;i<boundary_indices.size();++i)
00485 {
00486 ClusterMap::iterator it = cmap.insert( std::pair<int,Cluster>(temp_ids[i], Cluster(temp_ids[i])) ).first;
00487 it->second.comp3 = Eigen::Vector3f(coef[i].values[0], coef[i].values[1], coef[i].values[2]);
00488 cob_3d_mapping::Polygon& p = *it->second.poly;
00489 for(int c=0; c<3; c++) p.normal[c] = coef[i].values[c];
00490 p.d = coef[i].values[3];
00491 it->second.centroid = it->second.comp3 * p.d;
00492 std::vector<Eigen::Vector3f> pts;
00493 for(int j=0; j<boundary_indices[i].indices.size(); ++j)
00494 pts.push_back((*cloud)[boundary_indices[i].indices[j]].getVector3fMap());
00495 for(int j=0; j<inlier_indices[i].indices.size(); ++j)
00496 it->second.indices.push_back(inlier_indices[i].indices[j]);
00497
00498 p.contours.push_back(pts);
00499 p.holes.push_back(false);
00500 p.computeCentroid();
00501 p.computeAttributes(it->second.comp3, p.centroid);
00502 }
00503 }
00504 #endif
00505 #endif
00506
00507
00508
00509
00510
00511
00512 class MainApp : public wxApp
00513 {
00514 typedef Gui::ResourceTypes::Image RImg;
00515 typedef Gui::ResourceTypes::OrganizedPointCloud<PT> RPC;
00516 typedef Gui::ViewTypes::Color VCol;
00517
00518
00519 Gui::Core* c;
00520 PointCloud::Ptr pc_exp;
00521 PointCloud::Ptr pc_pred;
00522
00523 ClusterMap exp;
00524 ClusterMap pred;
00525 ClusterMap pred_new;
00526
00527 ClusterMap::iterator c_it;
00528
00529 Gui::Resource<RImg>* r_tmp;
00530 Gui::View<RImg,VCol>* v_tmp;
00531 std::set<int> used_ids;
00532
00533 public:
00534 MainApp() : pc_exp(new PointCloud), pc_pred(new PointCloud)
00535 {
00536 c = Gui::Core::Get();
00537 }
00538
00539 void OnClick(wxMouseEvent& event, Gui::Resource<RPC>* rs)
00540 {
00541 wxPoint p = event.GetPosition();
00542 int rgba = rs->getData()->at(p.x,p.y).rgba;
00543 if(rgba == LBL_UNDEF)
00544 {
00545 std::cout<<"you dismissed this cluster! continue..."<<std::endl;
00546 ++c_it;
00547 showNext();
00548 return;
00549 }
00550 if (rgba == 0xFFFFFF)
00551 {
00552 std::cout<<"you can't use this one! please try again..."<<std::endl;
00553 return;
00554 }
00555 if (used_ids.find(rgba) != used_ids.end())
00556 {
00557 std::cout<<"you already used this one! please try again..."<<std::endl;
00558 return;
00559 }
00560
00561 (pred_new.insert(std::pair<int,Cluster>(c_it->first, pred.find(rgba)->second))).first->second.id = c_it->first;
00562 used_ids.insert(rgba);
00563 std::cout<<"You matched: "<<colorHumanReadable(rgba)<<std::endl;
00564 std::cout<<"Size now: " << pred_new.size() << std::endl;
00565
00566 ++c_it;
00567 showNext();
00568 }
00569
00570 void showNext()
00571 {
00572 if(c_it == exp.end())
00573 {
00574 std::cout << "you're done here..." <<std::endl;
00575 std::cout << "these are your results! Hope u like 'em :)\n"<<std::endl;
00576 printForFile(exp, pred_new);
00577
00578 if(this->argc == 4)
00579 {
00580 ClusterMap::iterator it = pred_new.begin();
00581 while(it!=pred_new.end())
00582 {
00583 for(int i=0; i<it->second.indices.size(); ++i)
00584 {
00585 (*pc_pred)[it->second.indices[i]].rgba = it->second.id;
00586 }
00587 ++it;
00588 }
00589 std::string file_out(wxString(this->argv[3]).mb_str());
00590 cob_3d_mapping_common::PPMWriter wppm;
00591 wppm.writeRGB(file_out, *pc_pred);
00592 }
00593
00594 return;
00595 }
00596 Gui::cvImagePtr cvmat = r_tmp->getData();
00597 cv::Vec3b dark = cv::Vec3b((int)50,(int)50,(int)50), id;
00598 id[0] = c_it->first & 0x0000ff;
00599 id[1] = (c_it->first >> 8) & 0x0000ff;
00600 id[2] = (c_it->first >> 16) & 0x0000ff;
00601
00602 for (int y = 0; y<cvmat->rows; ++y)
00603 {
00604 for (int x = 0; x<cvmat->cols; ++x)
00605 {
00606 cv::Vec3b& here = (*cvmat)(y,x);
00607
00608 here = dark;
00609 }
00610 }
00611
00612 std::vector<int>::iterator it = c_it->second.indices.begin(), it_end = c_it->second.indices.end();
00613 while(it != it_end)
00614 {
00615 int v = int(*it) / int(640);
00616 int u = int(*it) % int(640);
00617
00618 cv::Vec3b& here = (*cvmat)(v,u);
00619 here = id;
00620 ++it;
00621 }
00622
00623 if(c_it == exp.begin()) { v_tmp->show(); return; }
00624 else v_tmp->onDataChanged();
00625 }
00626
00627 bool OnInit()
00628 {
00629 if (this->argc < 3) { std::cout << "command path_to_pointcloud.pcd path_to_groundtruth.ppm " << std::endl; exit(0); }
00630
00631
00632
00633
00634
00635
00636
00637
00638
00639
00640
00641
00642
00643
00644
00645
00646
00647 std::string file_pcd(wxString(this->argv[1]).mb_str());
00648 std::string file_ppm(wxString(this->argv[2]).mb_str());
00649 if (pcl::io::loadPCDFile<PT>(file_pcd, *pc_exp) < 0) exit(0);
00650 cob_3d_mapping_tools::PPMReader ppm;
00651 if (ppm.mapRGB(file_ppm, *pc_exp, true) == -1) { exit(0); }
00652 *pc_pred = *pc_exp;
00653 std::cout << pc_exp->width << " " << pc_exp->height << std::endl;
00654 createClusters(pc_exp, exp);
00655
00656 #ifdef PCL_MINOR_VERSION
00657 #if PCL_MINOR_VERSION >= 6
00658 createClustersUsingMultiPlaneSegmentation(pc_pred, pred);
00659 #else
00660 createClustersUsingPlaneExtraction(pc_pred, pred);
00661 #endif
00662 #else
00663 createClustersUsingPlaneExtraction(pc_pred, pred);
00664 #endif
00665 c_it = exp.begin();
00666
00667 Gui::Resource<RPC>* r_exp = Gui::Core::rMan()->create<RPC>("res_expected", pc_exp);
00668 Gui::Resource<RPC>* r_pred = Gui::Core::rMan()->create<RPC>("res_predicted", pc_pred);
00669
00670 Gui::View<RPC,VCol>* v_exp = r_exp->createView<VCol>("Expectation");
00671 Gui::View<RPC,Gui::ViewTypes::Depth_Z>* v2_exp = r_exp->createView<Gui::ViewTypes::Depth_Z>("depth_exp");
00672 Gui::View<RPC,VCol>* v_pred = r_pred->createView<VCol>("Prediction");
00673 r_tmp = Gui::Core::rMan()->create<RImg>("res_copy", file_ppm);
00674 v_tmp = r_tmp->createView<VCol>("CurrentCluster");
00675
00676 boost::function<void (wxMouseEvent&, Gui::Resource<RPC>*)> f = boost::bind(&MainApp::OnClick, this, _1, _2);
00677 v_pred->registerMouseCallback(f);
00678
00679
00680 v_exp->show();
00681 v_pred->show();
00682 Gui::Core::wMan()->moveWindow(v_pred, 700, 0);
00683 v2_exp->show();
00684 showNext();
00685
00686
00687 std::cout << "Done init" << std::endl;
00688 return true;
00689 }
00690
00691 int OnExit()
00692 {
00693 std::cout << "I shut myself down!" << std::endl;
00694 return 0;
00695 }
00696
00697 };
00698
00699 IMPLEMENT_APP(MainApp)