Go to the documentation of this file.00001 #include <pointcloud_vrml/pointcloud_utils.h>
00002
00003 namespace ndt_feature_reg
00004 {
00005
00006 template <typename PointT>
00007 NDTFrameViewer<PointT>::NDTFrameViewer(NDTFrameProc<PointT> *proc)
00008 {
00009
00010 _proc = proc;
00011 initViewer();
00012 }
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 template <typename PointT>
00023 void
00024 NDTFrameViewer<PointT>::initViewer()
00025 {
00026 _viewer.reset (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00027 _viewer->setBackgroundColor( 0, 0, 0.01 );
00028 _viewer->addCoordinateSystem(1.0);
00029 }
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046 template <typename PointT>
00047 void
00048 NDTFrameViewer<PointT>::showFeaturePC()
00049 {
00050
00051 pcl::PointCloud<pcl::PointXYZRGB>::Ptr big_cloud (new pcl::PointCloud<pcl::PointXYZRGB>());
00052 std::string name = "featcloud";
00053 for (size_t i = 0; i < _proc->frames.size(); i++)
00054 {
00055 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = _proc->createColoredFeaturePC(*_proc->frames[i], this->getPCLColor(i));
00056 lslgeneric::transformPointCloudInPlace(_proc->transformVector[i],*tmp);
00057
00058
00059
00060
00061
00062
00063 *big_cloud += *tmp;
00064 }
00065 big_cloud->is_dense = false;
00066 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(big_cloud);
00067 _viewer->addPointCloud<pcl::PointXYZRGB> (big_cloud, rgb, name);
00068
00069
00070 }
00071
00072 template <typename PointT>
00073 void
00074 NDTFrameViewer<PointT>::showNDT()
00075 {
00076
00077 }
00078
00079 template <typename PointT>
00080 void
00081 NDTFrameViewer<PointT>::showMatches(const std::vector<std::pair<int,int> > &matches)
00082 {
00083 assert(_proc->frames.size() == 2);
00084
00085 for (size_t i = 0; i < matches.size(); i++)
00086 {
00087 const PointT& pt1 = _proc->frames[0]->getKeyPointCenter(matches[i].first);
00088 const PointT& pt2 = _proc->frames[1]->getKeyPointCenter(matches[i].second);
00089
00090 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T = _proc->transformVector[1];
00091 Eigen::Vector3d pt;
00092 pt<<pt2.x,pt2.y,pt2.z;
00093 pt = T*pt;
00094 PointT pt3;
00095 pt3.x = pt(0);
00096 pt3.y = pt(1);
00097 pt3.z = pt(2);
00098
00099 std::string name = "line" + toString(i);
00100 _viewer->addLine<PointT, PointT>(pt1, pt3, 0, 1, 1, name);
00101 }
00102 }
00103
00104 template <typename PointT>
00105 void
00106 NDTFrameViewer<PointT>::showMatches(const std::vector<cv::DMatch> &matches)
00107 {
00108 std::vector<std::pair<int,int> > tmp;
00109 _proc->convertMatches(matches, tmp);
00110 this->showMatches(tmp);
00111 }
00112
00113 template <typename PointT>
00114 bool
00115 NDTFrameViewer<PointT>::wasStopped()
00116 {
00117 return _viewer->wasStopped();
00118 }
00119
00120 template <typename PointT>
00121 void
00122 NDTFrameViewer<PointT>::spinOnce()
00123 {
00124 _viewer->spinOnce(100);
00125 }
00126
00127 }