$search
00001 00002 #include <blort/Tracker/TextureTracker.h> 00003 #include <blort/TomGine/tgLighting.h> 00004 #include <blort/TomGine/tgMaterial.h> 00005 #include <blort/TomGine/tgError.h> 00006 00007 00008 using namespace std; 00009 using namespace Tracking; 00010 using namespace TomGine; 00011 00012 // *** PRIVATE *** 00013 00014 // Draw TrackerModel to screen, extract modelview matrix, perform image processing for model 00015 void TextureTracker::model_processing(ModelEntry* modelEntry){ 00016 00017 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 00018 00019 // Render camera image as background 00020 if(modelEntry->model.getTextured()){ 00021 glDisable(GL_DEPTH_TEST); 00022 glDepthMask(0); 00023 m_ip->render(m_tex_frame); 00024 glDepthMask(1); 00025 glEnable(GL_DEPTH_TEST); 00026 } 00027 00028 // Render textured model to screen 00029 m_cam_perspective.Activate(); 00030 m_lighting.Activate(); 00031 modelEntry->pose.Activate(); 00032 modelEntry->model.restoreTexture(); 00033 modelEntry->model.drawPass(); 00034 00035 // Extract modelview-projection matrix 00036 mat4 modelview, projection; 00037 glGetFloatv(GL_MODELVIEW_MATRIX, modelview); 00038 glGetFloatv(GL_PROJECTION_MATRIX, projection); 00039 modelEntry->modelviewprojection = projection * modelview; 00040 00041 // pass new modelview matrix to shader 00042 m_shadeCompare->bind(); 00043 m_shadeCompare->setUniform("modelviewprojection", modelEntry->modelviewprojection, GL_FALSE); // send matrix to shader 00044 m_shadeCompare->unbind(); 00045 m_shadeConfidenceMM->bind(); 00046 m_shadeConfidenceMM->setUniform("modelviewprojection", modelEntry->modelviewprojection, GL_FALSE); // send matrix to shader 00047 m_shadeConfidenceMM->unbind(); 00048 modelEntry->pose.Deactivate(); 00049 m_lighting.Deactivate(); 00050 00051 // Copy model rendered into image to texture (=reprojection to model) 00052 m_tex_model->copyTexImage2D(params.camPar.width, params.camPar.height); 00053 00054 // perform image processing with reprojected image 00055 glDisable(GL_DEPTH_TEST); 00056 glDepthMask(0); 00057 00058 // Extract edges in various line widths 00059 if(modelEntry->model.getTextured()){ 00060 m_ip->gauss(m_tex_model, m_tex_model_ip[0]); 00061 m_ip->sobel(m_tex_model_ip[0], m_tex_model_ip[0], params.model_sobel_th, true); 00062 }else{ 00063 m_ip->sobel(m_tex_model, m_tex_model_ip[0], params.model_sobel_th, true); 00064 } 00065 00066 if(modelEntry->mask_geometry_edges){ 00067 Texture mask; 00068 this->computeModelEdgeMask(modelEntry, mask); 00069 m_ip->thinning(m_tex_model_ip[0], m_tex_model_ip[0], &mask); 00070 }else{ 00071 m_ip->thinning(m_tex_model_ip[0], m_tex_model_ip[0]); 00072 } 00073 00074 for(unsigned i=1; i<params.num_spreadings; i++) 00075 m_ip->spreading(m_tex_model_ip[i-1], m_tex_model_ip[i]); 00076 00077 glDepthMask(1); 00078 } 00079 00080 // Particle filtering 00081 void TextureTracker::particle_filtering(ModelEntry* modelEntry){ 00082 int num_particles; 00083 m_cam_perspective.Activate(); 00084 00085 // Calculate Zoom Direction and pass it to the particle filter 00086 TomGine::tgVector3 vCam = m_cam_perspective.GetPos(); 00087 TomGine::tgVector3 vObj = TomGine::tgVector3(modelEntry->pose.t.x, modelEntry->pose.t.y, modelEntry->pose.t.z); 00088 modelEntry->vCam2Model = vObj - vCam; 00089 modelEntry->predictor->setCamViewVector(modelEntry->vCam2Model); 00090 00091 Particle variation = params.variation; 00092 00093 for(unsigned i=0; i<modelEntry->num_recursions; i++){ 00094 // unsigned i=0; 00095 // TODO Evaluate if this makes sense (robustness, accuracy) 00096 // float c_max = modelEntry->distribution.getMaxC(); 00097 // params.m_spreadlvl = (int)floor((params.num_spreadings)*(0.5-c_max)); 00098 // if(params.m_spreadlvl>=params.num_spreadings) 00099 // params.m_spreadlvl = params.num_spreadings-1; 00100 // else if(params.m_spreadlvl<0) 00101 // params.m_spreadlvl = 0; 00102 00103 // TODO Evaluate if this makes sense (robustness, accuracy) 00104 int j = (int)params.num_spreadings - (int)i; 00105 if(j > 1){ 00106 params.m_spreadlvl = j - 1; 00107 }else{ 00108 params.m_spreadlvl = 1; 00109 } 00110 float varred_t = 1.0f; 00111 float varred_q = 1.0f; 00112 float varred_z = 1.0f; 00113 if(modelEntry->num_recursions > 1){ 00114 varred_t = 1.0f - 0.7f * float(i)/(modelEntry->num_recursions - 1); 00115 varred_q = 1.0f - 0.8f * float(i)/(modelEntry->num_recursions - 1); 00116 varred_z = 1.0f - 0.8f * float(i)/(modelEntry->num_recursions - 1); 00117 } 00118 variation.t = params.variation.t * varred_t; 00119 variation.q = params.variation.q * varred_q; 00120 variation.z = params.variation.z * varred_z; 00121 00122 // variation.z = params.variation.z * varred; 00123 // ROS_DEBUG("%d %f %f %f\n", params.m_spreadlvl, variation.t.x, variation.r.x*180/PI, varred_t); 00124 00125 // if(i == modelEntry->num_recursions - 1) 00126 // m_showparticles = true; 00127 // else 00128 // m_showparticles = false; 00129 00130 //BENCE: commented these, they are not really used 00131 // m_tex_model_ip[params.m_spreadlvl]->bind(0); 00132 // m_tex_frame_ip[params.m_spreadlvl]->bind(1); 00133 // m_tex_model->bind(2); 00134 // m_tex_frame->bind(3); 00135 00136 // TODO Evaluate if this makes sense (robustness, accuracy) 00137 // params.kernel_size = (int)floor(0.5*(params.max_kernel_size)*(1.0-c_max)); 00138 // m_shadeCompare->bind(); 00139 // m_shadeCompare->setUniform("kernelsize", params.kernel_size); 00140 // m_shadeCompare->unbind(); 00141 00142 // update importance weights and confidence levels 00143 // ROS_DEBUG("Recursion[%d] %d c:%f p: ", i, params.m_spreadlvl, modelEntry->distribution.getParticle(0).c); 00144 // modelEntry->distribution.getParticle(0).Print(); 00145 modelEntry->distribution.updateLikelihood(modelEntry->model, m_shadeCompare, 1, params.convergence, m_showparticles); 00146 00147 //modelEntry->distribution = d1; 00148 // ROS_DEBUG("%f\n", ( 1.0 - i * 0.5 / (float)(modelEntry->num_recursions-1))); 00149 // TODO Evaluate if this makes sense (accuracy) 00150 // p = (params.variation * ( 1.0 - i * 0.8 / (float)(modelEntry->num_recursions-1))); 00151 00152 // "Attention mechanism" modifies number of particles indirect proportional to the overall confidence 00153 //num_particles = modelEntry->num_particles * (1.0 - c_max); 00154 num_particles = modelEntry->num_particles; 00155 00156 // predict movement of object 00157 00158 modelEntry->predictor->resample(modelEntry->distribution, num_particles, variation, (i==0)); 00159 00160 // set timestep to 0.0 for further recursion (within same image) 00161 modelEntry->predictor->updateTime(0.0); 00162 } 00163 tgCheckError("TextureTracker::particle_filtering"); 00164 // weighted mean 00165 modelEntry->pose_prev = modelEntry->pose; 00166 modelEntry->pose = modelEntry->distribution.getMean(); 00167 // modelEntry->pose = modelEntry->distribution.getParticle(0); 00168 } 00169 00170 00171 00172 // *** PUBLIC *** 00173 00174 TextureTracker::TextureTracker(){ 00175 m_lock = false; 00176 m_showparticles = false; 00177 m_showmodel = 0; 00178 m_draw_edges = false; 00179 m_tracker_initialized = false; 00180 m_drawimage = false; 00181 } 00182 00183 TextureTracker::~TextureTracker(){ 00184 delete(m_tex_model); 00185 for(unsigned i=0; i<params.num_spreadings; i++){ 00186 delete(m_tex_model_ip[i]); 00187 } 00188 } 00189 00190 // Initialise function (must be called before tracking) 00191 bool TextureTracker::initInternal(){ 00192 00193 int id; 00194 00195 // Shader 00196 if((id = g_Resources->AddShader("texEdgeTest", "texEdgeTest.vert", "texEdgeTest.frag")) == -1) 00197 exit(1); 00198 m_shadeTexEdgeTest = g_Resources->GetShader(id); 00199 00200 if((id = g_Resources->AddShader("texColorTest", "texColorTest.vert", "texColorTest.frag")) == -1) 00201 exit(1); 00202 m_shadeTexColorTest = g_Resources->GetShader(id); 00203 00204 if((id = g_Resources->AddShader("mmConfidence", "mmConfidence.vert", "mmConfidence.frag")) == -1) 00205 exit(1); 00206 m_shadeConfidenceMM = g_Resources->GetShader(id); 00207 00208 m_shadeCompare = m_shadeTexEdgeTest; 00209 00210 // Texture 00211 m_tex_model = new Texture(); 00212 glTexEnvf(GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_REPLACE); 00213 00214 m_tex_model_ip.push_back( new Texture() ); 00215 glTexEnvf(GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_REPLACE); 00216 for(int i=0; i<(int)params.num_spreadings-1; i++){ 00217 m_tex_model_ip.push_back( new Texture() ); 00218 glTexEnvf(GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_REPLACE); 00219 } 00220 00221 // Load 00222 float w = (float)params.camPar.width; 00223 float h = (float)params.camPar.height; 00224 00225 GLfloat offX[9] = { -1.0f/w, 0.0f, 1.0f/w, 00226 -1.0f/w, 0.0f, 1.0f/w, 00227 -1.0f/w, 0.0f, 1.0f/w }; 00228 GLfloat offY[9] = { 1.0f/h, 1.0f/h, 1.0f/h, 00229 0.0f, 0.0f, 0.0f, 00230 -1.0f/h,-1.0f/h, -1.0f/h }; 00231 00232 m_shadeTexEdgeTest->bind(); 00233 m_shadeTexEdgeTest->setUniform("tex_model_edge", 0); 00234 m_shadeTexEdgeTest->setUniform("tex_frame_edge", 1); 00235 m_shadeTexEdgeTest->setUniform("fTol", params.edge_tolerance); 00236 m_shadeTexEdgeTest->setUniform( "mOffsetX", mat3(offX), GL_FALSE ); 00237 m_shadeTexEdgeTest->setUniform( "mOffsetY", mat3(offY), GL_FALSE ); 00238 m_shadeTexEdgeTest->setUniform("drawcolor", vec4(1.0f,0.0f,0.0f,0.0f)); 00239 m_shadeTexEdgeTest->setUniform("kernelsize", (GLint)params.kernel_size); 00240 m_shadeTexEdgeTest->unbind(); 00241 00242 m_shadeTexColorTest->bind(); 00243 m_shadeTexColorTest->setUniform("tex_model_color", 2); 00244 m_shadeTexColorTest->setUniform("tex_frame_color", 3); 00245 m_shadeTexColorTest->setUniform("fTol", params.edge_tolerance); 00246 m_shadeTexColorTest->setUniform( "mOffsetX", mat3(offX), GL_FALSE ); 00247 m_shadeTexColorTest->setUniform( "mOffsetY", mat3(offY), GL_FALSE ); 00248 m_shadeTexColorTest->setUniform("drawcolor", vec4(0.0f,0.0f,1.0f,0.0f)); 00249 m_shadeTexColorTest->setUniform("kernelsize", (GLint)params.kernel_size); 00250 m_shadeTexColorTest->unbind(); 00251 00252 m_shadeConfidenceMM->bind(); 00253 m_shadeConfidenceMM->setUniform("tex_model_color", 2); 00254 m_shadeConfidenceMM->setUniform("tex_frame_color", 3); 00255 m_shadeConfidenceMM->setUniform("fTol", params.edge_tolerance); 00256 m_shadeConfidenceMM->setUniform( "mOffsetX", mat3(offX), GL_FALSE ); 00257 m_shadeConfidenceMM->setUniform( "mOffsetY", mat3(offY), GL_FALSE ); 00258 m_shadeConfidenceMM->setUniform("drawcolor", vec4(0.0f,0.0f,1.0f,0.0f)); 00259 m_shadeConfidenceMM->setUniform("kernelsize", (GLint)params.kernel_size); 00260 m_shadeConfidenceMM->unbind(); 00261 00262 tgLight light; 00263 tgVector3 cam_f = m_cam_perspective.GetF(); 00264 light.ambient = vec4(0.4f,0.4f,0.4f,1.0f); 00265 light.diffuse = vec4(1.0f,1.0f,1.0f,1.0f); 00266 light.specular = vec4(1.0f,1.0f,1.0f,1.0f); 00267 light.position = vec4(-cam_f.x, -cam_f.y, -cam_f.z, 1.0f); 00268 m_lighting.ApplyLight(light,0); 00269 00270 return true; 00271 } 00272 00273 float TextureTracker::evaluateParticle(ModelEntry* modelEntry) 00274 { 00275 return evaluateParticle(modelEntry, m_shadeCompare); 00276 } 00277 00278 // evaluate single particle 00279 float TextureTracker::evaluateParticle(ModelEntry* modelEntry, Shader* shader){ 00280 unsigned int queryMatches; 00281 unsigned int queryEdges; 00282 int v, d; 00283 float c; 00284 00285 glGenQueriesARB(1, &queryMatches); 00286 glGenQueriesARB(1, &queryEdges); 00287 00288 m_cam_perspective.Activate(); 00289 //glViewport(0,0,256,256); 00290 glColorMask(0,0,0,0); glDepthMask(0); 00291 glColor3f(1.0,1.0,1.0); 00292 00293 m_tex_model_ip[params.m_spreadlvl]->bind(0); 00294 m_tex_frame_ip[params.m_spreadlvl]->bind(1); 00295 m_tex_model->bind(2); 00296 m_tex_frame->bind(3); 00297 00298 // Draw particles and count pixels 00299 shader->bind(); 00300 shader->setUniform("analyze", false); 00301 00302 modelEntry->pose.Activate(); 00303 00304 // Draw all model edge pixels 00305 glBeginQueryARB(GL_SAMPLES_PASSED_ARB, queryEdges); 00306 shader->setUniform("compare", false); 00307 if(m_showparticles) 00308 glColorMask(1,1,1,1); 00309 modelEntry->model.drawTexturedFaces(); 00310 modelEntry->model.drawUntexturedFaces(); 00311 glEndQueryARB(GL_SAMPLES_PASSED_ARB); 00312 00313 glColorMask(0,0,0,0); 00314 00315 // Draw matching model edge pixels using a shader 00316 glBeginQueryARB(GL_SAMPLES_PASSED_ARB, queryMatches); 00317 shader->setUniform("compare", true); 00318 shader->setUniform("textured", true); 00319 modelEntry->model.drawTexturedFaces(); 00320 shader->setUniform("textured", false); 00321 modelEntry->model.drawUntexturedFaces(); 00322 glEndQueryARB(GL_SAMPLES_PASSED_ARB); 00323 00324 modelEntry->pose.Deactivate(); 00325 00326 shader->unbind(); 00327 00328 glGetQueryObjectivARB(queryMatches, GL_QUERY_RESULT_ARB, &d); 00329 glGetQueryObjectivARB(queryEdges, GL_QUERY_RESULT_ARB, &v); 00330 glColorMask(1,1,1,1); glDepthMask(1); 00331 glDeleteQueriesARB(1, &queryMatches); 00332 glDeleteQueriesARB(1, &queryEdges); 00333 00334 c = modelEntry->distribution.confidenceFunction(d,v); 00335 00336 00337 00338 return c; 00339 } 00340 00341 // Process camera image (gauss, sobel, thinning, spreading, rendering) 00342 void TextureTracker::image_processing(unsigned char* image, GLenum format){ 00343 00344 // Load camera image to texture 00345 m_tex_frame->load(image, params.camPar.width, params.camPar.height, format); 00346 00347 // Preprocessing for camera image 00348 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 00349 glDisable(GL_DEPTH_TEST); 00350 glDepthMask(0); 00351 glColor3f(1.0,1.0,1.0); 00352 00353 m_ip->flipUpsideDown(m_tex_frame, m_tex_frame); 00354 00355 m_ip->gauss(m_tex_frame, m_tex_frame_ip[0]); 00356 m_ip->sobel(m_tex_frame_ip[0], m_tex_frame_ip[0], params.image_sobel_th, true); 00357 m_ip->thinning(m_tex_frame_ip[0], m_tex_frame_ip[0]); 00358 for(unsigned i=1; i<params.num_spreadings; i++) 00359 m_ip->spreading(m_tex_frame_ip[i-1], m_tex_frame_ip[i]); 00360 00361 glDepthMask(1); 00362 } 00363 00364 // Process camera image (gauss, sobel, thinning, spreading, rendering) 00365 void TextureTracker::image_processing(unsigned char* image, const TomGine::tgModel &m, const tgPose &p, GLenum format){ 00366 00367 // Load camera image to texture 00368 m_tex_frame->load(image, params.camPar.width, params.camPar.height, format); 00369 00370 // Preprocessing for camera image 00371 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 00372 glDisable(GL_DEPTH_TEST); 00373 glDepthMask(0); 00374 glColor3f(1.0,1.0,1.0); 00375 00376 m_ip->flipUpsideDown(m_tex_frame, m_tex_frame); 00377 00378 // Draw model (i.e. a virutal occluder) 00379 glDepthMask(1); 00380 glEnable(GL_DEPTH_TEST); 00381 drawModel(m,p); 00382 glDisable(GL_DEPTH_TEST); 00383 glDepthMask(0); 00384 m_tex_frame->copyTexImage2D(params.camPar.width, params.camPar.height); 00385 00386 m_ip->gauss(m_tex_frame, m_tex_frame_ip[0]); 00387 m_ip->sobel(m_tex_frame_ip[0], m_tex_frame_ip[0], params.image_sobel_th, true); 00388 m_ip->thinning(m_tex_frame_ip[0], m_tex_frame_ip[0]); 00389 for(unsigned i=1; i<params.num_spreadings; i++) 00390 m_ip->spreading(m_tex_frame_ip[i-1], m_tex_frame_ip[i]); 00391 00392 glDepthMask(1); 00393 } 00394 00395 void TextureTracker::image_processing(unsigned char* image, int model_id, const tgPose &p, GLenum format){ 00396 00397 // Load camera image to texture 00398 m_tex_frame->load(image, params.camPar.width, params.camPar.height, format); 00399 00400 // Preprocessing for camera image 00401 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 00402 glDisable(GL_DEPTH_TEST); 00403 glDepthMask(0); 00404 glColor3f(1.0,1.0,1.0); 00405 00406 m_ip->flipUpsideDown(m_tex_frame, m_tex_frame); 00407 00408 // glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 00409 00410 // Draw model (i.e. a virutal occluder) 00411 ModelEntryList::iterator it = m_modellist.begin(); 00412 while(it != m_modellist.end()){ 00413 if(model_id==(*it)->id){ 00414 m_cam_perspective.Activate(); 00415 glClear(GL_DEPTH_BUFFER_BIT); 00416 m_lighting.Activate(); 00417 glEnable(GL_DEPTH_TEST); 00418 glDepthMask(1); 00419 p.Activate(); 00420 00421 //(*it)->model.restoreTexture(); 00422 (*it)->model.drawPass(); 00423 00424 p.Deactivate(); 00425 glDepthMask(0); 00426 glDisable(GL_DEPTH_TEST); 00427 m_lighting.Deactivate(); 00428 glClear(GL_DEPTH_BUFFER_BIT); 00429 } 00430 ++it; 00431 } 00432 m_tex_frame->copyTexImage2D(params.camPar.width, params.camPar.height); 00433 00434 m_ip->gauss(m_tex_frame, m_tex_frame_ip[0]); 00435 m_ip->sobel(m_tex_frame_ip[0], m_tex_frame_ip[0], params.image_sobel_th, true); 00436 m_ip->thinning(m_tex_frame_ip[0], m_tex_frame_ip[0]); 00437 for(unsigned i=1; i<params.num_spreadings; i++) 00438 m_ip->spreading(m_tex_frame_ip[i-1], m_tex_frame_ip[i]); 00439 00440 glDepthMask(1); 00441 } 00442 00443 bool TextureTracker::track(){ 00444 if(!m_tracker_initialized){ 00445 ROS_DEBUG("[TextureTracker::track()] Error tracker not initialised!\n"); 00446 return false; 00447 } 00448 00449 // Track models 00450 for(unsigned i=0; i<m_modellist.size(); i++){ 00451 track(m_modellist[i]); 00452 } 00453 00454 //BENCE: this part never runs 00455 // Track hypothesis 00456 // ModelEntryList::iterator m1 = m_hypotheses.begin(); 00457 // while(m1 < m_hypotheses.end()){ 00458 // track((*m1)); 00459 // if((*m1)->num_convergence++>params.hypotheses_trials){ 00460 // if((*m1)->past_confidences.size() < params.hypotheses_trials){ 00461 // 00462 // (*m1)->past_confidences.push_back((*m1)->distribution.getMaxC()); 00463 // m_modellist[(*m1)->hypothesis_id]->past_confidences.push_back(m_modellist[(*m1)->hypothesis_id]->distribution.getMaxC()); 00464 // }else{ 00465 // 00466 // // Evaluate mean confidence of hypothesis 00467 // float c_hyp = 0.0; 00468 // int s = (*m1)->past_confidences.size(); 00469 // for(int j=0; j<s; j++){ 00470 // c_hyp += (*m1)->past_confidences[j]; 00471 // } 00472 // if(s>0) 00473 // c_hyp = c_hyp / (float)s; 00474 // 00475 // // Evaluate mean confidence of model, the hypothesis belongs to 00476 // float c_model = 0.0; 00477 // s = m_modellist[(*m1)->hypothesis_id]->past_confidences.size(); 00478 // for(int j=0; j<s; j++){ 00479 // c_model += m_modellist[(*m1)->hypothesis_id]->past_confidences[j]; 00480 // } 00481 // if(s>0) 00482 // c_model = c_model / (float)s; 00483 // 00484 // // Compare confidence of model to the hypothesis 00485 // if(c_model >= c_hyp){ 00486 // // if model is more confident, delete hypothesis 00487 // delete(*m1); 00488 // m_hypotheses.erase(m1); 00489 // }else{ 00490 // // if hypothesis is more confident, delete model and replace modellist-entry with hypothesis 00491 // delete(m_modellist[(*m1)->hypothesis_id]); 00492 // (*m1)->id = (*m1)->hypothesis_id; 00493 // m_modellist[(*m1)->hypothesis_id] = (*m1); 00494 // m_hypotheses.erase(m1); 00495 // } 00496 // } 00497 // } 00498 // m1++; 00499 // } 00500 tgCheckError("TextureTracker::track()"); 00501 return true; 00502 } 00503 00504 bool TextureTracker::track(ModelEntry *modelEntry){ 00505 00506 // Process model (texture reprojection, edge detection) 00507 model_processing(modelEntry); 00508 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 00509 00510 if(m_drawimage) 00511 drawImage(false); 00512 00513 // Apply particle filtering 00514 if(!modelEntry->lock){ 00515 particle_filtering(modelEntry); 00516 if(!m_cam_perspective.GetFrustum()->PointInFrustum(modelEntry->pose.t.x, modelEntry->pose.t.y, modelEntry->pose.t.z)) 00517 reset(); 00518 }else{ 00519 modelEntry->pose.c = evaluateParticle(modelEntry, m_shadeCompare); 00520 } 00521 00522 modelEntry->confidence_edge = evaluateParticle(modelEntry, m_shadeTexEdgeTest); 00523 modelEntry->confidence_color = evaluateParticle(modelEntry, m_shadeTexColorTest); 00524 00525 modelEntry->filter_pose(); 00526 modelEntry->evaluate_states(params.variation, params.num_recursions, 00527 params.c_th_base, params.c_th_min, params.c_th_fair, 00528 params.c_mv_not, params.c_mv_slow, params.c_th_lost); 00529 00530 m_ftime = (float)m_timer.Update(); 00531 return true; 00532 } 00533 00534 bool TextureTracker::track(int id){ 00535 if(!m_tracker_initialized){ 00536 ROS_DEBUG("[TextureTracker::track(int)] Error tracker not initialised!\n"); 00537 return false; 00538 } 00539 00540 ModelEntryList::iterator it = m_modellist.begin(); 00541 while(it != m_modellist.end()){ 00542 if(id==(*it)->id){ 00543 track(m_modellist[id]); 00544 tgCheckError("TextureTracker::track(int)"); 00545 return true; 00546 } 00547 ++it; 00548 } 00549 00550 return false; 00551 } 00552 00553 // grabs texture from camera image and attaches it to faces of model 00554 void TextureTracker::textureFromImage(bool use_num_pixels){ 00555 std::vector<tgVertex> vertices; 00556 00557 Parameter tmpParams = params; 00558 00559 params.num_particles = 500; 00560 params.num_recursions = 10; 00561 params.m_spreadlvl = 0; 00562 params.variation = params.variation * 0.1; 00563 setKernelSize(0); 00564 00565 track(); 00566 00567 params = tmpParams; 00568 setKernelSize(params.kernel_size); 00569 00570 for(unsigned i=0; i<m_modellist.size(); i++){ 00571 00572 m_cam_perspective.Activate(); 00573 vector<unsigned> faceUpdateList = m_modellist[i]->model.getFaceUpdateList(m_modellist[i]->pose, 00574 vec3(m_modellist[i]->vCam2Model.x, m_modellist[i]->vCam2Model.y, m_modellist[i]->vCam2Model.z), 00575 params.minTexGrabAngle, 00576 use_num_pixels); 00577 00578 if(!faceUpdateList.empty()){ 00579 vertices.clear(); 00580 m_modellist[i]->model.textureFromImage( m_tex_frame, 00581 params.camPar.width, params.camPar.height, 00582 m_modellist[i]->pose, 00583 vec3(m_modellist[i]->vCam2Model.x, m_modellist[i]->vCam2Model.y, m_modellist[i]->vCam2Model.z), 00584 params.minTexGrabAngle, 00585 faceUpdateList, 00586 vertices, 00587 &m_cam_perspective); 00588 } 00589 faceUpdateList.clear(); 00590 } 00591 } 00592 00593 // grabs texture from camera image and attaches it to faces of model 00594 void TextureTracker::textureFromImage(int id, const TomGine::tgPose &pose, bool use_num_pixels){ 00595 std::vector<tgVertex> vertices; 00596 00597 ModelEntry* modelEntry = 0; 00598 ModelEntryList::iterator it = m_modellist.begin(); 00599 while(it != m_modellist.end()){ 00600 if(id==(*it)->id){ 00601 modelEntry = (*it); 00602 } 00603 ++it; 00604 } 00605 00606 modelEntry->pose = pose; 00607 00608 m_cam_perspective.Activate(); 00609 vector<unsigned> faceUpdateList = modelEntry->model.getFaceUpdateList(modelEntry->pose, 00610 vec3(modelEntry->vCam2Model.x, modelEntry->vCam2Model.y, modelEntry->vCam2Model.z), 00611 params.minTexGrabAngle, 00612 use_num_pixels); 00613 00614 if(!faceUpdateList.empty()){ 00615 vertices.clear(); 00616 00617 modelEntry->model.textureFromImage(m_tex_frame, 00618 params.camPar.width, params.camPar.height, 00619 modelEntry->pose, 00620 vec3(modelEntry->vCam2Model.x, modelEntry->vCam2Model.y, modelEntry->vCam2Model.z), 00621 params.minTexGrabAngle, 00622 faceUpdateList, 00623 vertices, 00624 &m_cam_perspective); 00625 } 00626 faceUpdateList.clear(); 00627 } 00628 00629 void TextureTracker::untextureModels(){ 00630 for(unsigned i=0; i<m_modellist.size(); i++){ 00631 m_modellist[i]->model.releasePassList(); 00632 } 00633 } 00634 00635 // Draw result of texture tracking (particle with maximum likelihood) 00636 void TextureTracker::drawResult(float linewidth){ 00637 00638 m_cam_perspective.Activate(); 00639 m_lighting.Activate(); 00640 00641 glEnable(GL_DEPTH_TEST); 00642 glClear(GL_DEPTH_BUFFER_BIT); 00643 00644 for(unsigned i=0; i<m_modellist.size(); i++){ 00645 drawModelEntry(m_modellist[i], linewidth); 00646 } 00647 00648 // for(int i=0; i<m_hypotheses.size(); i++){ 00649 // drawModelEntry(m_hypotheses[i]); 00650 // } 00651 00652 m_lighting.Deactivate(); 00653 tgCheckError("TextureTracker::drawResult B"); 00654 } 00655 00656 void TextureTracker::drawModelEntry(ModelEntry* modelEntry, float linewidth){ 00657 00658 modelEntry->pose.Activate(); 00659 00660 switch(m_showmodel){ 00661 case 0: 00662 modelEntry->model.restoreTexture(); 00663 modelEntry->model.drawPass(false); 00664 break; 00665 case 1: 00666 m_lighting.Deactivate(); 00667 //glColorMask(0,0,0,0); 00668 //modelEntry->model.drawFaces(); 00669 //glColorMask(1,1,1,1); 00670 if(linewidth<1.0f) 00671 linewidth = 1.0f; 00672 glLineWidth(linewidth); 00673 modelEntry->model.drawEdges(); 00674 glColor3f(1.0,1.0,1.0); 00675 break; 00676 case 2: 00677 m_tex_model_ip[params.m_spreadlvl]->bind(0); 00678 m_tex_frame_ip[params.m_spreadlvl]->bind(1); 00679 m_tex_model->bind(2); 00680 m_tex_frame->bind(3); 00681 m_shadeCompare->bind(); 00682 m_shadeCompare->setUniform("analyze", true); 00683 m_shadeCompare->setUniform("compare", true); 00684 m_shadeCompare->setUniform("textured", true); 00685 modelEntry->model.drawTexturedFaces(); 00686 m_shadeCompare->setUniform("textured", false); 00687 modelEntry->model.drawUntexturedFaces(); 00688 m_shadeCompare->unbind(); 00689 break; 00690 case 3: 00691 break; 00692 default: 00693 m_showmodel = 0; 00694 break; 00695 } 00696 00697 // m_modellist[i]->model.drawCoordinates(); 00698 // m_modellist[i]->model.drawNormals(); 00699 modelEntry->pose.Deactivate(); 00700 } 00701 00702 void TextureTracker::drawTrackerModel(int id, const TomGine::tgPose &p, float linewidth) 00703 { 00704 m_cam_perspective.Activate(); 00705 ModelEntryList::iterator it = m_modellist.begin(); 00706 while(it != m_modellist.end()){ 00707 if(id==(*it)->id){ 00708 ModelEntry* modelEntry = (*it); 00709 p.Activate(); 00710 switch(m_showmodel){ 00711 case 0: 00712 modelEntry->model.restoreTexture(); 00713 modelEntry->model.drawPass(false); 00714 break; 00715 case 1: 00716 m_lighting.Deactivate(); 00717 //glColorMask(0,0,0,0); 00718 //modelEntry->model.drawFaces(); 00719 //glColorMask(1,1,1,1); 00720 if(linewidth<1.0f) 00721 linewidth = 1.0f; 00722 glLineWidth(linewidth); 00723 modelEntry->model.drawEdges(); 00724 glColor3f(1.0,1.0,1.0); 00725 break; 00726 case 2: 00727 case 3: 00728 break; 00729 default: 00730 m_showmodel = 0; 00731 break; 00732 } 00733 p.Deactivate(); 00734 } 00735 ++it; 00736 } 00737 } 00738 00739 void TextureTracker::evaluatePDF(int id, 00740 float x_min, float y_min, 00741 float x_max, float y_max, 00742 int res, 00743 const char* meshfile, const char* xfile) 00744 { 00745 ModelEntryList::iterator it = m_modellist.begin(); 00746 while(it != m_modellist.end()){ 00747 if(id==(*it)->id){ 00748 vector<float> pdf; 00749 pdf = getPDFxy((*it), x_min, y_min, x_max, y_max, res); 00750 savePDF(pdf, x_min, y_min, x_max, y_max, res, meshfile, xfile); 00751 return; 00752 } 00753 ++it; 00754 } 00755 } 00756 00757 // Plots pdf in x-y plane (with z and rotational DOF locked) 00758 vector<float> TextureTracker::getPDFxy(ModelEntry* modelEntry, 00759 float x_min, float y_min, 00760 float x_max, float y_max, 00761 int res) 00762 { 00763 int i = 0; 00764 ROS_DEBUG("Evaluating PDF constrained to x,y movement only"); 00765 float x_step = (x_max-x_min) / res; 00766 float y_step = (y_max-y_min) / res; 00767 float scale = 0.1f; 00768 00769 x_min = (modelEntry->pose.t.x += x_min); 00770 y_min = (modelEntry->pose.t.y += y_min); 00771 00772 vector<float> vPDF; 00773 vPDF.assign(res*res, 0.0); 00774 00775 TomGine::tgFrustum* frustum = m_cam_perspective.GetFrustum(); 00776 00777 00778 float p; 00779 i=0; 00780 modelEntry->pose.t.y = y_min; 00781 for(int n=0; n<res; n++){ 00782 modelEntry->pose.t.x = x_min; 00783 for(int m=0; m<res; m++){ 00784 if(frustum->PointInFrustum(modelEntry->pose.t.x, modelEntry->pose.t.y, modelEntry->pose.t.z)){ 00785 p = evaluateParticle(modelEntry, m_shadeTexEdgeTest) * scale; 00786 // ROS_DEBUG("%f %f %f %f\n", modelEntry->pose.t.x, modelEntry->pose.t.y, modelEntry->pose.t.z, p); 00787 }else{ 00788 p = 0.0; 00789 } 00790 vPDF[i] = p; 00791 00792 i++; 00793 modelEntry->pose.t.x += x_step; 00794 } 00795 modelEntry->pose.t.y += y_step; 00796 } 00797 00798 // glBlendFunc( GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); 00799 // glEnable(GL_BLEND); 00800 // glBegin(GL_QUADS); 00801 // glColor4f(1.0,0.0,0.0,0.5); 00802 // glVertex3f(x_min, y_min, 0.0); 00803 // glVertex3f(x_min+x_step*res, y_min, 0.0); 00804 // glVertex3f(x_min+x_step*res, y_min+y_step*res, 0.0); 00805 // glVertex3f(x_min, y_min+y_step*res, 0.0); 00806 // glEnd(); 00807 // glDisable(GL_BLEND); 00808 // 00809 // swap(); 00810 // usleep(3000000); 00811 00812 return vPDF; 00813 } 00814 00815 // draws a rectangular terrain using a heightmap 00816 void TextureTracker::savePDF(vector<float> vPDFMap, 00817 float x_min, float y_min, 00818 float x_max, float y_max, 00819 unsigned res, 00820 const char* meshfile, const char* xfile) 00821 { 00822 unsigned i,d,x,y; 00823 00824 float x_step = (x_max-x_min) / res; 00825 float y_step = (y_max-y_min) / res; 00826 00827 vector<vec3> vertexlist; 00828 vector<vec3> normallist; 00829 vector<vec2> texcoordlist; 00830 vector<unsigned int> indexlist; 00831 00832 for(y=0; y<res; y++){ 00833 for(x=0; x<res; x++){ 00834 vec3 v[5], n; 00835 vec2 tc; 00836 d=0; 00837 00838 v[0].x = x_min + float(x)*x_step; 00839 v[0].y = y_min + float(y)*y_step; 00840 v[0].z = vPDFMap[y*res+x]; 00841 00842 if(x<res-1){ 00843 v[1].x = x_min + float(x+1)*x_step; 00844 v[1].y = y_min + float(y)*y_step; 00845 v[1].z = vPDFMap[y*res+(x+1)]; 00846 n += (v[1]-v[0]); 00847 d++; 00848 } 00849 00850 if(y<res-1){ 00851 v[2].x = x_min + float(x)*x_step; 00852 v[2].y = y_min + float(y+1)*y_step; 00853 v[2].z = vPDFMap[(y+1)*res+x]; 00854 n += (v[2]-v[0]); 00855 d++; 00856 } 00857 00858 if(x>0){ 00859 v[3].x = x_min + float(x-1)*x_step; 00860 v[3].y = y_min + float(y)*y_step; 00861 v[3].z = vPDFMap[y*res+(x-1)]; 00862 n += (v[3]-v[0]); 00863 d++; 00864 } 00865 00866 if(y>0){ 00867 v[4].x = x_min + float(x)*x_step; 00868 v[4].y = y_min + float(y-1)*y_step; 00869 v[4].z = vPDFMap[(y-1)*res+x]; 00870 n += (v[4]-v[0]); 00871 d++; 00872 } 00873 00874 n = n * (1.0f/float(d)); 00875 00876 tc.x = float(x)/res; 00877 tc.y = float(y)/res; 00878 00879 vertexlist.push_back(v[0]); 00880 normallist.push_back(n); 00881 texcoordlist.push_back(tc); 00882 00883 if(x<res-1 && y<res-1){ 00884 indexlist.push_back(y*res+x); 00885 indexlist.push_back(y*res+(x+1)); 00886 indexlist.push_back((y+1)*res+(x+1)); 00887 00888 indexlist.push_back(y*res+x); 00889 indexlist.push_back((y+1)*res+(x+1)); 00890 indexlist.push_back((y+1)*res+x); 00891 } 00892 } 00893 } 00894 /* 00895 glClear(GL_DEPTH_BUFFER_BIT); 00896 m_lighting.Activate(); 00897 00898 glEnableClientState(GL_VERTEX_ARRAY); glVertexPointer(3, GL_FLOAT, 0, &vertexlist[0]); 00899 glEnableClientState(GL_NORMAL_ARRAY); glNormalPointer(GL_FLOAT, 0, &normallist[0]); 00900 glEnableClientState(GL_TEXTURE_COORD_ARRAY); glTexCoordPointer(2, GL_FLOAT, 0, &texcoordlist[0]); 00901 00902 glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); 00903 glDrawElements(GL_TRIANGLES, 6 * (xres-1) * (yres-1), GL_UNSIGNED_INT, &indexlist[0]); 00904 glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); 00905 00906 glDisableClientState(GL_VERTEX_ARRAY); 00907 glDisableClientState(GL_NORMAL_ARRAY); 00908 glDisableClientState(GL_TEXTURE_COORD_ARRAY); 00909 00910 m_lighting.Deactivate(); 00911 */ 00912 if(meshfile){ 00913 FILE* fd = fopen(meshfile,"w"); 00914 fprintf(fd, "ply\nformat ascii 1.0\n"); 00915 fprintf(fd, "element vertex %d\n", res*res); 00916 fprintf(fd, "property float x\n"); 00917 fprintf(fd, "property float y\n"); 00918 fprintf(fd, "property float z\n"); 00919 fprintf(fd, "property float nx\n"); 00920 fprintf(fd, "property float ny\n"); 00921 fprintf(fd, "element face %d\n", (res-1)*(res-1)*2); 00922 fprintf(fd, "property list uchar uint vertex_indices\n"); 00923 fprintf(fd, "end_header\n"); 00924 00925 for(i=0; i<vertexlist.size(); i++){ 00926 vec3 v = vertexlist[i]; 00927 vec3 n = normallist[i]; 00928 fprintf(fd, "%f %f %f %f %f\n", v.x, v.y, v.z, n.x, n.y); 00929 } 00930 00931 for(i=0; i<indexlist.size(); i+=3){ 00932 fprintf(fd, "3 %d %d %d\n", indexlist[i], indexlist[i+1], indexlist[i+2]); 00933 } 00934 00935 ROS_DEBUG(" output written to '%s'", meshfile); 00936 00937 fclose(fd); 00938 } 00939 00940 if(xfile){ 00941 FILE* fd2 = fopen(xfile,"w"); 00942 y = res>>1; 00943 for(x=0; x<res; x++){ 00944 fprintf(fd2, "%f\n", vPDFMap[y*res+x]); 00945 } 00946 ROS_DEBUG(" output written to '%s'", xfile); 00947 fclose(fd2); 00948 } 00949 } 00950 00951 // get m_tex_model 00952 cv::Mat TextureTracker::getModelTexture() 00953 { 00954 return m_tex_model->toCvMat(); 00955 }