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
00010 #include <boost/msm/back/state_machine.hpp>
00011
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 "visp_tracker/MovingEdgeSites.h"
00029 #include "visp_tracker/KltPoints.h"
00030
00031 #include "cmd_line/cmd_line.h"
00032 #include "detectors/detector_base.h"
00033 #include <visp/vpMbEdgeTracker.h>
00034 #include "states.hpp"
00035 #include "events.h"
00036
00037 using namespace boost::accumulators;
00038 namespace msm = boost::msm;
00039 namespace mpl = boost::mpl;
00040 namespace tracking{
00041
00042 class Tracker_ : public msm::front::state_machine_def<Tracker_>{
00043 public:
00044 typedef struct {
00045 boost::accumulators::accumulator_set<
00046 double,
00047 boost::accumulators::stats<
00048 boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile),
00049 boost::accumulators::tag::max,
00050 boost::accumulators::tag::mean
00051 >
00052 > var,var_x,var_y,var_z,var_wx,var_wy,var_wz,checkpoints;
00053
00054 } statistics_t;
00055 private:
00056 CmdLine cmd;
00057 int iter_;
00058 vpImagePoint flashcode_center_;
00059 std::ofstream varfile_;
00060 detectors::DetectorBase* detector_;
00061 typedef boost::array<vpHinkley,6> hinkley_array_t;
00062 hinkley_array_t hink_;
00063
00064 vpMbTracker* tracker_;
00065 vpMe tracker_me_config_;
00066 vpImage<vpRGBa> *I_;
00067 vpImage<vpRGBa> *_I;
00068 vpHomogeneousMatrix cMo_;
00069 vpCameraParameters cam_;
00070 vpImage<unsigned char> Igray_;
00071
00072 std::vector<vpPoint> outer_points_3D_bcp_;
00073 std::vector<vpPoint> points3D_inner_;
00074 std::vector<vpPoint> points3D_outer_;
00075 std::vector<vpPoint> points3D_middle_;
00076 std::vector<vpPoint> f_;
00077 vpRect vpTrackingBox_;
00078 cv::Rect cvTrackingBox_;
00079 bool cvTrackingBox_init_;
00080
00081 statistics_t statistics;
00082 bool flush_display_;
00083
00084 public:
00085
00086 void set_flush_display(bool val);
00087 bool get_flush_display();
00088 detectors::DetectorBase& get_detector();
00089 vpMbTracker& get_mbt();
00090 std::vector<vpPoint>& get_points3D_inner();
00091 std::vector<vpPoint>& get_points3D_outer();
00092 std::vector<vpPoint>& get_points3D_middle();
00093 std::vector<vpPoint>& get_flashcode();
00094
00095
00096 template<class T>
00097 const T& get_tracking_box();
00098
00099 vpImage<vpRGBa>& get_I();
00100
00101 vpCameraParameters& get_cam();
00102
00103 CmdLine& get_cmd();
00104
00105
00106
00107 Tracker_(CmdLine& cmd, detectors::DetectorBase* detector,vpMbTracker* tracker_,bool flush_display = true);
00108
00109 typedef WaitingForInput initial_state;
00110
00111
00112 bool input_selected(input_ready const& evt);
00113 bool no_input_selected(input_ready const& evt);
00114 bool flashcode_detected(input_ready const& evt);
00115 bool flashcode_redetected(input_ready const& evt);
00116 bool model_detected(msm::front::none const&);
00117 bool mbt_success(input_ready const& evt);
00118
00119
00120 void find_flashcode_pos(input_ready const& evt);
00121 void track_model(input_ready const& evt);
00122
00123
00124 statistics_t& get_statistics();
00125
00126 void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites);
00127 void updateKltPoints(visp_tracker::KltPointsPtr klt);
00128
00129
00130 struct transition_table : mpl::vector<
00131
00132
00133 g_row< WaitingForInput , input_ready , WaitingForInput , &Tracker_::no_input_selected >,
00134
00135 g_row< WaitingForInput , input_ready , DetectFlashcode , &Tracker_::input_selected >,
00136
00137 _row< WaitingForInput , select_input , DetectFlashcode >,
00138
00139 _row< DetectFlashcode , input_ready , DetectFlashcode >,
00140
00141 row< DetectFlashcode , input_ready , DetectModel , &Tracker_::find_flashcode_pos,&Tracker_::flashcode_detected >,
00142
00143 _row< DetectModel , msm::front::none , DetectFlashcode >,
00144
00145 g_row< DetectModel , msm::front::none , TrackModel , &Tracker_::model_detected >,
00146
00147 _row< TrackModel , input_ready , ReDetectFlashcode >,
00148
00149 row< TrackModel , input_ready , TrackModel , &Tracker_::track_model ,&Tracker_::mbt_success >,
00150
00151 _row< ReDetectFlashcode, input_ready , DetectFlashcode >,
00152
00153 row< ReDetectFlashcode, input_ready , DetectModel , &Tracker_::find_flashcode_pos,&Tracker_::flashcode_redetected >,
00154
00155
00156
00157 _row< TrackModel , finished , Finished >,
00158
00159 _row< DetectModel , finished , Finished >,
00160
00161 _row< DetectFlashcode , finished , Finished >,
00162
00163 _row< ReDetectFlashcode, finished , Finished >
00164
00165 > {};
00166
00167 };
00168
00169 typedef msm::back::state_machine<Tracker_> Tracker;
00170
00171
00172 }
00173 #endif //__TRACKING_H__