Go to the documentation of this file.00001 #pragma once
00002
00022 #ifndef __PTAMWRAPPER_H
00023 #define __PTAMWRAPPER_H
00024
00025 #include "GLWindow2.h"
00026 #include "TooN/se3.h"
00027 #include <deque>
00028 #include "sensor_msgs/Image.h"
00029 #include "ardrone_autonomy/Navdata.h"
00030 #include "cvd/thread.h"
00031 #include "cvd/image.h"
00032 #include "cvd/byte.h"
00033 #include "MouseKeyHandler.h"
00034 #include "boost/thread.hpp"
00035
00036 class Map;
00037 class MapMaker;
00038 class Tracker;
00039 class ATANCamera;
00040 class Predictor;
00041 class DroneKalmanFilter;
00042 class DroneFlightModule;
00043 class EstimationNode;
00044
00045
00046 typedef TooN::Vector<3> tvec3;
00047 typedef TooN::SE3<> tse3;
00048
00049
00050
00051
00052
00053
00054 class PTAMWrapper : private CVD::Thread, private MouseKeyHandler
00055 {
00056 private:
00057
00058 GLWindow2* myGLWindow;
00059 CVD::ImageRef desiredWindowSize;
00060 CVD::ImageRef defaultWindowSize;
00061 bool changeSizeNextRender;
00062
00063
00064
00065
00066 void run();
00067
00068 void HandleFrame();
00069
00070
00071 DroneKalmanFilter* filter;
00072 EstimationNode* node;
00073
00074
00075 char charBuf[1000];
00076 std::string msg;
00077
00078 CVD::Image<CVD::byte> mimFrameBW;
00079 CVD::Image<CVD::byte> mimFrameBW_workingCopy;
00080 int mimFrameTime;
00081 int mimFrameTime_workingCopy;
00082 unsigned int mimFrameSEQ;
00083 unsigned int mimFrameSEQ_workingCopy;
00084 ros::Time mimFrameTimeRos;
00085 ros::Time mimFrameTimeRos_workingCopy;
00086 int frameWidth, frameHeight;
00087
00088
00089
00090
00091 Map *mpMap;
00092 MapMaker *mpMapMaker;
00093 Tracker *mpTracker;
00094 ATANCamera *mpCamera;
00095 Predictor* predConvert;
00096 Predictor* predIMUOnlyForScale;
00097
00098 double minKFTimeDist;
00099 double minKFWiggleDist;
00100 double minKFDist;
00101
00102 double min_tol;
00103 double max_tol;
00104
00105
00106 Predictor* imuOnlyPred;
00107 int lastScaleEKFtimestamp;
00108
00109 bool resetPTAMRequested;
00110 enum {UI_NONE = 0, UI_DEBUG = 1, UI_PRES = 2} drawUI;
00111
00112
00113 bool forceKF;
00114
00115 bool flushMapKeypoints;
00116
00117 int lastAnimSentClock;
00118 enum {ANIM_NONE, ANIM_TOOKKF, ANIM_GOOD, ANIM_INIT, ANIM_LOST, ANIM_FALSEPOS} lastAnimSent;
00119
00120
00121 int lastGoodYawClock;
00122 int isGoodCount;
00123
00124 TooN::Vector<3> PTAMPositionForScale;
00125 int ptamPositionForScaleTakenTimestamp;
00126 int framesIncludedForScaleXYZ;
00127 std::deque<ardrone_autonomy::Navdata> navInfoQueue;
00128 bool navQueueOverflown;
00129 TooN::Vector<3> evalNavQue(unsigned int from, unsigned int to, bool* zCorrupted, bool* allCorrupted, float* out_start_pressure, float* out_end_pressure);
00130
00131
00132
00133 bool keepRunning;
00134
00135 bool lockNextFrame;
00136
00137 boost::condition_variable new_frame_signal;
00138 boost::mutex new_frame_signal_mutex;
00139
00140
00141
00142 void ResetInternal();
00143
00144 void renderGrid(TooN::SE3<> camFromWorld);
00145
00146 int videoFramePing;
00147
00148 std::ofstream* logfileScalePairs;
00149 static pthread_mutex_t logScalePairs_CS;
00150
00151 public:
00152
00153 PTAMWrapper(DroneKalmanFilter* dkf, EstimationNode* nde);
00154 ~PTAMWrapper(void);
00155
00156
00157
00158 void newImage(sensor_msgs::ImageConstPtr img);
00159 void newNavdata(ardrone_autonomy::Navdata* nav);
00160 bool newImageAvailable;
00161 void setPTAMPars(double minKFTimeDist, double minKFWiggleDist, double minKFDist,
00162 double min_tol, double max_tol);
00163
00164 bool handleCommand(std::string s);
00165 bool mapLocked;
00166 int maxKF;
00167 static pthread_mutex_t navInfoQueueCS;
00168 static pthread_mutex_t shallowMapCS;
00169
00170
00171
00172 virtual void on_key_down(int key);
00173
00174 virtual void on_mouse_down(CVD::ImageRef where, int state, int button);
00175
00176
00177
00178 inline void Reset() {resetPTAMRequested = true;};
00179
00180
00181 void startSystem();
00182 void stopSystem();
00183
00184 enum {PTAM_IDLE = 0, PTAM_INITIALIZING = 1, PTAM_LOST = 2, PTAM_GOOD = 3, PTAM_BEST = 4, PTAM_TOOKKF = 5, PTAM_FALSEPOSITIVE = 6} PTAMStatus;
00185 TooN::SE3<> lastPTAMResultRaw;
00186 std::string lastPTAMMessage;
00187
00188
00189 std::vector<tvec3> mapPointsTransformed;
00190 std::vector<tse3> keyFramesTransformed;
00191
00192 ardrone_autonomy::Navdata lastNavinfoReceived;
00193
00194 int PTAMInitializedClock;
00195
00196 };
00197
00198 #endif