tum_ardrone_gui.h
Go to the documentation of this file.
00001 #pragma once
00002 
00021 #ifndef __TUMARDRONEGUI_H
00022 #define __TUMARDRONEGUI_H
00023  
00024  
00025  
00026  
00027 #include <QtGui/QWidget>
00028 #include "ui_tum_ardrone_gui.h"
00029 #include "geometry_msgs/Twist.h"
00030 
00031 class RosThread;
00032 class PingThread;
00033 struct ControlCommand;
00034 
00035 enum ControlSource {CONTROL_KB = 0, CONTROL_JOY = 1, CONTROL_AUTO = 2, CONTROL_NONE = 3};
00036 
00037 class tum_ardrone_gui : public QWidget
00038 {
00039     Q_OBJECT
00040 
00041 public slots:
00042         void LandClicked();
00043         void TakeoffClicked();
00044         void ToggleCamClicked();
00045         void EmergencyClicked();
00046 
00047         void ClearClicked();
00048         void SendClicked();
00049         void ClearSendClicked();
00050         void ResetClicked();
00051         void FlattrimClicked();
00052 
00053         void LoadFileChanged(QString val);
00054         void ToggledUseHovering(int val);
00055         void ToggledPingDrone(int val);
00056 
00057         void ControlSourceChanged();
00058 
00059 private slots:
00060     void setCountsSlot(unsigned int nav,unsigned int control,unsigned int pose,unsigned int joy);
00061     void setPingsSlot(int p500, int p20000);
00062     void setControlSourceSlot(int cont);
00063 
00064     void addLogLineSlot(QString);
00065     void setAutopilotInfoSlot(QString);
00066     void setStateestimationInfoSlot(QString);
00067     void setMotorSpeedsSlot(QString);
00068 
00069     void closeWindowSlot();
00070 
00071 
00072 signals:
00073         void setCountsSignal(unsigned int nav,unsigned int control,unsigned int pose,unsigned int joy);
00074     void setPingsSignal(int p500, int p20000);
00075         void setControlSourceSignal(int cont);
00076 
00077         void addLogLineSignal(QString);
00078         void setAutopilotInfoSignal(QString);
00079         void setStateestimationInfoSignal(QString);
00080     void setMotorSpeedsSignal(QString);
00081 
00082         void closeWindowSignal();
00083 
00084 
00085 public:
00086     tum_ardrone_gui(QWidget *parent = 0);
00087     ~tum_ardrone_gui();
00088     RosThread* rosThread;
00089     PingThread* pingThread;
00090 
00091     void setCounts(unsigned int nav,unsigned int control,unsigned int pose,unsigned int joy);
00092     void setPings(int p500, int p20000);
00093     void setControlSource(ControlSource cont);
00094     void addLogLine(std::string s);
00095     void setAutopilotInfo(std::string s);
00096     void setStateestimationInfo(std::string s);
00097     void setMotorSpeeds(std::string s);
00098     void closeWindow();
00099 
00100     // calculates KB command, based on currently pressed keys.
00101     ControlCommand calcKBControl();
00102     ControlSource currentControlSource;
00103     double sensGaz, sensYaw, sensRP;
00104     bool useHovering;
00105 
00106 protected:
00107 
00108     // keyboard control.... this is the only way i managed to do this...
00109     void keyPressEvent( QKeyEvent * key);
00110     void keyReleaseEvent( QKeyEvent * key);
00111     int mapKey(int k);
00112     bool isPressed[8];  //{j k l i u o q a}
00113     unsigned int lastRepeat[8];
00114 
00115 
00116 private:
00117     Ui::tum_ardrone_guiClass ui;
00118 };
00119 
00120 #endif /* __TUMARDRONEGUI_H */
00121 


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