UAS.cc 26.6 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

Donald Gagne's avatar
Donald Gagne committed
10 11 12
// NO NEW CODE HERE
// UASInterface, UAS.h/cc are deprecated. All new functionality should go into Vehicle.h/cc
//
13 14 15 16 17 18

#include <QList>
#include <QTimer>
#include <QSettings>
#include <iostream>
#include <QDebug>
Don Gagne's avatar
Don Gagne committed
19

20 21
#include <cmath>
#include <qmath.h>
Don Gagne's avatar
Don Gagne committed
22

23 24 25
#include <limits>
#include <cstdlib>

26 27 28 29 30 31
#include "UAS.h"
#include "LinkInterface.h"
#include "QGC.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
Gus Grubba's avatar
Gus Grubba committed
32
#ifndef NO_SERIAL_LINK
33
#include "SerialLink.h"
dogmaphobic's avatar
dogmaphobic committed
34
#endif
Don Gagne's avatar
Don Gagne committed
35
#include "FirmwarePluginManager.h"
36
#include "QGCLoggingCategory.h"
37
#include "Vehicle.h"
38
#include "Joystick.h"
39
#include "QGCApplication.h"
40

41
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
42

Don Gagne's avatar
Don Gagne committed
43
// THIS CLASS IS DEPRECATED. ALL NEW FUNCTIONALITY SHOULD GO INTO Vehicle class
44
UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(),
45 46
    lipoFull(4.2f),
    lipoEmpty(3.5f),
47
    uasId(vehicle->id()),
48 49
    unknownPackets(),
    mavlink(protocol),
50 51 52 53 54 55
    receiveDropRate(0),
    sendDropRate(0),

    status(-1),

    startTime(QGC::groundTimeMilliseconds()),
56
    onboardTimeOffset(0),
57

58 59 60 61
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
62

63 64 65
    attitudeKnown(false),
    attitudeStamped(false),
    lastAttitude(0),
66

Don Gagne's avatar
Don Gagne committed
67 68
    imagePackets(0),    // We must initialize to 0, otherwise extended data packets maybe incorrectly thought to be images

Don Gagne's avatar
Don Gagne committed
69 70 71
    blockHomePositionChanges(false),
    receivedMode(false),

72 73
    // Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
    // TODO: calibrate stand-still pixhawk variances
74
    xacc_var(0.6457f),
dogmaphobic's avatar
dogmaphobic committed
75
    yacc_var(0.7048f),
76
    zacc_var(0.97885f),
dogmaphobic's avatar
dogmaphobic committed
77 78 79
    rollspeed_var(0.8126f),
    pitchspeed_var(0.6145f),
    yawspeed_var(0.5852f),
80 81 82 83 84 85 86
    xmag_var(0.2393f),
    ymag_var(0.2283f),
    zmag_var(0.1665f),
    abs_pressure_var(0.5802f),
    diff_pressure_var(0.5802f),
    pressure_alt_var(0.5802f),
    temperature_var(0.7145f),
87
    /*
88 89 90 91 92 93 94 95 96 97 98 99 100
    xacc_var(0.0f),
    yacc_var(0.0f),
    zacc_var(0.0f),
    rollspeed_var(0.0f),
    pitchspeed_var(0.0f),
    yawspeed_var(0.0f),
    xmag_var(0.0f),
    ymag_var(0.0f),
    zmag_var(0.0f),
    abs_pressure_var(0.0f),
    diff_pressure_var(0.0f),
    pressure_alt_var(0.0f),
    temperature_var(0.0f),
101
    */
102

103
    // The protected members.
104 105 106 107
    connectionLost(false),
    lastVoltageWarning(0),
    lastNonNullTime(0),
    onboardTimeOffsetInvalidCount(0),
108 109
    _vehicle(vehicle),
    _firmwarePluginManager(firmwarePluginManager)
110
{
dogmaphobic's avatar
dogmaphobic committed
111

112 113 114 115 116 117 118 119 120 121
}

/**
* @ return the id of the uas
*/
int UAS::getUASID() const
{
    return uasId;
}

122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139
// Ignore warnings from mavlink headers for both GCC/Clang and MSVC
#ifdef __GNUC__

#if __GNUC__ > 8
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
#elif defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Waddress-of-packed-member"
#else
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wall"
#endif

#else
#pragma warning(push, 0)
#endif

140
void UAS::receiveMessage(mavlink_message_t message)
141 142 143 144
{
    // Only accept messages from this system (condition 1)
    // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
    // and we already got one attitude packet
145
    if (message.sysid == uasId && (!attitudeStamped || lastAttitude != 0 || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161
    {
        bool multiComponentSourceDetected = false;
        bool wrongComponent = false;

        switch (message.compid)
        {
        case MAV_COMP_ID_IMU_2:
            // Prefer IMU 2 over IMU 1 (FIXME)
            componentID[message.msgid] = MAV_COMP_ID_IMU_2;
            break;
        default:
            // Do nothing
            break;
        }

        // Store component ID
Gus Grubba's avatar
Gus Grubba committed
162
        if (!componentID.contains(message.msgid))
163 164 165
        {
            // Prefer the first component
            componentID[message.msgid] = message.compid;
Gus Grubba's avatar
Gus Grubba committed
166
            componentMulti[message.msgid] = false;
167 168 169 170 171 172 173 174 175 176 177
        }
        else
        {
            // Got this message already
            if (componentID[message.msgid] != message.compid)
            {
                componentMulti[message.msgid] = true;
                wrongComponent = true;
            }
        }

Gus Grubba's avatar
Gus Grubba committed
178 179 180
        if (componentMulti[message.msgid] == true) {
            multiComponentSourceDetected = true;
        }
181 182 183 184 185 186 187 188 189 190 191 192


        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
193 194 195

            // Send the base_mode and system_status values to the plotter. This uses the ground time
            // so the Ground Time checkbox must be ticked for these values to display
196
            quint64 time = getUnixTime();
197 198 199 200 201
            QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
            emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time);
            emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time);
            emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time);

202 203
            // We got the mode
            receivedMode = true;
204 205 206
        }

            break;
207

208 209 210 211 212 213 214 215 216
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);

217
            // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
218
            quint64 time = getUnixTime();
219 220 221 222 223 224 225
            QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
            emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
            emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
            emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
            emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
            emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
            emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
226 227
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

228 229 230 231
            // Process CPU load.
            emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
            emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
        }
232
            break;
233

234 235
        case MAVLINK_MSG_ID_PARAM_VALUE:
        {
236 237 238
            mavlink_param_value_t rawValue;
            mavlink_msg_param_value_decode(&message, &rawValue);
            QByteArray bytes(rawValue.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
239 240 241
            // Construct a string stopping at the first NUL (0) character, else copy the whole
            // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
            QString parameterName(bytes);
242 243 244
            mavlink_param_union_t paramVal;
            paramVal.param_float = rawValue.param_value;
            paramVal.type = rawValue.param_type;
245

246 247
            processParamValueMsg(message, parameterName,rawValue,paramVal);
         }
248
            break;
249
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
250
        {
251 252 253 254
            mavlink_attitude_target_t out;
            mavlink_msg_attitude_target_decode(&message, &out);
            float roll, pitch, yaw;
            mavlink_quaternion_to_euler(out.q, &roll, &pitch, &yaw);
255
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
256 257

            // For plotting emit roll sp, pitch sp and yaw sp values
258 259 260
            emit valueChanged(uasId, "roll sp", "rad", roll, time);
            emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
            emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
261 262
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
263

264 265 266 267 268 269 270 271 272 273 274 275
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
        {
            mavlink_data_transmission_handshake_t p;
            mavlink_msg_data_transmission_handshake_decode(&message, &p);
            imageSize = p.size;
            imagePackets = p.packets;
            imagePayload = p.payload;
            imageQuality = p.jpg_quality;
            imageType = p.type;
            imageWidth = p.width;
            imageHeight = p.height;
            imageStart = QGC::groundTimeMilliseconds();
276 277
            imagePacketsArrived = 0;

278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293
        }
            break;

        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
        {
            mavlink_encapsulated_data_t img;
            mavlink_msg_encapsulated_data_decode(&message, &img);
            int seq = img.seqnr;
            int pos = seq * imagePayload;

            // Check if we have a valid transaction
            if (imagePackets == 0)
            {
                // NO VALID TRANSACTION - ABORT
                // Restart statemachine
                imagePacketsArrived = 0;
Don Gagne's avatar
Don Gagne committed
294
                break;
295 296 297 298 299 300 301 302 303 304 305 306 307
            }

            for (int i = 0; i < imagePayload; ++i)
            {
                if (pos <= imageSize) {
                    imageRecBuffer[pos] = img.data[i];
                }
                ++pos;
            }

            ++imagePacketsArrived;

            // emit signal if all packets arrived
308
            if (imagePacketsArrived >= imagePackets)
309 310
            {
                // Restart statemachine
Don Gagne's avatar
Don Gagne committed
311 312
                imagePackets = 0;
                imagePacketsArrived = 0;
313 314 315 316 317
                emit imageReady(this);
            }
        }
            break;

dogmaphobic's avatar
dogmaphobic committed
318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333
        case MAVLINK_MSG_ID_LOG_ENTRY:
        {
            mavlink_log_entry_t log;
            mavlink_msg_log_entry_decode(&message, &log);
            emit logEntry(this, log.time_utc, log.size, log.id, log.num_logs, log.last_log_num);
        }
            break;

        case MAVLINK_MSG_ID_LOG_DATA:
        {
            mavlink_log_data_t log;
            mavlink_msg_log_data_decode(&message, &log);
            emit logData(this, log.ofs, log.id, log.count, log.data);
        }
            break;

334 335 336 337 338 339
        default:
            break;
        }
    }
}

340 341 342 343 344 345 346 347 348 349 350
// Pop warnings ignoring for mavlink headers for both GCC/Clang and MSVC
#ifdef __GNUC__
    #if defined(__clang__)
        #pragma clang diagnostic pop
    #else
        #pragma GCC diagnostic pop
    #endif
#else
#pragma warning(pop, 0)
#endif

351
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
352
{
353 354 355
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
356

357 358 359 360 361
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
362
    int pressureCal = 0;
363
    int escCal = 0;
dogmaphobic's avatar
dogmaphobic committed
364

365
    switch (calType) {
366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386
    case StartCalibrationGyro:
        gyroCal = 1;
        break;
    case StartCalibrationMag:
        magCal = 1;
        break;
    case StartCalibrationAirspeed:
        airspeedCal = 1;
        break;
    case StartCalibrationRadio:
        radioCal = 1;
        break;
    case StartCalibrationCopyTrims:
        radioCal = 2;
        break;
    case StartCalibrationAccel:
        accelCal = 1;
        break;
    case StartCalibrationLevel:
        accelCal = 2;
        break;
387 388 389
    case StartCalibrationPressure:
        pressureCal = 1;
        break;
390 391 392 393 394 395 396 397 398
    case StartCalibrationEsc:
        escCal = 1;
        break;
    case StartCalibrationUavcanEsc:
        escCal = 2;
        break;
    case StartCalibrationCompassMot:
        airspeedCal = 1; // ArduPilot, bit of a hack
        break;
399
    }
dogmaphobic's avatar
dogmaphobic committed
400

401 402
    // We can't use sendMavCommand here since we have no idea how long it will be before the command returns a result. This in turn
    // causes the retry logic to break down.
403
    mavlink_message_t msg;
404 405 406 407 408 409 410 411 412 413
    mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
                                       mavlink->getComponentId(),
                                       _vehicle->priorityLink()->mavlinkChannel(),
                                       &msg,
                                       uasId,
                                       _vehicle->defaultComponentId(),   // target component
                                       MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                       0,                                // 0=first transmission of command
                                       gyroCal,                          // gyro cal
                                       magCal,                           // mag cal
414
                                       pressureCal,                      // ground pressure
415 416 417 418
                                       radioCal,                         // radio cal
                                       accelCal,                         // accel cal
                                       airspeedCal,                      // PX4: airspeed cal, ArduPilot: compass mot
                                       escCal);                          // esc cal
419
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->priorityLink(), msg);
420 421
}

422
void UAS::stopCalibration(void)
423
{
424 425 426
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
427

428 429 430 431 432 433 434 435 436 437
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_CALIBRATION,     // command id
                             true,                              // showError
                             0,                                 // gyro cal
                             0,                                 // mag cal
                             0,                                 // ground pressure
                             0,                                 // radio cal
                             0,                                 // accel cal
                             0,                                 // airspeed cal
                             0);                                // unused
438 439
}

440 441
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
442 443 444
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
445

446
   int actuatorCal = 0;
447 448 449 450

    switch (calType) {
        case StartBusConfigActuators:
            actuatorCal = 1;
451 452 453 454
        break;
        case EndBusConfigActuators:
            actuatorCal = 0;
        break;
455 456
    }

457 458 459 460
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_UAVCAN,          // command id
                             true,                              // showError
                             actuatorCal);                      // actuators
461 462 463 464
}

void UAS::stopBusConfig(void)
{
465 466 467
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
468

469 470 471 472
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_UAVCAN,          // command id
                             true,                              // showError
                             0);                                // cancel
473 474
}

475 476
/**
* Check if time is smaller than 40 years, assuming no system without Unix
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 522 523 524 525 526 527
* timestamp runs longer than 40 years continuously without reboot. In worst case
* this will add/subtract the communication delay between GCS and MAV, it will
* never alter the timestamp in a safety critical way.
*/
quint64 UAS::getUnixReferenceTime(quint64 time)
{
    // Same as getUnixTime, but does not react to attitudeStamped mode
    if (time == 0)
    {
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
        return QGC::groundTimeMilliseconds();
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000000LLU)
#else
    else if (time < 1261440000000000)
#endif
    {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
        if (onboardTimeOffset == 0)
        {
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
        }
        return time/1000 + onboardTimeOffset;
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        return time/1000;
    }
}

/**
* @warning If attitudeStamped is enabled, this function will not actually return
528
* the precise time stamp of this measurement augmented to UNIX time, but will
529
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
530
* reason why one would want this, except for system setups where the onboard
531
* clock is not present or broken and datasets should be collected that are still
532
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
533 534 535 536 537 538 539 540 541
* SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
*/
quint64 UAS::getUnixTimeFromMs(quint64 time)
{
    return getUnixTime(time*1000);
}

/**
* @warning If attitudeStamped is enabled, this function will not actually return
542 543 544 545
* the precise time stam of this measurement augmented to UNIX time, but will
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
* reason why one would want this, except for system setups where the onboard
* clock is not present or broken and datasets should be collected that are
546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602
* still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
* RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
*/
quint64 UAS::getUnixTime(quint64 time)
{
    quint64 ret = 0;
    if (attitudeStamped)
    {
        ret = lastAttitude;
    }

    if (time == 0)
    {
        ret = QGC::groundTimeMilliseconds();
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000000LLU)
#else
    else if (time < 1261440000000000)
#endif
    {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
        if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100))
        {
            lastNonNullTime = time;
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
        }
        if (time > lastNonNullTime) lastNonNullTime = time;

        ret = time/1000 + onboardTimeOffset;
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        ret = time/1000;
    }

    return ret;
}

603
/**
604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664
* Get the status of the code and a description of the status.
* Status can be unitialized, booting up, calibrating sensors, active
* standby, cirtical, emergency, shutdown or unknown.
*/
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
    case MAV_STATE_UNINIT:
        uasState = tr("UNINIT");
        stateDescription = tr("Unitialized, booting up.");
        break;
    case MAV_STATE_BOOT:
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait.");
        break;
    case MAV_STATE_CALIBRATING:
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors, please wait.");
        break;
    case MAV_STATE_ACTIVE:
        uasState = tr("ACTIVE");
        stateDescription = tr("Active, normal operation.");
        break;
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby mode, ready for launch.");
        break;
    case MAV_STATE_CRITICAL:
        uasState = tr("CRITICAL");
        stateDescription = tr("FAILURE: Continuing operation.");
        break;
    case MAV_STATE_EMERGENCY:
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Land Immediately!");
        break;
        //case MAV_STATE_HILSIM:
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;

    case MAV_STATE_POWEROFF:
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system.");
        break;

    default:
        uasState = tr("UNKNOWN");
        stateDescription = tr("Unknown system state");
        break;
    }
}

QImage UAS::getImage()
{

//    qDebug() << "IMAGE TYPE:" << imageType;

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
665
        int imgColors = 255;
666 667 668 669 670

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
        header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);

Don Gagne's avatar
Don Gagne committed
671
        QByteArray tmpImage(header.toStdString().c_str(), header.length());
672 673 674 675 676 677 678 679 680 681 682 683
        tmpImage.append(imageRecBuffer);

        //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;

        if (imageRecBuffer.isNull())
        {
            qDebug()<< "could not convertToPGM()";
            return QImage();
        }

        if (!image.loadFromData(tmpImage, "PGM"))
        {
684
            qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
685 686 687 688 689 690 691 692 693 694 695 696
            return QImage();
        }

    }
    // BMP with header
    else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
             imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
             imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
             imageType == MAVLINK_DATA_STREAM_IMG_PNG)
    {
        if (!image.loadFromData(imageRecBuffer))
        {
697
            qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
698
            return QImage();
699 700
        }
    }
701

702 703
    // Restart statemachine
    imagePacketsArrived = 0;
704 705
    imagePackets = 0;
    imageRecBuffer.clear();
706 707 708 709 710
    return image;
}

void UAS::requestImage()
{
711 712 713
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
714

715
   qDebug() << "trying to get an image from the uas...";
716 717 718 719 720

    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
721 722 723 724 725 726
        mavlink_msg_data_transmission_handshake_pack_chan(mavlink->getSystemId(),
                                                          mavlink->getComponentId(),
                                                          _vehicle->priorityLink()->mavlinkChannel(),
                                                          &msg,
                                                          MAVLINK_DATA_STREAM_IMG_JPEG,
                                                          0, 0, 0, 0, 0, 50);
727
        _vehicle->sendMessageOnLinkThreadSafe(_vehicle->priorityLink(), msg);
728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750
    }
}


/* MANAGEMENT */

/**
 *
 * @return The uptime in milliseconds
 *
 */
quint64 UAS::getUptime() const
{
    if(startTime == 0)
    {
        return 0;
    }
    else
    {
        return QGC::groundTimeMilliseconds() - startTime;
    }
}

751
//TODO update this to use the parameter manager / param data model instead
752
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue,  mavlink_param_union_t& paramUnion)
753 754 755
{
    int compId = msg.compid;

756
    QVariant paramValue;
757 758

    // Insert with correct type
759

760 761
    switch (rawValue.param_type) {
        case MAV_PARAM_TYPE_REAL32:
Don Gagne's avatar
Don Gagne committed
762
            paramValue = QVariant(paramUnion.param_float);
763
            break;
764

765
        case MAV_PARAM_TYPE_UINT8:
Don Gagne's avatar
Don Gagne committed
766
            paramValue = QVariant(paramUnion.param_uint8);
767
            break;
768

769
        case MAV_PARAM_TYPE_INT8:
Don Gagne's avatar
Don Gagne committed
770
            paramValue = QVariant(paramUnion.param_int8);
771
            break;
772

773 774 775 776
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant(paramUnion.param_uint16);
            break;

777
        case MAV_PARAM_TYPE_INT16:
Don Gagne's avatar
Don Gagne committed
778
            paramValue = QVariant(paramUnion.param_int16);
779
            break;
780

781
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
782
            paramValue = QVariant(paramUnion.param_uint32);
783
            break;
dogmaphobic's avatar
dogmaphobic committed
784

785
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
786
            paramValue = QVariant(paramUnion.param_int32);
787
            break;
788

789 790 791 792 793 794 795 796
        //-- Note: These are not handled above:
        //
        //   MAV_PARAM_TYPE_UINT64
        //   MAV_PARAM_TYPE_INT64
        //   MAV_PARAM_TYPE_REAL64
        //
        //   No space in message (the only storage allocation is a "float") and not present in mavlink_param_union_t

797 798
        default:
            qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
799
    }
800

801
    qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
802

803
    emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
804 805
}

806
/**
Jean Cyr's avatar
Jean Cyr committed
807
* Order the robot to start receiver pairing
808 809 810
*/
void UAS::pairRX(int rxType, int rxSubType)
{
811 812 813 814 815 816
    if (_vehicle) {
        _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                                 MAV_CMD_START_RX_PAIR,             // command id
                                 true,                              // showError
                                 rxType,
                                 rxSubType);
817
    }
818
}
dogmaphobic's avatar
dogmaphobic committed
819

Don Gagne's avatar
Don Gagne committed
820 821
void UAS::shutdownVehicle(void)
{
822
    _vehicle = nullptr;
Don Gagne's avatar
Don Gagne committed
823
}