Go to the documentation of this file.00001 
00009 #ifndef _MODEL_ENTRY_H_
00010 #define _MODEL_ENTRY_H_
00011 
00012 #include <blort/TomGine/tgMathlib.h>
00013 #include <blort/Tracker/TrackingStates.h>
00014 #include <blort/Tracker/TrackerModel.h>
00015 #include <blort/Tracker/Distribution.h>
00016 #include <blort/Tracker/Predictor.h>
00017 #include <blort/Tracker/Filter.h>
00018 
00019 namespace Tracking{
00020 
00022 class ModelEntry
00023 {
00024 private:
00025         void poseDiff(float &t, float &a);
00026         void speed();
00027 
00028         float max(float a, float b){ return (((a) > (b)) ? (a) : (b)); }
00029         float abs(float a){ return ((a>=0.0f) ? a : (-a)); }
00030         
00031         
00032         
00033 public:
00034         ModelEntry();
00035         ModelEntry(const TomGine::tgModel& m);
00036         ~ModelEntry();
00037         
00038         void setInitialPose(const TomGine::tgPose &p, float lpf_delay=0.0f, float lpf_delay_z=0.0f);
00039         void filter_pose();
00040         void evaluate_states(   const Particle &variation, unsigned rec,
00041                                                         float c_th_base=0.6f, float c_th_min=0.3f, float c_th_fair=0.5f,
00042                                                         float c_mv_not=0.01f, float c_mv_slow=0.05f, float c_th_lost=0.1f);
00043         
00044         std::string label;
00045         
00046         float t, a, t_max, a_max, c_edge, c_th, c_lost, abs_a, abs_t;
00047         
00048         movement_state st_movement;                             
00049         confidence_state st_confidence;                 
00050         quality_state st_quality;                               
00051         
00052         TrackerModel            model;                          
00053         Distribution            distribution;           
00054         Predictor*                      predictor;                      
00055         Texture*                        mask;                           
00056         Particle                        pose;                           
00057         Particle                        pose_prev;                      
00058         Particle                        lpf_pose;               
00059         Particle                        initial_pose;           
00060         
00061         float   speed_angular;                                  
00062         float   speed_translational;                    
00063 
00064         float   confidence_color;                               
00065         float   confidence_edge;                                
00066         
00067         int     id;                                                     
00068         unsigned        num_convergence;                        
00069         unsigned        hypothesis_id;                          
00070         std::vector<float> past_confidences;    
00071         unsigned        num_particles;                          
00072         unsigned        num_recursions;                         
00073         
00074         bool            bfc;                                            
00075         bool            lock;                                           
00076         bool            mask_geometry_edges;            
00077         
00078         mat4 modelviewprojection;                               
00079         TomGine::tgVector3 vCam2Model;                  
00080         
00081 private:
00082         Predictor* del_predictor;
00083         SmoothFilter m_lpf_pose_tx;
00084         SmoothFilter m_lpf_pose_ty;
00085         SmoothFilter m_lpf_pose_tz;
00086         SmoothFilter m_lpf_pose_qx;
00087         SmoothFilter m_lpf_pose_qy;
00088         SmoothFilter m_lpf_pose_qz;
00089         SmoothFilter m_lpf_pose_qw;
00090 
00091 public:
00092         SmoothFilter m_lpf_a;
00093         SmoothFilter m_lpf_t;
00094         SmoothFilter m_lpf_cs;
00095         SmoothFilter m_lpf_cl;
00096 
00097 };
00098 
00099 } 
00100 
00101 #endif