00001
00021 #include "tum_ardrone_gui.h"
00022 #include "RosThread.h"
00023 #include "PingThread.h"
00024 #include "time.h"
00025 #include "../HelperFunctions.h"
00026
00027 #include "ros/ros.h"
00028 #include "ros/package.h"
00029
00030 #include <sys/types.h>
00031 #include <dirent.h>
00032 #include <errno.h>
00033 #include <vector>
00034 #include <string>
00035 #include <iostream>
00036 #include <fstream>
00037
00038 int getdirtxt (std::string dir, std::vector<std::string> &files)
00039 {
00040 DIR *dp;
00041 struct dirent *dirp;
00042 if((dp = opendir(dir.c_str())) == NULL) {
00043 std::cout << "Error(" << errno << ") opening " << dir << std::endl;
00044 return errno;
00045 }
00046
00047 while ((dirp = readdir(dp)) != NULL) {
00048 std::string f = dirp->d_name;
00049 if(f.size() > 4 && f.substr(f.size()-4) == ".txt")
00050 files.push_back(std::string(dirp->d_name));
00051 }
00052 closedir(dp);
00053 return 0;
00054 }
00055
00056
00057 tum_ardrone_gui::tum_ardrone_gui(QWidget *parent)
00058 : QWidget(parent)
00059 {
00060 ui.setupUi(this);
00061 rosThread = NULL;
00062 sensGaz = sensYaw = sensRP = 1;
00063 currentControlSource = CONTROL_NONE;
00064 useHovering = true;
00065
00066 for(int i=0;i<8;i++)
00067 {
00068 isPressed[i] = false;
00069 lastRepeat[i] = 0;
00070 }
00071
00072
00073 QObject::connect( this, SIGNAL( setCountsSignal(unsigned int,unsigned int,unsigned int,unsigned int) ),
00074 this, SLOT( setCountsSlot(unsigned int,unsigned int,unsigned int,unsigned int) ) );
00075
00076 QObject::connect( this, SIGNAL( setPingsSignal(int, int) ),
00077 this, SLOT( setPingsSlot(int, int) ) );
00078
00079 QObject::connect( this, SIGNAL( setControlSourceSignal(int) ),
00080 this, SLOT( setControlSourceSlot(int) ) );
00081
00082 QObject::connect( this, SIGNAL( addLogLineSignal(QString) ),
00083 this, SLOT( addLogLineSlot(QString) ) );
00084
00085 QObject::connect( this, SIGNAL( setAutopilotInfoSignal(QString) ),
00086 this, SLOT( setAutopilotInfoSlot(QString) ) );
00087
00088 QObject::connect( this, SIGNAL( setStateestimationInfoSignal(QString) ),
00089 this, SLOT( setStateestimationInfoSlot(QString) ) );
00090
00091 QObject::connect( this, SIGNAL( setMotorSpeedsSignal(QString) ),
00092 this, SLOT( setMotorSpeedsSlot(QString) ) );
00093
00094 QObject::connect( this, SIGNAL( closeWindowSignal() ),
00095 this, SLOT( closeWindowSlot() ) );
00096
00097
00098 std::vector<std::string> files = std::vector<std::string>();
00099 getdirtxt( ros::package::getPath("tum_ardrone") + std::string("/flightPlans/"),files);
00100
00101 ui.comboBoxLoadFile->addItem(QString(""), QVariant());
00102 for(unsigned int i=0;i<files.size();i++)
00103 ui.comboBoxLoadFile->addItem(QString(files[i].c_str()), QVariant());
00104
00105 }
00106
00107
00108
00109 tum_ardrone_gui::~tum_ardrone_gui()
00110 {
00111 }
00112
00113
00114 void tum_ardrone_gui::LandClicked()
00115 {
00116 rosThread->sendLand();
00117 }
00118 void tum_ardrone_gui::TakeoffClicked()
00119 {
00120 rosThread->sendTakeoff();
00121 }
00122 void tum_ardrone_gui::ToggleCamClicked()
00123 {
00124 rosThread->sendToggleCam();
00125 }
00126 void tum_ardrone_gui::FlattrimClicked()
00127 {
00128 rosThread->sendFlattrim();
00129 }
00130 void tum_ardrone_gui::EmergencyClicked()
00131 {
00132 rosThread->sendToggleState();
00133 }
00134
00135 void tum_ardrone_gui::ClearClicked()
00136 {
00137 rosThread->publishCommand("c clearCommands");
00138 }
00139 void tum_ardrone_gui::SendClicked()
00140 {
00141 QStringList l = ui.plainTextEditSendCommand->toPlainText().split('\n');
00142 for(int i=0;i<l.length();i++)
00143 {
00144 std::string s = l[i].trimmed().toStdString();
00145
00146 if(s.size() > 0)
00147 rosThread->publishCommand(std::string("c ")+s);
00148 }
00149 setControlSource(CONTROL_AUTO);
00150 }
00151 void tum_ardrone_gui::ClearSendClicked()
00152 {
00153 ClearClicked();
00154 SendClicked();
00155 }
00156 void tum_ardrone_gui::ResetClicked()
00157 {
00158 setControlSource(CONTROL_NONE);
00159 ClearClicked();
00160 rosThread->publishCommand("f reset");
00161 }
00162
00163
00164 void tum_ardrone_gui::LoadFileChanged(QString val)
00165 {
00166 if(val == "")
00167 ui.plainTextEditSendCommand->setPlainText("");
00168 else
00169 {
00170 std::string path = ros::package::getPath("tum_ardrone") + std::string("/flightPlans/") + val.toStdString();
00171 addLogLine("Load File "+ path);
00172
00173 std::ifstream t;
00174 t.open(path.c_str());
00175 std::string buffer = "";
00176 std::string line;
00177 while(!t.eof())
00178 {
00179 std::getline(t, line);
00180 buffer = buffer + line + "\n";
00181 }
00182 t.close();
00183
00184 ui.plainTextEditSendCommand->setPlainText(buffer.c_str());
00185 }
00186 }
00187 void tum_ardrone_gui::ToggledUseHovering(int val)
00188 {
00189 useHovering = (val != 0);
00190 }
00191
00192 void tum_ardrone_gui::ToggledPingDrone(int val)
00193 {
00194 pingThread->measure = (val != 0);
00195 }
00196
00197
00198 void tum_ardrone_gui::ControlSourceChanged()
00199 {
00200 ControlSource s = CONTROL_NONE;
00201
00202 if(ui.radioButtonControKB->isChecked())
00203 s = CONTROL_KB;
00204 if(ui.radioButtonControlNone->isChecked())
00205 s = CONTROL_NONE;
00206 if(ui.radioButtonControlJoy->isChecked())
00207 s = CONTROL_JOY;
00208 if(ui.radioButtonControlAuto->isChecked())
00209 s = CONTROL_AUTO;
00210
00211 if(s != CONTROL_AUTO)
00212 rosThread->publishCommand("c stop");
00213 else
00214 rosThread->publishCommand("c start");
00215
00216 currentControlSource = s;
00217 }
00218
00219
00220 void tum_ardrone_gui::setControlSourceSlot(int cont)
00221 {
00222
00223 currentControlSource = (ControlSource)cont;
00224 if(cont == CONTROL_KB)
00225 ui.radioButtonControKB->setChecked(true);
00226 if(cont == CONTROL_NONE)
00227 ui.radioButtonControlNone->setChecked(true);
00228 if(cont == CONTROL_JOY)
00229 ui.radioButtonControlJoy->setChecked(true);
00230 if(cont == CONTROL_AUTO)
00231 ui.radioButtonControlAuto->setChecked(true);
00232
00233 ControlSourceChanged();
00234 }
00235
00236 void tum_ardrone_gui::setCountsSlot(unsigned int nav,unsigned int control,unsigned int pose,unsigned int joy)
00237 {
00238 char buf[100];
00239 snprintf(buf,100, "Drone Control: %d Hz", control);
00240 ui.labelControl->setText(buf);
00241
00242 snprintf(buf,100, "Joy Input: %d Hz", joy);
00243 ui.labelJoy->setText(buf);
00244
00245 snprintf(buf,100, "Drone Navdata: %d Hz", nav);
00246 ui.labelNavdata->setText(buf);
00247
00248 snprintf(buf,100, "Pose Estimates: %d Hz", pose);
00249 ui.labelPoseEst->setText(buf);
00250 }
00251
00252 void tum_ardrone_gui::setPingsSlot(int p500, int p20000)
00253 {
00254 char buf[100];
00255 snprintf(buf,100, "Pings (RTT): %d (500B), %d (20kB)", p500, p20000);
00256 ui.labelDronePings->setText(buf);
00257 }
00258
00259 void tum_ardrone_gui::addLogLineSlot(QString s)
00260 {
00261 ui.plainTextEditMessages->appendPlainText(s);
00262 }
00263 void tum_ardrone_gui::setAutopilotInfoSlot(QString s)
00264 {
00265 ui.plainTextEditAutopilotStatus->setPlainText(s);
00266 }
00267 void tum_ardrone_gui::setStateestimationInfoSlot(QString s)
00268 {
00269 ui.plainTextEditStateestimationStatus->setPlainText(s);
00270 }
00271 void tum_ardrone_gui::setMotorSpeedsSlot(QString s)
00272 {
00273 ui.labelDroneMotors->setText(s);
00274 }
00275 void tum_ardrone_gui::closeWindowSlot()
00276 {
00277 closeWindow();
00278 }
00279
00280
00281
00282
00283 void tum_ardrone_gui::setCounts(unsigned int nav,unsigned int control,unsigned int pose,unsigned int joy)
00284 {
00285 emit setCountsSignal(nav, control, pose, joy);
00286 }
00287 void tum_ardrone_gui::setControlSource(ControlSource cont)
00288 {
00289 emit setControlSourceSignal((int)cont);
00290 }
00291 void tum_ardrone_gui::addLogLine(std::string s)
00292 {
00293 emit addLogLineSignal(QString(s.c_str()));
00294 }
00295 void tum_ardrone_gui::setAutopilotInfo(std::string s)
00296 {
00297 emit setAutopilotInfoSignal(QString(s.c_str()));
00298 }
00299 void tum_ardrone_gui::setMotorSpeeds(std::string s)
00300 {
00301 emit setMotorSpeedsSignal(QString(s.c_str()));
00302 }
00303 void tum_ardrone_gui::setStateestimationInfo(std::string s)
00304 {
00305 emit setStateestimationInfoSignal(QString(s.c_str()));
00306 }
00307 void tum_ardrone_gui::setPings(int p500, int p20000)
00308 {
00309 emit setPingsSignal(p500, p20000);
00310 }
00311 void tum_ardrone_gui::closeWindow()
00312 {
00313 emit closeWindowSignal();
00314 }
00315
00316
00317
00318 int tum_ardrone_gui::mapKey(int k)
00319 {
00320 switch(k)
00321 {
00322 case 74:
00323 return 0;
00324 case 75:
00325 return 1;
00326 case 76:
00327 return 2;
00328 case 73:
00329 return 3;
00330 case 85:
00331 return 4;
00332 case 79:
00333 return 5;
00334 case 81:
00335 return 6;
00336 case 65:
00337 return 7;
00338 }
00339 return -1;
00340 }
00341
00342 void tum_ardrone_gui::keyReleaseEvent( QKeyEvent * key)
00343 {
00344 if(currentControlSource == CONTROL_KB)
00345 {
00346 int idx = mapKey(key->key());
00347 if(idx >= 0)
00348 {
00349 bool changed = false;
00350 if(!key->isAutoRepeat())
00351 {
00352 changed = isPressed[idx];
00353 isPressed[idx] = false;
00354 }
00355
00356 if(changed)
00357 rosThread->sendControlToDrone(calcKBControl());
00358 }
00359 }
00360 }
00361
00362 void tum_ardrone_gui::keyPressEvent( QKeyEvent * key)
00363 {
00364
00365 if(currentControlSource == CONTROL_KB)
00366 {
00367 int idx = mapKey(key->key());
00368 if(idx >= 0)
00369 {
00370 bool changed = !isPressed[idx];
00371
00372 isPressed[idx] = true;
00373 lastRepeat[idx] = getMS();
00374
00375 if(changed)
00376 rosThread->sendControlToDrone(calcKBControl());
00377 }
00378
00379 else if(key->key() == 83)
00380 rosThread->sendTakeoff();
00381
00382 else if(key->key() == 68)
00383 rosThread->sendLand();
00384 }
00385
00386
00387 if(key->key() == 16777216)
00388 {
00389 setFocus();
00390 setControlSource(CONTROL_KB);
00391 }
00392
00393
00394 if(key->key() == 16777264)
00395 {
00396 rosThread->sendToggleState();
00397 }
00398 }
00399
00400 ControlCommand tum_ardrone_gui::calcKBControl()
00401 {
00402
00403 for(int i=0;i<8;i++)
00404 isPressed[i] = isPressed[i] && ((lastRepeat[i] + 1000) > getMS());
00405
00406 ControlCommand c;
00407
00408 if(isPressed[0]) c.roll = -sensRP;
00409 if(isPressed[1]) c.pitch = sensRP;
00410 if(isPressed[2]) c.roll = sensRP;
00411 if(isPressed[3]) c.pitch = -sensRP;
00412 if(isPressed[4]) c.yaw = -sensYaw;
00413 if(isPressed[5]) c.yaw = sensYaw;
00414 if(isPressed[6]) c.gaz = sensRP;
00415 if(isPressed[7]) c.gaz = -sensRP;
00416
00417 return c;
00418 }