$search
00001 00002 #include <blort/Recognizer3D/Recognizer3D.h> 00003 00004 #include <opencv/cv.h> 00005 #include <opencv/highgui.h> 00006 #include <opencv/cxcore.h> 00007 #include <blort/Recognizer3D/SDraw.hh> 00008 #include <blort/Recognizer3D/cvgeometry.h> 00009 #include <blort/TomGine/tgModelLoader.h> 00010 #include <blort/TomGine/tgCollission.h> 00011 #include <blort/blort/pal_util.h> 00012 #include <ros/ros.h> 00013 00014 using namespace blortRecognizer; 00015 00016 CameraParameter::CameraParameter(const sensor_msgs::CameraInfo &cam_info) 00017 { 00018 w = cam_info.width; 00019 h = cam_info.height; 00020 fx =cam_info.K.at(0); 00021 cx = cam_info.K.at(2); 00022 fy = cam_info.K.at(4); 00023 cy = cam_info.K.at(5); 00024 k1 = cam_info.D.at(0); 00025 k2 = cam_info.D.at(1); 00026 k3 = cam_info.D.at(4); 00027 p1 = cam_info.D.at(2); 00028 p2 = cam_info.D.at(3); 00029 } 00030 00031 void Recognizer3D::Convert(P::PoseCv& p1, TomGine::tgPose& p2){ 00032 00033 mat3 cR; 00034 vec3 ct; 00035 00036 cR[0] = cvmGet(p1.R,0,0); cR[3] = cvmGet(p1.R,0,1); cR[6] = cvmGet(p1.R,0,2); 00037 cR[1] = cvmGet(p1.R,1,0); cR[4] = cvmGet(p1.R,1,1); cR[7] = cvmGet(p1.R,1,2); 00038 cR[2] = cvmGet(p1.R,2,0); cR[5] = cvmGet(p1.R,2,1); cR[8] = cvmGet(p1.R,2,2); 00039 00040 ct.x = cvmGet(p1.t,0,0); 00041 ct.y = cvmGet(p1.t,1,0); 00042 ct.z = cvmGet(p1.t,2,0); 00043 00044 p2.SetPose(cR,ct); 00045 } 00046 00047 Recognizer3D::Recognizer3D(const blortRecognizer::CameraParameter& camParam, 00048 std::string config_root, bool display) 00049 { 00050 do_undistort = true; 00051 this->config_root = config_root; 00052 pIntrinsicDistort = cvCreateMat(3,3, CV_64FC1); 00053 pDistortion = cvCreateMat(1,4, CV_64FC1); 00054 C = cvCreateMat(3,3, CV_32F); 00055 00056 m_cp = camParam; 00057 00058 cvmSet(pIntrinsicDistort, 0, 0, camParam.fx); 00059 cvmSet(pIntrinsicDistort, 0, 1, 0.); 00060 cvmSet(pIntrinsicDistort, 0, 2, camParam.cx); 00061 cvmSet(pIntrinsicDistort, 1, 0, 0.); 00062 cvmSet(pIntrinsicDistort, 1, 1, camParam.fy); 00063 cvmSet(pIntrinsicDistort, 1, 2, camParam.cy); 00064 cvmSet(pIntrinsicDistort, 2, 0, 0.); 00065 cvmSet(pIntrinsicDistort, 2, 1, 0.); 00066 cvmSet(pIntrinsicDistort, 2, 2, 1.); 00067 00068 cvmSet(pDistortion, 0, 0, camParam.k1); 00069 cvmSet(pDistortion, 0, 1, camParam.k2); 00070 cvmSet(pDistortion, 0, 2, camParam.k3); 00071 cvmSet(pDistortion, 0, 3, 0.0); 00072 00073 //camera matrix for undistorted images 00074 cvmSet(C, 0, 0, camParam.fx); 00075 cvmSet(C, 0, 1, 0.); 00076 cvmSet(C, 0, 2, camParam.cx); 00077 cvmSet(C, 1, 0, 0.); 00078 cvmSet(C, 1, 1, camParam.fy); 00079 cvmSet(C, 1, 2, camParam.cy); 00080 cvmSet(C, 2, 0, 0.); 00081 cvmSet(C, 2, 1, 0.); 00082 cvmSet(C, 2, 2, 1.); 00083 00084 m_detect.SetCameraParameter(C); 00085 00086 pMapX = cvCreateMat (camParam.h, camParam.w, CV_32FC1 ); 00087 pMapY = cvCreateMat (camParam.h, camParam.w, CV_32FC1 ); 00088 cvInitUndistortMapExact(pIntrinsicDistort, pDistortion, pMapX, pMapY); 00089 00090 m_gauss_kernel = 5; 00091 m_gauss_dev = 1.5; 00092 00093 m_display = display; 00094 00095 m_model_loaded = false; 00096 00097 // // create and initialize opencv-based 3D detector core 00098 // cv_detect = cv::Ptr<pal_blort::CvDetect3D>(new pal_blort::CvDetect3D("FAST","SIFT","FlannBased")); 00099 // cv_detect->setCameraMatrix(cv::Mat(pIntrinsicDistort, true)); 00100 // cv::Mat dist_coeffs(1, 5, CV_32FC1); 00101 // dist_coeffs.at<float>(0,0) = camParam.k1; 00102 // dist_coeffs.at<float>(0,1) = camParam.k2; 00103 // dist_coeffs.at<float>(0,2) = camParam.p1; 00104 // dist_coeffs.at<float>(0,3) = camParam.p2; 00105 // dist_coeffs.at<float>(0,4) = camParam.k3; 00106 // cv_detect->setDistCoeffs(dist_coeffs); 00107 } 00108 00109 Recognizer3D::~Recognizer3D() 00110 { 00111 cvReleaseMat(&pIntrinsicDistort); 00112 cvReleaseMat(&pDistortion); 00113 cvReleaseMat(&C); 00114 cvReleaseMat(&pMapX); 00115 cvReleaseMat(&pMapY); 00116 } 00117 00118 void Recognizer3D::setCameraParameter(const blortRecognizer::CameraParameter& camParam) 00119 { 00120 m_cp = camParam; 00121 00122 cvmSet(pIntrinsicDistort, 0, 0, camParam.fx); 00123 cvmSet(pIntrinsicDistort, 0, 1, 0.); 00124 cvmSet(pIntrinsicDistort, 0, 2, camParam.cx); 00125 cvmSet(pIntrinsicDistort, 1, 0, 0.); 00126 cvmSet(pIntrinsicDistort, 1, 1, camParam.fy); 00127 cvmSet(pIntrinsicDistort, 1, 2, camParam.cy); 00128 cvmSet(pIntrinsicDistort, 2, 0, 0.); 00129 cvmSet(pIntrinsicDistort, 2, 1, 0.); 00130 cvmSet(pIntrinsicDistort, 2, 2, 1.); 00131 00132 cvmSet(pDistortion, 0, 0, camParam.k1); 00133 cvmSet(pDistortion, 0, 1, camParam.k2); 00134 cvmSet(pDistortion, 0, 2, camParam.k3); 00135 cvmSet(pDistortion, 0, 3, 0.0); 00136 00137 //camera matrix for undistorted images 00138 cvmSet(C, 0, 0, camParam.fx); 00139 cvmSet(C, 0, 1, 0.); 00140 cvmSet(C, 0, 2, camParam.cx); 00141 cvmSet(C, 1, 0, 0.); 00142 cvmSet(C, 1, 1, camParam.fy); 00143 cvmSet(C, 1, 2, camParam.cy); 00144 cvmSet(C, 2, 0, 0.); 00145 cvmSet(C, 2, 1, 0.); 00146 cvmSet(C, 2, 2, 1.); 00147 00148 m_detect.SetCameraParameter(C); 00149 00150 pMapX = cvCreateMat (camParam.h, camParam.w, CV_32FC1 ); 00151 pMapY = cvCreateMat (camParam.h, camParam.w, CV_32FC1 ); 00152 cvInitUndistortMapExact(pIntrinsicDistort, pDistortion, pMapX, pMapY); 00153 } 00154 00155 bool Recognizer3D::recognize(IplImage* tFrame, TomGine::tgPose& pose, float &conf) 00156 { 00157 P::PoseCv cvPose; 00158 bool detected = false; 00159 conf = 0.0f; 00160 00161 if(!m_model_loaded || m_sift_model.codebook.Empty()) 00162 { 00163 ROS_DEBUG("[Recognizer3D::recognize] Warning: no sift points in codebook of object (did you load the model before?) -- Possible GPU library error."); 00164 return false; 00165 } 00166 00167 IplImage* tImg = 0; 00168 IplImage* grey = 0; 00169 00170 tImg = cvCreateImage( cvGetSize ( tFrame ), 8, 3 ); 00171 grey = cvCreateImage( cvGetSize ( tFrame ), 8, 1 ); 00172 00173 // undistort 00174 if(do_undistort) 00175 { 00176 cvRemap(tFrame, tImg, pMapX, pMapY); 00177 }else{ 00178 cvCopy(tFrame, tImg); 00179 } 00180 00181 // convert to gray scale image 00182 cvConvertImage(tImg, grey); 00183 00184 // extract sifts from current image 00185 sift.Operate(grey, m_image_keys); 00186 m_detect.SetDebugImage(tImg); 00187 00188 if(m_display) 00189 sift.Draw(tImg, m_image_keys); 00190 00191 //EXPERIMENTAL 00192 //cv_detect->detect(cv::Mat(grey, true), m_sift_model); 00193 if(m_detect.Detect(m_image_keys, m_sift_model)) 00194 { 00195 if(m_sift_model.conf > 0.03) 00196 { 00197 conf = m_sift_model.conf; 00198 if(m_display) 00199 { 00200 // object contours & features drawn with green 00201 P::SDraw::DrawPoly(tImg, m_sift_model.contour.v, CV_RGB(0,255,0),2); 00202 m_detect.DrawInlier(tImg, CV_RGB(0,255,0)); 00203 } 00204 CopyPoseCv(m_sift_model.pose, cvPose); 00205 Convert(cvPose, pose); 00206 ROS_DEBUG("[Recognizer3D::recognize] object found (conf: %f)\n", m_sift_model.conf); 00207 detected = true; 00208 }else{ 00209 if(m_display) 00210 // pose estimage object contours drawn with purple 00211 P::SDraw::DrawPoly(tImg, m_sift_model.contour.v, CV_RGB(128,0,128),2); 00212 00213 ROS_DEBUG("[Recognizer3D::recognize] No object (conf: %f)\n", m_sift_model.conf); 00214 detected = false; 00215 } 00216 00217 }else{ 00218 conf = m_sift_model.conf; 00219 00220 if(m_display) 00221 P::SDraw::DrawPoly(tImg, m_sift_model.contour.v, CV_RGB(128,0,128),2); 00222 00223 ROS_DEBUG("[Recognizer3D::recognize] No object (conf: %f)\n", m_sift_model.conf); 00224 detected = false; 00225 } 00226 00227 if(m_display) 00228 { 00229 display_image = cv::Mat(tImg, true); 00230 } 00231 00232 cvReleaseImage(&tImg); 00233 cvReleaseImage(&grey); 00234 00235 //EXPERIMENTAL 00236 //debug_image = cv_detect->getImage(); 00237 00238 return detected; 00239 } 00240 00241 bool Recognizer3D::learnSifts(IplImage* tFrame, const TomGine::tgModel& m1, const TomGine::tgPose& pose) 00242 { 00243 P::Array<P::KeypointDescriptor*> m_tmp_keys; 00244 00245 mat3 R, Rt; 00246 vec3 t; 00247 TomGine::tgModel m2 = m1; 00248 m_lastsiftexlist.clear(); 00249 00250 // Transform model vertices to camera coordinats 00251 pose.GetPose(R,t); 00252 Rt = R.transpose(); 00253 for(unsigned int i=0; i<m2.m_vertices.size(); i++) 00254 { 00255 m2.m_vertices[i].pos = (R * m2.m_vertices[i].pos) + t; 00256 m2.m_vertices[i].normal = R * m2.m_vertices[i].normal; 00257 } 00258 00259 IplImage* tImg = 0; 00260 IplImage* grey = 0; 00261 float dcpfx = 1/m_cp.fx; 00262 float dcpfy = 1/m_cp.fy; 00263 00264 tImg = cvCreateImage ( cvGetSize ( tFrame ), 8, 3 ); 00265 grey = cvCreateImage ( cvGetSize ( tFrame ), 8, 1 ); 00266 00267 // undistort 00268 cvRemap(tFrame, tImg, pMapX, pMapY ); 00269 00270 // convert to gray scale image 00271 cvConvertImage(tImg, grey); 00272 00273 //EXPERIMENTAL: 00274 // cv::Mat descriptors; 00275 // std::vector<cv::KeyPoint> keypoints; 00276 // cv_detect->extract(cv::Mat(grey, true), descriptors, keypoints); 00277 // 00278 // pal_blort::CvDetect3D::cvKeypoints2BlortKeyPoints( 00279 // descriptors, keypoints, m_image_keys); 00280 // END OF EXPERIMENTAL 00281 00282 sift.Operate(grey, m_image_keys); 00283 00284 for(unsigned int i=0; i<m_image_keys.Size(); i++) 00285 { 00286 vec3 point, normal; 00287 std::vector<vec3> pl; // point list 00288 std::vector<vec3> nl; // normal list 00289 std::vector<double> zl; // z-value list (depth) 00290 float u,v,x,y; 00291 00292 u = (float)m_image_keys[i]->p.x; 00293 v = (float)m_image_keys[i]->p.y; 00294 x = (u-m_cp.cx) * dcpfx; 00295 y = (v-m_cp.cy) * dcpfy; 00296 00297 // Create ray from pixel 00298 TomGine::tgRay ray; 00299 ray.start = vec3(0.0f,0.0f,0.0f); 00300 ray.dir = vec3(x,y,1.0f); 00301 ray.dir.normalize(); 00302 00303 if( TomGine::tgCollission::IntersectRayModel(pl, nl, zl, ray, m2) 00304 && !pl.empty() 00305 && !zl.empty()) 00306 { 00307 // determine nearest intersection point 00308 unsigned int idx_min = 0; 00309 float z_min = zl[0]; 00310 for(unsigned int idx=0; idx<zl.size(); idx++){ 00311 if(zl[idx] < z_min){ 00312 idx_min = idx; 00313 z_min = zl[idx]; 00314 } 00315 } 00316 00317 if(z_min > 0.0f){ 00318 // Transform to object space 00319 point = (Rt * (pl[idx_min] - t)); 00320 normal = (Rt * nl[idx_min]); 00321 vec3 r = (Rt * ray.dir) * zl[idx_min]; 00322 00323 Siftex s; 00324 s.pos = point; 00325 s.normal = normal; 00326 s.viewray = r; 00327 00328 normal.normalize(); 00329 r.normalize(); 00330 00331 if( (r * normal) < -0.1f) 00332 { 00333 // Save sift 00334 m_siftexlist.push_back(s); 00335 m_lastsiftexlist.push_back(s); 00336 m_image_keys[i]->SetPos(point.x, point.y, point.z); 00337 m_tmp_keys.PushBack(m_image_keys[i]); 00338 } 00339 } 00340 } 00341 00342 } 00343 00344 if(m_tmp_keys.Size() > 0) 00345 { 00346 m_sift_model_learner.AddToModel(m_tmp_keys, m_sift_model); 00347 ROS_INFO("[Recognizer3D::learnSifts] added %d sifts to model\n", m_tmp_keys.Size()); 00348 m_model_loaded = true; 00349 } 00350 00351 if(m_display){ 00352 display_image = cv::Mat(tImg, true); 00353 } 00354 00355 cvReleaseImage(&tImg); 00356 cvReleaseImage(&grey); 00357 00358 return true; 00359 } 00360 00361 bool Recognizer3D::loadModelFromFile(const std::string sift_file) 00362 { 00363 ROS_INFO("[Recognizer3D::loadModelFromFile] loading sift model from '%s'\n", sift_file.c_str()); 00364 m_model_loaded = m_sift_model_learner.LoadModel(pal_blort::addRoot(sift_file, config_root), m_sift_model); 00365 //EXPERIMENTAL 00366 //cv_detect->addCodeBook(m_sift_model); 00367 return true; 00368 } 00369 00370 bool Recognizer3D::saveModelToFile(const char* sift_file) 00371 { 00372 ROS_INFO("[Recognizer3D::saveModelToFile] saving sift model to '%s'\n", sift_file); 00373 m_sift_model_learner.SaveModel(pal_blort::addRoot(sift_file, config_root).c_str(), m_sift_model); 00374 return true; 00375 } 00376 00377 unsigned int Recognizer3D::getCodeBookSize() 00378 { 00379 return m_sift_model.codebook.Size(); 00380 } 00381 00382 void Recognizer3D::setNNThreshold(double nn_threshold) 00383 { 00384 m_detect.setNNThreshold(nn_threshold); 00385 } 00386 00387 void Recognizer3D::setRansacNPointsToMatch(unsigned int n) 00388 { 00389 m_detect.setNPointsToMatch(n); 00390 }