MapView.h
Go to the documentation of this file.
00001 #pragma once
00002 
00021 #ifndef __MAPVIEW_H
00022 #define __MAPVIEW_H
00023  
00024  
00025  
00026 
00027 #include "GLWindow2.h"
00028 #include <deque>
00029 #include "cvd/thread.h"
00030 #include "TooN/se3.h"
00031 #include "MouseKeyHandler.h"
00032 
00033 
00034 class DroneKalmanFilter;
00035 class PTAMWrapper;
00036 class Predictor;
00037 class EstimationNode;
00038 
00039 class TrailPoint
00040 {
00041 public:
00042         inline TrailPoint(TooN::Vector<3> filter)
00043         {
00044                 pointFilter = filter;
00045                 PTAMValid = false;
00046         }
00047         inline TrailPoint(TooN::Vector<3> filter, TooN::Vector<3> ptam)
00048         {
00049                 pointFilter = filter;
00050                 pointPTAM = ptam;
00051                 PTAMValid = true;
00052         }
00053         TooN::Vector<3> pointPTAM;
00054         TooN::Vector<3> pointFilter;
00055         bool PTAMValid;
00056 };
00057 
00058 class MapView : private CVD::Thread, private MouseKeyHandler
00059 {
00060 private:
00061         // base window
00062         GLWindow2* myGLWindow;
00063         CVD::ImageRef desiredWindowSize;                // size the window scould get changed to if [changeSizeNextRender]
00064         CVD::ImageRef defaultWindowSize;                // size the window gets opened with
00065         bool changeSizeNextRender;
00066 
00067 
00068         // the associated thread's run function.
00069         // calls control() every time a new PTAM info is available or every 20ms.
00070         void run();
00071 
00072         // main routine; uses all available information, 
00073         // in order to calculate and send a new control command to the drone
00074         void control();
00075 
00076         // renders map view
00077         void Render();
00078 
00079         DroneKalmanFilter* filter;
00080         PTAMWrapper* ptamWrapper;
00081         EstimationNode* node;
00082 
00083         bool resetRequested;
00084 
00085         // keep Running
00086         bool keepRunning;
00087 
00088         Predictor* predConvert;
00089 
00090 
00091         // ---------- rendering stuff ---------------------------
00092         char charBuf[1000];
00093         std::string msg;
00094         enum {UI_NONE = 0, UI_DEBUG = 1, UI_PRES = 2} drawUI;
00095         float lineWidthFactor;
00096 
00097         // plot stuff
00098         void plotMapPoints();
00099         void plotGrid();
00100         void plotKeyframes();
00101         void SetupFrustum();
00102         void SetupModelView(TooN::SE3<> se3WorldFromCurrent = TooN::SE3<>());
00103 
00104         // viewing options
00105         TooN::SE3<> mse3ViewerFromWorld;
00106         TooN::Vector<3> mv3MassCenter;
00107         bool resetMapViewFlag;
00108 
00109         void plotCam(TooN::SE3<> droneToGlobal, bool xyCross, float thick, float len, float alpha);
00110         void drawTrail();
00111 
00112         // resets tracking. private as it needs to be called from internal thread.
00113         void ResetInternal();
00114 
00115         // values for rendering.
00116         TooN::Vector<10> lastFramePoseSpeed;
00117         bool inControl;
00118         bool clearTrail;
00119 
00120 
00121         // trail for rendering
00122         std::vector<TrailPoint> trailPoints;
00123 
00124 public:
00125 
00126         MapView(DroneKalmanFilter* f, PTAMWrapper* p, EstimationNode* nde);
00127         ~MapView(void);
00128 
00129         bool handleCommand(std::string s);
00130 
00131         inline void Reset() {resetRequested = true;};
00132 
00133         // Event handling routines.
00134         // get called by the myGLWindow on respective event.
00135         void on_key_down(int key);
00136         //virtual void on_mouse_move(CVD::ImageRef where, int state);
00137         //virtual void on_mouse_down(CVD::ImageRef where, int state, int button);
00138         //virtual void on_event(int event);
00139 
00140 
00141         static pthread_mutex_t trailPointsVec_CS; //pthread_mutex_lock( &cs_mutex );
00142 
00143         // start and stop system and respective thread.
00144         void startSystem();
00145         void stopSystem();
00146 
00147         void resetMapView();
00148 };
00149 #endif /* __MAPVIEW_H */
00150 


tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:27:23