UAS.cc 34.3 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
#ifndef __mobile__
64
    fileManager(this, vehicle),
65
#endif
Don Gagne's avatar
Don Gagne committed
66

67 68 69
    attitudeKnown(false),
    attitudeStamped(false),
    lastAttitude(0),
70

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

Don Gagne's avatar
Don Gagne committed
73 74 75
    blockHomePositionChanges(false),
    receivedMode(false),

76 77
    // Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
    // TODO: calibrate stand-still pixhawk variances
78
    xacc_var(0.6457f),
dogmaphobic's avatar
dogmaphobic committed
79
    yacc_var(0.7048f),
80
    zacc_var(0.97885f),
dogmaphobic's avatar
dogmaphobic committed
81 82 83
    rollspeed_var(0.8126f),
    pitchspeed_var(0.6145f),
    yawspeed_var(0.5852f),
84 85 86 87 88 89 90
    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),
91
    /*
92 93 94 95 96 97 98 99 100 101 102 103 104
    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),
105
    */
106

107
    // The protected members.
108 109 110 111
    connectionLost(false),
    lastVoltageWarning(0),
    lastNonNullTime(0),
    onboardTimeOffsetInvalidCount(0),
112 113
    _vehicle(vehicle),
    _firmwarePluginManager(firmwarePluginManager)
114
{
dogmaphobic's avatar
dogmaphobic committed
115

116
#ifndef __mobile__
117
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
118
#endif
119

120 121 122 123 124 125 126 127 128 129
}

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

130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147
// 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

148
void UAS::receiveMessage(mavlink_message_t message)
149 150 151 152
{
    // 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
153
    if (message.sysid == uasId && (!attitudeStamped || lastAttitude != 0 || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169
    {
        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
170
        if (!componentID.contains(message.msgid))
171 172 173
        {
            // Prefer the first component
            componentID[message.msgid] = message.compid;
Gus Grubba's avatar
Gus Grubba committed
174
            componentMulti[message.msgid] = false;
175 176 177 178 179 180 181 182 183 184 185
        }
        else
        {
            // Got this message already
            if (componentID[message.msgid] != message.compid)
            {
                componentMulti[message.msgid] = true;
                wrongComponent = true;
            }
        }

Gus Grubba's avatar
Gus Grubba committed
186 187 188
        if (componentMulti[message.msgid] == true) {
            multiComponentSourceDetected = true;
        }
189 190 191 192 193 194 195 196 197 198 199 200


        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
201 202 203

            // 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
204
            quint64 time = getUnixTime();
205 206 207 208 209
            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);

210 211
            // We got the mode
            receivedMode = true;
212 213 214
        }

            break;
215

216 217 218 219 220 221 222 223 224
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);

225
            // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
226
            quint64 time = getUnixTime();
227 228 229 230 231 232 233
            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);
234 235
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

236 237 238 239
            // 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);
        }
240
            break;
241

242 243
        case MAVLINK_MSG_ID_PARAM_VALUE:
        {
244 245 246
            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);
247 248 249
            // 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);
250 251 252
            mavlink_param_union_t paramVal;
            paramVal.param_float = rawValue.param_value;
            paramVal.type = rawValue.param_type;
253

254 255
            processParamValueMsg(message, parameterName,rawValue,paramVal);
         }
256
            break;
257
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
258
        {
259 260 261 262
            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);
263
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
264 265

            // For plotting emit roll sp, pitch sp and yaw sp values
266 267 268
            emit valueChanged(uasId, "roll sp", "rad", roll, time);
            emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
            emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
269 270
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
271

272 273 274 275 276 277 278 279 280 281 282 283
        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();
284 285
            imagePacketsArrived = 0;

286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301
        }
            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
302
                break;
303 304 305 306 307 308 309 310 311 312 313 314 315
            }

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

            ++imagePacketsArrived;

            // emit signal if all packets arrived
316
            if (imagePacketsArrived >= imagePackets)
317 318
            {
                // Restart statemachine
Don Gagne's avatar
Don Gagne committed
319 320
                imagePackets = 0;
                imagePacketsArrived = 0;
321 322 323 324 325
                emit imageReady(this);
            }
        }
            break;

dogmaphobic's avatar
dogmaphobic committed
326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341
        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;

342 343 344 345 346 347
        default:
            break;
        }
    }
}

348 349 350 351 352 353 354 355 356 357 358
// 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

359
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
360
{
361 362 363
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
364

365 366 367 368 369
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
370
    int pressureCal = 0;
371
    int escCal = 0;
dogmaphobic's avatar
dogmaphobic committed
372

373
    switch (calType) {
374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394
    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;
395 396 397
    case StartCalibrationPressure:
        pressureCal = 1;
        break;
398 399 400 401 402 403 404 405 406
    case StartCalibrationEsc:
        escCal = 1;
        break;
    case StartCalibrationUavcanEsc:
        escCal = 2;
        break;
    case StartCalibrationCompassMot:
        airspeedCal = 1; // ArduPilot, bit of a hack
        break;
407
    }
dogmaphobic's avatar
dogmaphobic committed
408

409 410
    // 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.
411
    mavlink_message_t msg;
412 413 414 415 416 417 418 419 420 421
    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
422
                                       pressureCal,                      // ground pressure
423 424 425 426 427
                                       radioCal,                         // radio cal
                                       accelCal,                         // accel cal
                                       airspeedCal,                      // PX4: airspeed cal, ArduPilot: compass mot
                                       escCal);                          // esc cal
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
428 429
}

430
void UAS::stopCalibration(void)
431
{
432 433 434
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
435

436 437 438 439 440 441 442 443 444 445
    _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
446 447
}

448 449
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
450 451 452
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
453

454
   int actuatorCal = 0;
455 456 457 458

    switch (calType) {
        case StartBusConfigActuators:
            actuatorCal = 1;
459 460 461 462
        break;
        case EndBusConfigActuators:
            actuatorCal = 0;
        break;
463 464
    }

465 466 467 468
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_UAVCAN,          // command id
                             true,                              // showError
                             actuatorCal);                      // actuators
469 470 471 472
}

void UAS::stopBusConfig(void)
{
473 474 475
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
476

477 478 479 480
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_UAVCAN,          // command id
                             true,                              // showError
                             0);                                // cancel
481 482
}

483 484
/**
* Check if time is smaller than 40 years, assuming no system without Unix
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 528 529 530 531 532 533 534 535
* 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
536
* the precise time stamp of this measurement augmented to UNIX time, but will
537
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
538
* reason why one would want this, except for system setups where the onboard
539
* clock is not present or broken and datasets should be collected that are still
540
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
541 542 543 544 545 546 547 548 549
* 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
550 551 552 553
* 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
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 603 604 605 606 607 608 609 610
* 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;
}

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 665 666 667 668 669 670 671 672
* 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)
    {
673
        int imgColors = 255;
674 675 676 677 678

        // 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
679
        QByteArray tmpImage(header.toStdString().c_str(), header.length());
680 681 682 683 684 685 686 687 688 689 690 691
        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"))
        {
692
            qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
693 694 695 696 697 698 699 700 701 702 703 704
            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))
        {
705
            qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
706
            return QImage();
707 708
        }
    }
709

710 711
    // Restart statemachine
    imagePacketsArrived = 0;
712 713
    imagePackets = 0;
    imageRecBuffer.clear();
714 715 716 717 718
    return image;
}

void UAS::requestImage()
{
719 720 721
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
722

723
   qDebug() << "trying to get an image from the uas...";
724 725 726 727 728

    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
729 730 731 732 733 734 735
        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);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758
    }
}


/* MANAGEMENT */

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

759
//TODO update this to use the parameter manager / param data model instead
760
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue,  mavlink_param_union_t& paramUnion)
761 762 763
{
    int compId = msg.compid;

764
    QVariant paramValue;
765 766

    // Insert with correct type
767

768 769
    switch (rawValue.param_type) {
        case MAV_PARAM_TYPE_REAL32:
Don Gagne's avatar
Don Gagne committed
770
            paramValue = QVariant(paramUnion.param_float);
771
            break;
772

773
        case MAV_PARAM_TYPE_UINT8:
Don Gagne's avatar
Don Gagne committed
774
            paramValue = QVariant(paramUnion.param_uint8);
775
            break;
776

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

781 782 783 784
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant(paramUnion.param_uint16);
            break;

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

789
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
790
            paramValue = QVariant(paramUnion.param_uint32);
791
            break;
dogmaphobic's avatar
dogmaphobic committed
792

793
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
794
            paramValue = QVariant(paramUnion.param_int32);
795
            break;
796

797 798 799 800 801 802 803 804
        //-- 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

805 806
        default:
            qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
807
    }
808

809
    qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
810

811
    emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
812 813
}

814 815
/**
* Set the manual control commands.
816 817
* This can only be done if the system has manual inputs enabled and is armed.
*/
Gus Grubba's avatar
Gus Grubba committed
818
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
819
{
820
    if (!_vehicle || !_vehicle->priorityLink()) {
821 822
        return;
    }
823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956
    mavlink_message_t message;
    if (joystickMode == Vehicle::JoystickModeAttitude) {
        // send an external attitude setpoint command (rate control disabled)
        float attitudeQuaternion[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, attitudeQuaternion);
        uint8_t typeMask = 0x7; // disable rate control
        mavlink_msg_set_attitude_target_pack_chan(
            mavlink->getSystemId(),
            mavlink->getComponentId(),
            _vehicle->priorityLink()->mavlinkChannel(),
            &message,
            QGC::groundTimeUsecs(),
            this->uasId,
            0,
            typeMask,
            attitudeQuaternion,
            0,
            0,
            0,
            thrust);
    } else if (joystickMode == Vehicle::JoystickModePosition) {
        // Send the the local position setpoint (local pos sp external message)
        static float px = 0;
        static float py = 0;
        static float pz = 0;
        //XXX: find decent scaling
        px -= pitch;
        py += roll;
        pz -= 2.0f*(thrust-0.5);
        uint16_t typeMask = (1<<11)|(7<<6)|(7<<3); // select only POSITION control
        mavlink_msg_set_position_target_local_ned_pack_chan(
            mavlink->getSystemId(),
            mavlink->getComponentId(),
            _vehicle->priorityLink()->mavlinkChannel(),
            &message,
            QGC::groundTimeUsecs(),
            this->uasId,
            0,
            MAV_FRAME_LOCAL_NED,
            typeMask,
            px,
            py,
            pz,
            0,
            0,
            0,
            0,
            0,
            0,
            yaw,
            0);
    } else if (joystickMode == Vehicle::JoystickModeForce) {
        // Send the the force setpoint (local pos sp external message)
        float dcm[3][3];
        mavlink_euler_to_dcm(roll, pitch, yaw, dcm);
        const float fx = -dcm[0][2] * thrust;
        const float fy = -dcm[1][2] * thrust;
        const float fz = -dcm[2][2] * thrust;
        uint16_t typeMask = (3<<10)|(7<<3)|(7<<0)|(1<<9); // select only FORCE control (disable everything else)
        mavlink_msg_set_position_target_local_ned_pack_chan(
            mavlink->getSystemId(),
            mavlink->getComponentId(),
            _vehicle->priorityLink()->mavlinkChannel(),
            &message,
            QGC::groundTimeUsecs(),
            this->uasId,
            0,
            MAV_FRAME_LOCAL_NED,
            typeMask,
            0,
            0,
            0,
            0,
            0,
            0,
            fx,
            fy,
            fz,
            0,
            0);
    } else if (joystickMode == Vehicle::JoystickModeVelocity) {
        // Send the the local velocity setpoint (local pos sp external message)
        static float vx = 0;
        static float vy = 0;
        static float vz = 0;
        static float yawrate = 0;
        //XXX: find decent scaling
        vx -= pitch;
        vy += roll;
        vz -= 2.0f*(thrust-0.5);
        yawrate += yaw; //XXX: not sure what scale to apply here
        uint16_t typeMask = (1<<10)|(7<<6)|(7<<0); // select only VELOCITY control
        mavlink_msg_set_position_target_local_ned_pack_chan(
            mavlink->getSystemId(),
            mavlink->getComponentId(),
            _vehicle->priorityLink()->mavlinkChannel(),
            &message,
            QGC::groundTimeUsecs(),
            this->uasId,
            0,
            MAV_FRAME_LOCAL_NED,
            typeMask,
            0,
            0,
            0,
            vx,
            vy,
            vz,
            0,
            0,
            0,
            0,
            yawrate);
    } else if (joystickMode == Vehicle::JoystickModeRC) {
        // Store scaling values for all 3 axes
        static const float axesScaling = 1.0 * 1000.0;
        // Calculate the new commands for roll, pitch, yaw, and thrust
        const float newRollCommand = roll * axesScaling;
        // negate pitch value because pitch is negative for pitching forward but mavlink message argument is positive for forward
        const float newPitchCommand  = -pitch * axesScaling;
        const float newYawCommand    = yaw * axesScaling;
        const float newThrustCommand = thrust * axesScaling;
        // Send the MANUAL_COMMAND message
        mavlink_msg_manual_control_pack_chan(
            static_cast<uint8_t>(mavlink->getSystemId()),
            static_cast<uint8_t>(mavlink->getComponentId()),
            _vehicle->priorityLink()->mavlinkChannel(),
            &message,
            static_cast<uint8_t>(this->uasId),
            static_cast<int16_t>(newPitchCommand),
            static_cast<int16_t>(newRollCommand),
            static_cast<int16_t>(newThrustCommand),
            static_cast<int16_t>(newYawCommand),
            buttons);
957
    }
958
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
959 960
}

dogmaphobic's avatar
dogmaphobic committed
961
#ifndef __mobile__
962 963
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
964 965 966
    if (!_vehicle) {
        return;
    }
967
    const uint8_t base_mode = _vehicle->baseMode();
dogmaphobic's avatar
dogmaphobic committed
968

969
   // If system has manual inputs enabled and is armed
970
    if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
971 972
    {
        mavlink_message_t message;
973 974
        float q[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, q);
975

Lorenz Meier's avatar
Lorenz Meier committed
976 977
        float yawrate = 0.0f;

978
        // Do not control rates and throttle
979
        quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
980
        mask |= (1 << 6); // ignore throttle
981 982 983 984 985 986 987
        mavlink_msg_set_attitude_target_pack_chan(mavlink->getSystemId(),
                                                  mavlink->getComponentId(),
                                                  _vehicle->priorityLink()->mavlinkChannel(),
                                                  &message,
                                                  QGC::groundTimeMilliseconds(), this->uasId, _vehicle->defaultComponentId(),
                                                  mask, q, 0, 0, 0, 0);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
Lorenz Meier's avatar
Lorenz Meier committed
988
        quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
989
            (1 << 6) | (1 << 7) | (1 << 8);
990 991 992 993 994
        mavlink_msg_set_position_target_local_ned_pack_chan(mavlink->getSystemId(), mavlink->getComponentId(),
                                                            _vehicle->priorityLink()->mavlinkChannel(),
                                                            &message, QGC::groundTimeMilliseconds(), this->uasId, _vehicle->defaultComponentId(),
                                                            MAV_FRAME_LOCAL_NED, position_mask, x, y, z, 0, 0, 0, 0, 0, 0, yaw, yawrate);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
995
        qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
996 997 998 999 1000
    }
    else
    {
        qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first";
    }
1001
}
dogmaphobic's avatar
dogmaphobic committed
1002
#endif
1003

1004
/**
Jean Cyr's avatar
Jean Cyr committed
1005
* Order the robot to start receiver pairing
1006 1007 1008
*/
void UAS::pairRX(int rxType, int rxSubType)
{
1009 1010 1011 1012 1013 1014
    if (_vehicle) {
        _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                                 MAV_CMD_START_RX_PAIR,             // command id
                                 true,                              // showError
                                 rxType,
                                 rxSubType);
1015
    }
1016
}
dogmaphobic's avatar
dogmaphobic committed
1017

Don Gagne's avatar
Don Gagne committed
1018 1019
void UAS::shutdownVehicle(void)
{
1020
    _vehicle = nullptr;
Don Gagne's avatar
Don Gagne committed
1021
}