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


uga_tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:30:11