ModelEntry.cpp
Go to the documentation of this file.
00001 #include <blort/Tracker/ModelEntry.h>
00002 #include <ros/console.h>
00003 
00004 using namespace Tracking;
00005 
00007 ModelEntry::ModelEntry()
00008 : m_lpf_a(0.7f), m_lpf_t(0.7f), m_lpf_cs(0.2f), m_lpf_cl(0.99f)
00009 {  
00010         del_predictor = predictor = new Predictor();
00011         bfc = false;
00012         lock = false;
00013         mask_geometry_edges = false;
00014         num_convergence = 0;
00015   st_quality = ST_OK; //2012-11-28: added by Jordi
00016         mask = 0;
00017   ROS_WARN_STREAM("(" << label << ") ModelEntry(): st_quality = " << st_quality );
00018 }
00019 
00020 ModelEntry::ModelEntry(const TomGine::tgModel& m)
00021 : model(m), m_lpf_a(0.7f), m_lpf_t(0.7f), m_lpf_cs(0.2f), m_lpf_cl(0.99f)
00022 {
00023         del_predictor = predictor = new Predictor();
00024         bfc = false;
00025         lock = false;
00026         mask_geometry_edges = false;
00027         num_convergence = 0;
00028         mask = 0;
00029 }
00030         
00031 ModelEntry::~ModelEntry()
00032 {
00033         delete(del_predictor);
00034 }
00035 
00036 void ModelEntry::poseDiff(float &t, float &a)
00037 {
00038         vec3 axis0, axis1;
00039         float angle0, angle1;
00040         
00041         pose.q.getAxisAngle(axis0, angle0);
00042         pose_prev.q.getAxisAngle(axis1, angle1);
00043         
00044         //vec3 axis01 = axis0 - axis1;
00045         vec3 t01 = pose.t - pose_prev.t;
00046         
00047         a = (angle0-angle1);
00048         t = t01.length();
00049 }
00050 
00051 void ModelEntry::speed()
00052 {
00053         static Timer s_timer;
00054         float dt = (float)s_timer.Update();
00055         
00056         float t,a;
00057         poseDiff(t,a);
00058         
00059         speed_angular = a/dt;
00060         speed_translational = t/dt;
00061 }
00062 
00063 void ModelEntry::filter_pose()
00064 {
00065         lpf_pose.t.x = m_lpf_pose_tx.Process(pose.t.x);
00066         lpf_pose.t.y = m_lpf_pose_ty.Process(pose.t.y);
00067         lpf_pose.t.z = m_lpf_pose_tz.Process(pose.t.z);
00068         lpf_pose.q.x = m_lpf_pose_qx.Process(pose.q.x);
00069         lpf_pose.q.y = m_lpf_pose_qy.Process(pose.q.y);
00070         lpf_pose.q.z = m_lpf_pose_qz.Process(pose.q.z);
00071         lpf_pose.q.w = m_lpf_pose_qw.Process(pose.q.w);
00072 }
00073 
00074 void ModelEntry::setInitialPose(const TomGine::tgPose &p, float lpf_delay, float lpf_delay_z)
00075 {
00076         initial_pose = p;
00077         initial_pose.c = pose.c;
00078         initial_pose.w = pose.w;
00079         m_lpf_pose_tx.Set(p.t.x, lpf_delay);
00080         m_lpf_pose_ty.Set(p.t.y, lpf_delay);
00081         m_lpf_pose_tz.Set(p.t.z, lpf_delay_z);
00082         m_lpf_pose_qx.Set(p.q.x, lpf_delay);
00083         m_lpf_pose_qy.Set(p.q.y, lpf_delay);
00084         m_lpf_pose_qz.Set(p.q.z, lpf_delay);
00085         m_lpf_pose_qw.Set(p.q.w, lpf_delay);
00086 }
00087 
00088 void ModelEntry::evaluate_states(const Particle &variation, unsigned rec,
00089                                  float c_th_base, float c_th_min, float c_th_fair,
00090                                  float c_mv_not, float c_mv_slow, float c_th_lost)
00091 {
00092         
00093   if(lock)
00094   {    
00095                 st_quality = ST_LOCKED;
00096                 return;
00097         }
00098         
00099         speed();
00100         
00101         poseDiff(t,a);
00102         
00103         t_max = max(variation.t.x, max(variation.t.y, variation.t.z));
00104         a_max = max(variation.r.x, max(variation.r.y, variation.r.z));
00105         
00106         t = t/(t_max * rec);
00107         a = a/(a_max * rec);
00108 
00109         t = m_lpf_t.Process(t);
00110         a = m_lpf_a.Process(a);
00111         
00112   c_edge = m_lpf_cs.Process(this->confidence_edge);  
00113 
00114         abs_a = abs(a);
00115         abs_t = abs(t);
00116         
00117         c_th = c_th_base -  max(abs_a, abs_t);
00118         if(c_th < c_th_min) c_th = c_th_min;
00119         
00120         if(c_edge < c_th)
00121                 c_lost = m_lpf_cl.Process(c_th - c_edge);
00122         else
00123                 c_lost = m_lpf_cl.Process(0.0f);  
00124 
00125         // Movement detection
00126         if( abs_a<c_mv_not && abs_t < c_mv_not )
00127                 st_movement = ST_STILL;
00128         else if( abs_a<c_mv_slow && abs_t < c_mv_slow )
00129                 st_movement = ST_SLOW;
00130         else
00131                 st_movement = ST_FAST;
00132 
00133   ROS_INFO_STREAM("(" << label << ") ModeEntry: evaluate_states: c_edge = " << c_edge << "  c_th = " << c_th << " c_lost = " << c_lost << "  c_th_lost = " << c_th_lost);
00134   ROS_INFO_STREAM("                            st_movement = " << st_movement << "  st_quality = " << st_quality);
00135         
00137   if( c_lost > c_th_lost )
00138   {
00139                 if( st_movement != ST_STILL && st_quality != ST_OCCLUDED)
00140     {
00141                         st_quality = ST_LOST;
00142     }
00143     else if( st_quality != ST_LOST)
00144     {
00145       st_quality = ST_OCCLUDED;
00146     }
00147   }
00148   else if( st_quality != ST_LOST && st_quality != ST_OCCLUDED )
00149   {
00150                 st_quality = ST_OK;
00151         }
00152 
00153         if( st_quality == ST_OCCLUDED && st_movement == ST_FAST )
00154   {
00155                 st_quality = ST_LOST;
00156   }   
00157         
00158         // Quality detection
00159         if( c_edge > c_th_base )
00160                 st_confidence = ST_GOOD;
00161         else if( c_edge > c_th_fair )
00162                 st_confidence = ST_FAIR;
00163         else
00164                 st_confidence = ST_BAD;
00165                 
00166   if( st_movement == ST_STILL && c_edge >= c_th_base )
00167   {
00168                 st_quality = ST_OK;
00169         }
00170 
00171   ROS_INFO_STREAM("(" << label << ") ModelEntry::evaluate_states has set st_confidence = " << st_confidence << "  st_quality = " << st_quality);
00172         
00173 }


blort
Author(s): Thomas Mörwald , Michael Zillich , Andreas Richtsfeld , Johann Prankl , Markus Vincze , Bence Magyar
autogenerated on Wed Aug 26 2015 15:24:12