$search
00001 #ifndef __TRACKING_H__ 00002 #define __TRACKING_H__ 00003 #include <boost/accumulators/accumulators.hpp> 00004 #include <boost/accumulators/statistics.hpp> 00005 #include <boost/accumulators/statistics/median.hpp> 00006 #include <boost/accumulators/statistics/p_square_quantile.hpp> 00007 00008 #include <iostream> 00009 // back-end 00010 #include <boost/msm/back/state_machine.hpp> 00011 //front-end 00012 #include <boost/msm/front/state_machine_def.hpp> 00013 #include <boost/array.hpp> 00014 #include <visp/vpImage.h> 00015 00016 00017 #include <visp/vpImage.h> 00018 #include <visp/vpRGBa.h> 00019 #include <visp/vpHomogeneousMatrix.h> 00020 #include <visp/vpCameraParameters.h> 00021 00022 #include <visp/vpDisplay.h> 00023 #include <visp/vpHinkley.h> 00024 #include <visp/vpMe.h> 00025 #include <vector> 00026 #include <fstream> 00027 00028 #include "cmd_line/cmd_line.h" 00029 #include "detectors/detector_base.h" 00030 #include <visp/vpMbEdgeTracker.h> 00031 #include "states.hpp" 00032 #include "events.h" 00033 00034 using namespace boost::accumulators; 00035 namespace msm = boost::msm; 00036 namespace mpl = boost::mpl; 00037 namespace tracking{ 00038 00039 class Tracker_ : public msm::front::state_machine_def<Tracker_>{ 00040 public: 00041 typedef struct { 00042 boost::accumulators::accumulator_set< 00043 double, 00044 boost::accumulators::stats< 00045 boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), 00046 boost::accumulators::tag::max, 00047 boost::accumulators::tag::mean 00048 > 00049 > var,var_x,var_y,var_z,var_wx,var_wy,var_wz,checkpoints; 00050 00051 } statistics_t; 00052 private: 00053 CmdLine cmd; 00054 int iter_; 00055 vpImagePoint flashcode_center_; 00056 std::ofstream varfile_; 00057 detectors::DetectorBase* detector_; 00058 typedef boost::array<vpHinkley,6> hinkley_array_t; 00059 hinkley_array_t hink_; 00060 00061 vpMbTracker* tracker_; // Create a model based tracker. 00062 vpMe tracker_me_config_; 00063 vpImage<vpRGBa> *I_; 00064 vpImage<vpRGBa> *_I; 00065 vpHomogeneousMatrix cMo_; // Pose computed using the tracker. 00066 vpCameraParameters cam_; 00067 vpImage<unsigned char> Igray_; 00068 00069 std::vector<vpPoint> outer_points_3D_bcp_; 00070 std::vector<vpPoint> points3D_inner_; 00071 std::vector<vpPoint> points3D_outer_; 00072 std::vector<vpPoint> points3D_middle_; 00073 std::vector<vpPoint> f_; 00074 vpRect vpTrackingBox_; 00075 cv::Rect cvTrackingBox_; 00076 bool cvTrackingBox_init_; 00077 00078 statistics_t statistics; 00079 bool flush_display_; 00080 00081 public: 00082 //getters to access useful members 00083 void set_flush_display(bool val); 00084 bool get_flush_display(); 00085 detectors::DetectorBase& get_detector(); 00086 vpMbTracker& get_mbt(); 00087 std::vector<vpPoint>& get_points3D_inner(); 00088 std::vector<vpPoint>& get_points3D_outer(); 00089 std::vector<vpPoint>& get_points3D_middle(); 00090 std::vector<vpPoint>& get_flashcode(); 00091 00092 //returns tracking box where to look for pattern (may be full image) 00093 template<class T> 00094 const T& get_tracking_box(); 00095 //returns currently treated image 00096 vpImage<vpRGBa>& get_I(); 00097 //returns camera parameters 00098 vpCameraParameters& get_cam(); 00099 //returns tracker configuration 00100 CmdLine& get_cmd(); 00101 00102 //constructor 00103 //inits tracker from a detector, a visp tracker 00104 Tracker_(CmdLine& cmd, detectors::DetectorBase* detector,vpMbTracker* tracker_,bool flush_display = true); 00105 00106 typedef WaitingForInput initial_state; //initial state of our state machine tracker 00107 00108 //Guards 00109 bool input_selected(input_ready const& evt); 00110 bool no_input_selected(input_ready const& evt); 00111 bool flashcode_detected(input_ready const& evt); 00112 bool flashcode_redetected(input_ready const& evt); 00113 bool model_detected(msm::front::none const&); 00114 bool mbt_success(input_ready const& evt); 00115 00116 //actions 00117 void find_flashcode_pos(input_ready const& evt); 00118 void track_model(input_ready const& evt); 00119 00120 //gets statistics about the last tracking experience 00121 statistics_t& get_statistics(); 00122 00123 //here is how the tracker works 00124 struct transition_table : mpl::vector< 00125 // Start Event Target Action Guard 00126 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00127 g_row< WaitingForInput , input_ready , WaitingForInput , &Tracker_::no_input_selected >, 00128 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00129 g_row< WaitingForInput , input_ready , DetectFlashcode , &Tracker_::input_selected >, 00130 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00131 _row< WaitingForInput , select_input , DetectFlashcode >, 00132 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00133 _row< DetectFlashcode , input_ready , DetectFlashcode /* default behaviour */ >, 00134 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00135 row< DetectFlashcode , input_ready , DetectModel , &Tracker_::find_flashcode_pos,&Tracker_::flashcode_detected >, 00136 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00137 _row< DetectModel , msm::front::none , DetectFlashcode /* default behaviour */ >, 00138 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00139 g_row< DetectModel , msm::front::none , TrackModel , &Tracker_::model_detected >, 00140 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00141 _row< TrackModel , input_ready , ReDetectFlashcode /* default behaviour */ >, 00142 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00143 row< TrackModel , input_ready , TrackModel , &Tracker_::track_model ,&Tracker_::mbt_success >, 00144 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00145 _row< ReDetectFlashcode, input_ready , DetectFlashcode /* default behaviour */ >, 00146 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00147 row< ReDetectFlashcode, input_ready , DetectModel , &Tracker_::find_flashcode_pos,&Tracker_::flashcode_redetected >, 00148 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00149 //row< ReDetectFlashcode, input_ready , TrackModel , &Tracker_::track_model ,&Tracker_::mbt_success >, 00150 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00151 _row< TrackModel , finished , Finished >, 00152 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00153 _row< DetectModel , finished , Finished >, 00154 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00155 _row< DetectFlashcode , finished , Finished >, 00156 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00157 _row< ReDetectFlashcode, finished , Finished > 00158 // +------------------+--------------------+-----------------------+------------------------------+------------------------------+ 00159 > {}; 00160 00161 }; 00162 00163 typedef msm::back::state_machine<Tracker_> Tracker; 00164 00165 00166 } 00167 #endif //__TRACKING_H__