00001 00064 #pragma once 00065 00066 #include <ros/console.h> 00067 #include <opencv2/core/core.hpp> 00068 #include <pcl/common/common.h> 00069 #include <pcl/point_types.h> 00070 #include <pcl/point_cloud.h> 00071 00072 namespace cob_3d_registration { 00073 00085 template <typename Point> 00086 class GeneralRegistration 00087 { 00088 public: 00089 GeneralRegistration():transformation_(Eigen::Matrix4f::Identity()),moved_(true),scene_changed_(false) 00090 {} 00091 00092 virtual ~GeneralRegistration() {} 00093 00095 virtual void setOdometry (const Eigen::Matrix4f &odometry) { 00096 transformation_ = odometry; 00097 } 00098 00100 virtual void setInputCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud) {//(const pcl::PointCloud<Point>::ConstPtr &cloud) { 00101 input_ = cloud; 00102 } 00103 00104 //TODO: change this mispelled word 00106 virtual void setInputOginalCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud) {//(const pcl::PointCloud<Point>::ConstPtr &cloud) { 00107 input_org_ = cloud; 00108 } 00109 00111 virtual void setInputImage (const boost::shared_ptr<const cv::Mat> &img) { 00112 input_image_ = img; 00113 } 00114 00116 virtual void setInputDepthImage (const boost::shared_ptr<const cv::Mat> &img) { 00117 input_depth_image_ = img; 00118 } 00119 00121 virtual boost::shared_ptr<const pcl::PointCloud<Point> > getMarkers() {return boost::shared_ptr<const pcl::PointCloud<Point> >();} 00122 00127 virtual bool compute() { 00128 if(!compute_features()) 00129 return false; 00130 if(!compute_corrospondences()) 00131 return false; 00132 if(!compute_transformation()) 00133 return false; 00134 return true; 00135 } 00136 00138 virtual Eigen::Matrix4f getTransformation() const {return transformation_;} 00139 virtual void setTransformation(const Eigen::Matrix4f &mat) {transformation_=mat;} 00140 virtual void setMoved(const bool b) {moved_=b;} 00141 virtual bool getSceneChanged() const {return scene_changed_;} 00142 00144 virtual boost::shared_ptr<pcl::PointCloud<Point> > getMap() {ROS_ERROR("should never happ"); return boost::shared_ptr<pcl::PointCloud<Point> >(new pcl::PointCloud<Point>);} 00145 00146 protected: 00147 00148 virtual bool compute_features()=0; 00149 virtual bool compute_corrospondences()=0; 00150 virtual bool compute_transformation()=0; 00151 00152 boost::shared_ptr<const pcl::PointCloud<Point> > input_, input_org_; 00153 boost::shared_ptr<const cv::Mat> input_image_, input_depth_image_; 00154 Eigen::Matrix4f transformation_; 00155 bool moved_, scene_changed_; 00156 00157 }; 00158 00159 }