SlugsDataSensorView.cc 19.1 KB
Newer Older
1 2 3 4
#include "SlugsDataSensorView.h"
#include "ui_SlugsDataSensorView.h"

#include <UASManager.h>
tecnosapiens's avatar
tecnosapiens committed
5
#include "SlugsMAV.h"
6

7 8
#include <QDebug>

9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32
SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
    QWidget(parent),
    ui(new Ui::SlugsDataSensorView)
{
    ui->setupUi(this);


    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));

    activeUAS = NULL;

    loadParameters();


    this->setVisible(false);

    // timer for refresh UI
    updateTimer = new QTimer(this);
    connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
    updateTimer->start(200);
}

void SlugsDataSensorView::loadParameters()
{
33 34 35 36 37 38 39

    //Global Position
    Latitude = 0;
    Longitude = 0;
    Height = 0;
    timeGlobalPosition = 0;

40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
    Xpos = 0;
    Ypos = 0;
    Zpos = 0;
    TimeActualPosition = 0;

    VXpos = 0;
    VYpos = 0;
    VZpos = 0;
    TimeActualSpeed =0;

    roll = 0;
    pitch = 0;
    yaw = 0;
    TimeActualAttitude = 0;

    //Sensor Biases
    //Acelerometer
    Axb = 0;
    Ayb = 0;
    Azb = 0;
    //Gyro
    Gxb = 0;
    Gyb = 0;
    Gzb = 0;
64
    TimeActualBias = 0;
65

66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138
    //Diagnostic Message
    diagFl1 = 0;
    diagFl2 = 0;
    diagFl3 = 0;
    diagSh1 = 0;
    diagSh2 = 0;
    diagSh3 = 0;
    timeDiagnostic = 0;

    //CPU Load
    sensLoad = 0;
    ctrlLoad = 0;
    batVolt = 0;
    timeCpuLoad = 0;

    //navigation
    u_m = 0;
    phi_c = 0;
    theta_c = 0;
    psiDot_c = 0;
    ay_body = 0;
    totalDist = 0;
    dist2Go = 0;
    fromWP = 0;
    toWP = 0;
    timeNavigation = 0;

    // Data Log
    Logfl_1 = 0;
    Logfl_2 = 0;
    Logfl_3 = 0;
    Logfl_4 = 0;
    Logfl_5 = 0;
    Logfl_6 = 0;
    timeDataLog = 0;

    //pwm commands
     dt_c = 0; ///< AutoPilot's throttle command
     dla_c = 0; ///< AutoPilot's left aileron command
     dra_c = 0; ///< AutoPilot's right aileron command
     dr_c  = 0; ///< AutoPilot's rudder command
     dle_c = 0; ///< AutoPilot's left elevator command
     dre_c  = 0; ///< AutoPilot's right elevator command
     dlf_c = 0; ///< AutoPilot's left  flap command
     drf_c = 0; ///< AutoPilot's right flap command
     aux1 = 0; ///< AutoPilot's aux1 command
     aux2 = 0; ///< AutoPilot's aux2 command
     timePWMCommand = 0;


     //filtered data
      aX = 0; ///< Accelerometer X value (m/s^2)
      aY = 0; ///< Accelerometer Y value (m/s^2)
      aZ = 0; ///< Accelerometer Z value (m/s^2)
      gX = 0; ///< Gyro X value (rad/s)
      gY = 0; ///< Gyro Y value (rad/s)
      gZ = 0; ///< Gyro Z value (rad/s)
      mX = 0; ///< Magnetometer X (normalized to 1)
      mY = 0; ///< Magnetometer Y (normalized to 1)
      mZ = 0; ///< Magnetometer Z (normalized to 1)
      timeFiltered = 0;

      //gps date and time
       year = 0  ; ///< Year reported by Gps
       month =0; ///< Month reported by Gps
       day = 0; ///< Day reported by Gps
       hour = 0; ///< Hour reported by Gps
       min = 0; ///< Min reported by Gps
       sec = 0; ///< Sec reported by Gps
       visSat = 0; ///< Visible sattelites reported by Gps
       timeGPSDateTime = 0;


139 140 141 142 143 144 145 146 147
}

SlugsDataSensorView::~SlugsDataSensorView()
{
    delete ui;
}

void SlugsDataSensorView::addUAS(UASInterface* uas)
{
tecnosapiens's avatar
tecnosapiens committed
148 149 150
    SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(uas);

    if (slugsMav != NULL)
151
    {
152
        //connect standar messages
tecnosapiens's avatar
tecnosapiens committed
153 154 155
        connect(slugsMav, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugLocalPositionChange(UASInterface*,double,double,double,quint64)));
        connect(slugsMav, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64)));
        connect(slugsMav, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64)));
156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171
        connect(slugsMav, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64)));


        //connect slugs especial messages
        connect(slugsMav, SIGNAL(slugsSensorBias(int,double,double,double,double,double,double,quint64)), this, SLOT(slugsSensorBiasChanged(int,double,double,double,double,double,double,quint64)));
        connect(slugsMav, SIGNAL(slugsDiagnostic(int,double,double,double,int16_t,int16_t,int16_t,quint64)), this, SLOT(slugsDiagnosticMessageChanged(int,double,double,double,int16_t,int16_t,int16_t,quint64)));
        connect(slugsMav, SIGNAL(slugsCPULoad(int,uint8_t,uint8_t,uint8_t,quint64)), this, SLOT(slugsCpuLoadChanged(int,uint8_t,uint8_t,uint8_t,quint64)));
        connect(slugsMav, SIGNAL(slugsNavegation(int,double,double,double,double,double,double,double,uint8_t,uint8_t,quint64)),this,SLOT(slugsNavegationChanged(int,double,double,double,double,double,double,double,uint8_t,uint8_t,quint64)));
        connect(slugsMav, SIGNAL(slugsDataLog(int,double,double,double,double,double,double,quint64)), this, SLOT(slugsDataLogChanged(int,double,double,double,double,double,double,quint64)));
        connect(slugsMav, SIGNAL(slugsPWM(int,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,quint64)),this,SLOT(slugsPWMChanged(int,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,uint16_t,quint64)));
        connect(slugsMav, SIGNAL(slugsFilteredData(int,double,double,double,double,double,double,double,double,double,quint64)),this,SLOT(slugsFilteredDataChanged(int,double,double,double,double,double,double,double,double,double,quint64)));
        connect(slugsMav, SIGNAL(slugsGPSDateTime(int,uint8_t,uint8_t,uint8_t,uint8_t,uint8_t,uint8_t,uint8_t,quint64)),this,SLOT(slugsGPSDateTimeChanged(int,uint8_t,uint8_t,uint8_t,uint8_t,uint8_t,uint8_t,uint8_t,quint64)));




tecnosapiens's avatar
tecnosapiens committed
172

173 174 175 176 177 178 179 180 181 182 183 184

        // Set this UAS as active if it is the first one
        if(activeUAS == 0)
        {
            activeUAS = uas;
        }
    }
}

void SlugsDataSensorView::setActiveUAS(UASInterface* uas)
{
    activeUAS = uas;
185 186


187 188 189 190 191
}


void SlugsDataSensorView::refresh()
{
192 193
    if(activeUAS)
    {
194 195 196 197 198 199 200 201 202 203 204 205
        //refresh Global Position
        ui->m_GpsLatitude->setText(QString::number(Latitude, 'f', 4));
        ui->m_GpsLongitude->setText(QString::number(Longitude, 'f', 4));
        ui->m_Gpsheigth->setText(QString::number(Height, 'f', 4));

        //refresh GPS Date and Time
        ui->m_GpsDate->setText(QString::number(day)+ "-" + QString::number(month)+ "-" + QString::number(year));
        ui->m_GpsTime->setText(QString::number(hour)+ "-" + QString::number(min)+ "-" + QString::number(sec));
        ui->m_GpsSat->setText(QString::number(visSat));
        ui->m_GpsCog->setText("No Data");
        ui->m_GpsSog->setText("No Data");

206

207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
            //refresh UI position data
            ui->ed_x->setPlainText(QString::number(Xpos, 'f', 4));
            ui->ed_y->setPlainText(QString::number(Ypos, 'f', 4));
            ui->ed_z->setPlainText(QString::number(Zpos, 'f', 4));

            //refresh UI speed position data
            ui->ed_vx->setPlainText(QString::number(VXpos,'f',4));
            ui->ed_vy->setPlainText(QString::number(VYpos,'f',4));
            ui->ed_vz->setPlainText(QString::number(VZpos,'f',4));

            //refresh UI attitude data
            ui->m_SlugAttitudeRoll_plainTextEdit->setPlainText(QString::number(roll,'f',4));
            ui->m_SlugAttitudePitch_plainTextEdit->setPlainText(QString::number(pitch,'f',4));
            ui->m_SlugAttitudeYaw_plainTextEdit->setPlainText(QString::number(yaw,'f',4));

            //refresh UI sensor bias acelerometer data
223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257
            ui->m_AxBiases->setText(QString::number(Axb, 'f', 4));
            ui->m_AyBiases->setText(QString::number(Ayb, 'f', 4));
            ui->m_AzBiases->setText(QString::number(Azb, 'f', 4));
            ui->m_GxBiases->setText(QString::number(Gxb, 'f', 4));
            ui->m_GyBiases->setText(QString::number(Gyb, 'f', 4));
            ui->m_GzBiases->setText(QString::number(Gzb, 'f', 4));

            //refresh UI diagnostic data
            ui->m_SlugsFl1_textEdit->setText(QString::number(diagFl1, 'f', 4));
            ui->m_SlugsFl2_textEdit->setText(QString::number(diagFl2, 'f', 4));
            ui->m_SlugsFl3_textEdit->setText(QString::number(diagFl3, 'f', 4));
            ui->m_SlugsSh1_textEdit->setText(QString::number(diagSh1, 'f', 4));
            ui->m_SlugsSh2_textEdit->setText(QString::number(diagSh2, 'f', 4));
            ui->m_SlugsSh3_textEdit->setText(QString::number(diagSh3, 'f', 4));

            //refresh UI navegation data
            ui->m_SlugsUm_textEdit->setText(QString::number(u_m, 'f', 4));
            ui->m_SlugsPitchC_textEdit->setText(QString::number(pitch, 'f', 4));
            ui->m_SlugsPsidC_textEdit->setText(QString::number(psiDot_c, 'f', 4));
            ui->m_SlugsPhiC_textEdit->setText(QString::number(phi_c, 'f', 4));
            ui->m_SlugsAyBody_textEdit->setText(QString::number(ay_body, 'f', 4));
            ui->m_SlugsFromWP_textEdit->setText(QString::number(fromWP, 'f', 4));
            ui->m_SlugsToWP_textEdit->setText(QString::number(toWP, 'f', 4));
            ui->m_SlugsTotRun_textEdit->setText(QString::number(totalDist, 'f', 4));
            ui->m_SlugsDistToGround_textEdit->setText(QString::number(dist2Go, 'f', 4));

            //refresh UI Data Log
            ui->m_logFl1_textEdit->setText(QString::number(Logfl_1, 'f', 4));
            ui->m_logFl2_textEdit->setText(QString::number(Logfl_2, 'f', 4));
            ui->m_logFl3_textEdit->setText(QString::number(Logfl_3, 'f', 4));
            ui->m_logFl4_textEdit->setText(QString::number(Logfl_4, 'f', 4));
            ui->m_logFl5_textEdit->setText(QString::number(Logfl_5, 'f', 4));
            ui->m_logFl6_textEdit->setText(QString::number(Logfl_6, 'f', 4));

            //refresh UI PWM Commands
258 259 260 261 262 263 264 265 266 267
            ui->m_pwmThro->setText(QString::number(dt_c, 'f', 4));
            ui->m_pwmThroTrim->setText(QString::number(dre_c, 'f', 4));
            ui->m_pwmAile->setText(QString::number(dla_c, 'f', 4));
            ui->m_pwmAileTrim->setText(QString::number(dlf_c, 'f', 4));
            ui->m_pwmElev->setText(QString::number(dle_c, 'f', 4));
            ui->m_pwmElevTrim->setText(QString::number(drf_c, 'f', 4));
            ui->m_pwmRudd->setText(QString::number(dr_c, 'f', 4));
            ui->m_pwmRuddTrim->setText(QString::number(aux1, 'f', 4));
            ui->m_pwmFailSafe->setText(QString::number(dre_c, 'f', 4));
            ui->m_pwmAvailable->setText("No Data");
268 269 270



271

272 273


tecnosapiens's avatar
tecnosapiens committed
274 275


276
    }
277 278 279

}

280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298
void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
                                                     double lat,
                                                     double lon,
                                                     double alt,
                                                     quint64 time)

{
    Q_UNUSED( uas);
    Latitude = lat;
    Longitude = lon;
    Height = alt;
    timeGlobalPosition = time;



}


void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
299 300 301 302
                                                   double x,
                                                   double y,
                                                   double z,
                                                   quint64 time)
303
{
304
    Q_UNUSED( uas);
305 306 307 308 309 310 311 312

    Xpos = x;
    Ypos = y;
    Zpos = z;
    TimeActualPosition = time;

}

313
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
314 315 316 317
                                                        double vx,
                                                        double vy,
                                                        double vz,
                                                        quint64 time)
318
{
319
    Q_UNUSED( uas);
320 321 322 323 324 325 326

    VXpos = vx;
    VYpos = vy;
    VZpos = vz;
    TimeActualSpeed = time;
}

327
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
328 329 330 331
                                              double slugroll,
                                              double slugpitch,
                                              double slugyaw,
                                              quint64 time)
332
{
333
    Q_UNUSED( uas);
334 335 336 337 338 339 340

    roll = slugroll;
    pitch = slugpitch;
    yaw = slugyaw;
    TimeActualAttitude = time;
}

341
void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
342 343 344 345 346 347 348
                                                 double axb,
                                                 double ayb,
                                                 double azb,
                                                 double gxb,
                                                 double gyb,
                                                 double gzb,
                                                 quint64 time)
349
{
350 351

     Q_UNUSED( systemId);
352 353 354 355

     Axb = axb;
     Ayb = ayb;
     Azb = azb;
356 357 358 359
     Gxb = gxb;
     Gyb = gyb;
     Gzb = gzb;
     TimeActualBias = time;
360 361 362 363


}

364 365 366 367 368 369 370 371 372 373
void SlugsDataSensorView::slugsDiagnosticMessageChanged(int systemId,
                                                        double diagfl1,
                                                        double diagfl2,
                                                        double diagfl3,
                                                        int16_t diagsh1,
                                                        int16_t diagsh2,
                                                        int16_t diagsh3,
                                                        quint64 time)
{
    Q_UNUSED(systemId);
374

375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521
    diagFl1 = diagfl1;
    diagFl2 = diagfl2;
    diagFl3 = diagfl3;
    diagSh1 = diagsh1;
    diagSh2 = diagsh2;
    diagSh3 = diagsh3;
    timeDiagnostic = time;

}


void SlugsDataSensorView::slugsCpuLoadChanged(int systemId,
                                              uint8_t sensload,
                                              uint8_t ctrlload,
                                              uint8_t batvolt,
                                              quint64 time)
{
     Q_UNUSED(systemId);
    sensLoad = sensload;
    ctrlLoad = ctrlload;
    batVolt = batvolt;
    timeCpuLoad = time;
}

void SlugsDataSensorView::slugsNavegationChanged(int systemId,
                                                 double navu_m,
                                                 double navphi_c,
                                                 double navtheta_c,
                                                 double navpsiDot_c,
                                                 double navay_body,
                                                 double navtotalDist,
                                                 double navdist2Go,
                                                 uint8_t navfromWP,
                                                 uint8_t navtoWP,
                                                 quint64 time)
{
     Q_UNUSED(systemId);
     u_m = navu_m;
     phi_c = navphi_c;
     theta_c = navtheta_c;
     psiDot_c = navpsiDot_c;
     ay_body = navay_body;
     totalDist = navtotalDist;
     dist2Go = navdist2Go;
     fromWP = navfromWP;
     toWP = navtoWP;
     timeNavigation = time;
}



void SlugsDataSensorView::slugsDataLogChanged(int systemId,
                                              double logfl_1,
                                              double logfl_2,
                                              double logfl_3,
                                              double logfl_4,
                                              double logfl_5,
                                              double logfl_6,
                                              quint64 time)
{
    qDebug()<<"----------------------------------------------------->>>>>>>>>>>>>>> ACTUALIZANDO LOG DATA";
     Q_UNUSED(systemId);
    Logfl_1 = logfl_1;
    Logfl_2 = logfl_2;
    Logfl_3 = logfl_3;
    Logfl_4 = logfl_4;
    Logfl_5 = logfl_5;
    Logfl_6 = logfl_6;
    timeDataLog = time;
}

void SlugsDataSensorView::slugsPWMChanged(int systemId,
                                          uint16_t vdt_c,
                                          uint16_t vdla_c,
                                          uint16_t vdra_c,
                                          uint16_t vdr_c,
                                          uint16_t vdle_c,
                                          uint16_t vdre_c,
                                          uint16_t vdlf_c,
                                          uint16_t vdrf_c,
                                          uint16_t vda1_c,
                                          uint16_t vda2_c,
                                          quint64 time)
{
       Q_UNUSED(systemId);
       dt_c = vdt_c; ///< AutoPilot's throttle command
       dla_c = vdla_c; ///< AutoPilot's left aileron command
       dra_c = vdra_c; ///< AutoPilot's right aileron command
       dr_c  = vdr_c; ///< AutoPilot's rudder command
       dle_c = vdle_c; ///< AutoPilot's left elevator command
       dre_c  = vdre_c; ///< AutoPilot's right elevator command
       dlf_c = vdlf_c; ///< AutoPilot's left  flap command
       drf_c = vdrf_c; ///< AutoPilot's right flap command
       aux1 = vda1_c; ///< AutoPilot's aux1 command
       aux2 = vda2_c; ///< AutoPilot's aux2 command
       timePWMCommand = time;

}

void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
                                                   double filaX,
                                                   double filaY,
                                                   double filaZ,
                                                   double filgX,
                                                   double filgY,
                                                   double filgZ,
                                                   double filmX,
                                                   double filmY,
                                                   double filmZ,
                                                   quint64 time)
{
    Q_UNUSED(systemId);

    aX = filaX; ///< Accelerometer X value (m/s^2)
    aY = filaY; ///< Accelerometer Y value (m/s^2)
    aZ = filaZ; ///< Accelerometer Z value (m/s^2)
    gX = filgX; ///< Gyro X value (rad/s)
    gY = filgY; ///< Gyro Y value (rad/s)
    gZ = filgZ; ///< Gyro Z value (rad/s)
    mX = filmX; ///< Magnetometer X (normalized to 1)
    mY = filmY; ///< Magnetometer Y (normalized to 1)
    mZ = filmZ; ///< Magnetometer Z (normalized to 1)
    timeFiltered = time;
}

void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
                                                  uint8_t gpsyear,
                                                  uint8_t gpsmonth,
                                                  uint8_t gpsday,
                                                  uint8_t gpshour,
                                                  uint8_t gpsmin,
                                                  uint8_t gpssec,
                                                  uint8_t gpsvisSat,
                                                  quint64 time)
{
    Q_UNUSED(systemId);

    year = gpsyear  ; ///< Year reported by Gps
    month = gpsmonth; ///< Month reported by Gps
    day = gpsday; ///< Day reported by Gps
    hour = gpshour; ///< Hour reported by Gps
    min = gpsmin; ///< Min reported by Gps
    sec = gpssec; ///< Sec reported by Gps
    visSat = gpsvisSat; ///< Visible sattelites reported by Gps
    timeGPSDateTime = time;

}