UAS.cc 56.8 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * 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 62 63 64 65
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
66

67
#ifndef __mobile__
68
    fileManager(this, vehicle),
69
#endif
Don Gagne's avatar
Don Gagne committed
70

71 72 73
    attitudeKnown(false),
    attitudeStamped(false),
    lastAttitude(0),
74

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

Don Gagne's avatar
Don Gagne committed
77 78 79
    blockHomePositionChanges(false),
    receivedMode(false),

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

dogmaphobic's avatar
dogmaphobic committed
111
#ifndef __mobile__
112
    simulation(0),
dogmaphobic's avatar
dogmaphobic committed
113
#endif
114 115

    // The protected members.
116 117 118 119
    connectionLost(false),
    lastVoltageWarning(0),
    lastNonNullTime(0),
    onboardTimeOffsetInvalidCount(0),
120
    hilEnabled(false),
121 122
    sensorHil(false),
    lastSendTimeGPS(0),
123
    lastSendTimeSensors(0),
124
    lastSendTimeOpticalFlow(0),
125 126
    _vehicle(vehicle),
    _firmwarePluginManager(firmwarePluginManager)
127
{
dogmaphobic's avatar
dogmaphobic committed
128

129
#ifndef __mobile__
130
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
131
#endif
132

133 134 135 136 137 138 139 140 141 142
}

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

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

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


        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
196 197 198

            // 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
199
            quint64 time = getUnixTime();
200 201 202 203 204
            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);

205 206
            // We got the mode
            receivedMode = true;
207 208 209
        }

            break;
210

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

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

231 232 233 234
            // 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);
        }
235 236 237 238 239 240 241 242
            break;
        case MAVLINK_MSG_ID_HIL_CONTROLS:
        {
            mavlink_hil_controls_t hil;
            mavlink_msg_hil_controls_decode(&message, &hil);
            emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
        }
            break;
243

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

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

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

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

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

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

            ++imagePacketsArrived;

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

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

344 345 346 347 348 349
        default:
            break;
        }
    }
}

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

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

364
    switch (calType) {
365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385
    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;
386 387 388
    case StartCalibrationPressure:
        pressureCal = 1;
        break;
389 390 391 392 393 394 395 396 397
    case StartCalibrationEsc:
        escCal = 1;
        break;
    case StartCalibrationUavcanEsc:
        escCal = 2;
        break;
    case StartCalibrationCompassMot:
        airspeedCal = 1; // ArduPilot, bit of a hack
        break;
398
    }
dogmaphobic's avatar
dogmaphobic committed
399

400 401
    // 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.
402
    mavlink_message_t msg;
403 404 405 406 407 408 409 410 411 412
    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
413
                                       pressureCal,                      // ground pressure
414 415 416 417 418
                                       radioCal,                         // radio cal
                                       accelCal,                         // accel cal
                                       airspeedCal,                      // PX4: airspeed cal, ArduPilot: compass mot
                                       escCal);                          // esc cal
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
419 420
}

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

427 428 429 430 431 432 433 434 435 436
    _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
437 438
}

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

445
   int actuatorCal = 0;
446 447 448 449

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

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

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

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

474 475
/**
* Check if time is smaller than 40 years, assuming no system without Unix
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 522 523 524 525 526
* 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
527
* the precise time stamp of this measurement augmented to UNIX time, but will
528
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
529
* reason why one would want this, except for system setups where the onboard
530
* clock is not present or broken and datasets should be collected that are still
531
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
532 533 534 535 536 537 538 539 540
* 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
541 542 543 544
* 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
545 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
* 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;
}

602
/**
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
* 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)
    {
664
        int imgColors = 255;
665 666 667 668 669

        // 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
670
        QByteArray tmpImage(header.toStdString().c_str(), header.length());
671 672 673 674 675 676 677 678 679 680 681 682
        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"))
        {
683
            qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
684 685 686 687 688 689 690 691 692 693 694 695
            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))
        {
696
            qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
697
            return QImage();
698 699
        }
    }
700

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

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

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

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


/* MANAGEMENT */

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

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

755
    QVariant paramValue;
756 757

    // Insert with correct type
758

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

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

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

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

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

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

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

788 789 790 791 792 793 794 795
        //-- 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

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

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

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

805 806
/**
* Set the manual control commands.
807 808
* This can only be done if the system has manual inputs enabled and is armed.
*/
Gus Grubba's avatar
Gus Grubba committed
809
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
810
{
811 812 813
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
814

815 816 817 818
    if (!_vehicle->priorityLink()) {
        return;
    }

819
    // Store the previous manual commands
820 821 822 823 824 825
    static float manualRollAngle = 0.0;
    static float manualPitchAngle = 0.0;
    static float manualYawAngle = 0.0;
    static float manualThrust = 0.0;
    static quint16 manualButtons = 0;
    static quint8 countSinceLastTransmission = 0; // Track how many calls to this function have occurred since the last MAVLink transmission
826

827 828 829 830 831 832 833 834 835
    // Transmit the external setpoints only if they've changed OR if it's been a little bit since they were last transmit. To make sure there aren't issues with
    // response rate, we make sure that a message is transmit when the commands have changed, then one more time, and then switch to the lower transmission rate
    // if no command inputs have changed.

    // The default transmission rate is 25Hz, but when no inputs have changed it drops down to 5Hz.
    bool sendCommand = false;
    if (countSinceLastTransmission++ >= 5) {
        sendCommand = true;
        countSinceLastTransmission = 0;
836 837
    } else if ((!qIsNaN(roll) && roll != manualRollAngle) || (!qIsNaN(pitch) && pitch != manualPitchAngle) ||
             (!qIsNaN(yaw) && yaw != manualYawAngle) || (!qIsNaN(thrust) && thrust != manualThrust) ||
838 839 840 841 842 843
             buttons != manualButtons) {
        sendCommand = true;

        // Ensure that another message will be sent the next time this function is called
        countSinceLastTransmission = 10;
    }
844

845 846 847 848 849 850 851 852 853 854 855
    // Now if we should trigger an update, let's do that
    if (sendCommand) {
        // Save the new manual control inputs
        manualRollAngle = roll;
        manualPitchAngle = pitch;
        manualYawAngle = yaw;
        manualThrust = thrust;
        manualButtons = buttons;

        mavlink_message_t message;

856
        if (joystickMode == Vehicle::JoystickModeAttitude) {
857 858 859 860
            // 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
861 862 863 864 865 866 867 868 869 870 871 872 873
            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);
874
        } else if (joystickMode == Vehicle::JoystickModePosition) {
875 876 877 878 879 880 881 882 883
            // 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
884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903
            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);
904
        } else if (joystickMode == Vehicle::JoystickModeForce) {
905 906 907 908 909 910 911
            // 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)
912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931
            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);
932
        } else if (joystickMode == Vehicle::JoystickModeVelocity) {
933 934 935 936 937 938 939 940 941 942 943
            // 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
944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963
            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);
964
        } else if (joystickMode == Vehicle::JoystickModeRC) {
965

966
            // Save the new manual control inputs
Gus Grubba's avatar
Gus Grubba committed
967 968 969 970 971
            manualRollAngle     = roll;
            manualPitchAngle    = pitch;
            manualYawAngle      = yaw;
            manualThrust        = thrust;
            manualButtons       = buttons;
972 973 974

            // Store scaling values for all 3 axes
            const float axesScaling = 1.0 * 1000.0;
dogmaphobic's avatar
dogmaphobic committed
975

976 977 978
            // 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
Gus Grubba's avatar
Gus Grubba committed
979 980
            const float newPitchCommand  = -pitch * axesScaling;
            const float newYawCommand    = yaw * axesScaling;
981 982 983
            const float newThrustCommand = thrust * axesScaling;

            // Send the MANUAL_COMMAND message
Gus Grubba's avatar
Gus Grubba committed
984 985 986 987 988 989 990 991 992 993 994
            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);
995
        }
996

997
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
998 999 1000
    }
}

dogmaphobic's avatar
dogmaphobic committed
1001
#ifndef __mobile__
1002 1003
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
1004 1005 1006
    if (!_vehicle) {
        return;
    }
1007
    const uint8_t base_mode = _vehicle->baseMode();
dogmaphobic's avatar
dogmaphobic committed
1008

1009
   // If system has manual inputs enabled and is armed
1010
    if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
1011 1012
    {
        mavlink_message_t message;
1013 1014
        float q[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, q);
1015

Lorenz Meier's avatar
Lorenz Meier committed
1016 1017
        float yawrate = 0.0f;

1018
        // Do not control rates and throttle
1019
        quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
1020
        mask |= (1 << 6); // ignore throttle
1021 1022 1023 1024 1025 1026 1027
        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
1028
        quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
1029
            (1 << 6) | (1 << 7) | (1 << 8);
1030 1031 1032 1033 1034
        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);
1035
        qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
1036 1037 1038 1039 1040
    }
    else
    {
        qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first";
    }
1041
}
dogmaphobic's avatar
dogmaphobic committed
1042
#endif
1043

1044
/**
Jean Cyr's avatar
Jean Cyr committed
1045
* Order the robot to start receiver pairing
1046 1047 1048
*/
void UAS::pairRX(int rxType, int rxSubType)
{
1049 1050 1051 1052 1053 1054
    if (_vehicle) {
        _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                                 MAV_CMD_START_RX_PAIR,             // command id
                                 true,                              // showError
                                 rxType,
                                 rxSubType);
1055
    }
1056
}
dogmaphobic's avatar
dogmaphobic committed
1057

1058 1059 1060
/**
* If enabled, connect the JSBSim link.
*/
dogmaphobic's avatar
dogmaphobic committed
1061
#ifndef __mobile__
1062 1063
void UAS::enableHilJSBSim(bool enable, QString options)
{
1064
    auto* link = qobject_cast<QGCJSBSimLink*>(simulation);
1065
    if (!link) {
1066 1067 1068 1069 1070
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1071
        simulation = new QGCJSBSimLink(_vehicle, options);
1072 1073
    }
    // Connect Flight Gear Link
1074
    link = qobject_cast<QGCJSBSimLink*>(simulation);
1075
    link->setStartupArguments(options);
1076 1077 1078 1079 1080 1081 1082 1083 1084
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1085
#endif
1086 1087 1088 1089

/**
* If enabled, connect the X-plane gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1090
#ifndef __mobile__
1091 1092
void UAS::enableHilXPlane(bool enable)
{
1093
    auto* link = qobject_cast<QGCXPlaneLink*>(simulation);
1094
    if (!link) {
1095 1096 1097 1098
        if (simulation) {
            stopHil();
            delete simulation;
        }
1099
        simulation = new QGCXPlaneLink(_vehicle);
1100

1101
        float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1102 1103 1104
        xacc_var = noise_scaler * 0.2914f;
        yacc_var = noise_scaler * 0.2914f;
        zacc_var = noise_scaler * 0.9577f;
1105 1106 1107
        rollspeed_var = noise_scaler * 0.8126f;
        pitchspeed_var = noise_scaler * 0.6145f;
        yawspeed_var = noise_scaler * 0.5852f;
Lorenz Meier's avatar
Lorenz Meier committed
1108 1109 1110
        xmag_var = noise_scaler * 0.0786f;
        ymag_var = noise_scaler * 0.0566f;
        zmag_var = noise_scaler * 0.0333f;
1111 1112 1113 1114
        abs_pressure_var = noise_scaler * 0.5604f;
        diff_pressure_var = noise_scaler * 0.2604f;
        pressure_alt_var = noise_scaler * 0.5604f;
        temperature_var = noise_scaler * 0.7290f;
1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125
    }
    // Connect X-Plane Link
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1126
#endif
1127

1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145
/**
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
dogmaphobic's avatar
dogmaphobic committed
1146
#ifndef __mobile__
1147 1148 1149 1150
void UAS::sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
                       float pitchspeed, float yawspeed, double lat, double lon, double alt,
                       float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
{
1151 1152 1153 1154
    Q_UNUSED(time_us);
    Q_UNUSED(xacc);
    Q_UNUSED(yacc);
    Q_UNUSED(zacc);
1155

1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175
        // Emit attitude for cross-check
        emit valueChanged(uasId, "roll sim", "rad", roll, getUnixTime());
        emit valueChanged(uasId, "pitch sim", "rad", pitch, getUnixTime());
        emit valueChanged(uasId, "yaw sim", "rad", yaw, getUnixTime());

        emit valueChanged(uasId, "roll rate sim", "rad/s", rollspeed, getUnixTime());
        emit valueChanged(uasId, "pitch rate sim", "rad/s", pitchspeed, getUnixTime());
        emit valueChanged(uasId, "yaw rate sim", "rad/s", yawspeed, getUnixTime());

        emit valueChanged(uasId, "lat sim", "deg", lat*1e7, getUnixTime());
        emit valueChanged(uasId, "lon sim", "deg", lon*1e7, getUnixTime());
        emit valueChanged(uasId, "alt sim", "deg", alt*1e3, getUnixTime());

        emit valueChanged(uasId, "vx sim", "m/s", vx*1e2, getUnixTime());
        emit valueChanged(uasId, "vy sim", "m/s", vy*1e2, getUnixTime());
        emit valueChanged(uasId, "vz sim", "m/s", vz*1e2, getUnixTime());

        emit valueChanged(uasId, "IAS sim", "m/s", ind_airspeed, getUnixTime());
        emit valueChanged(uasId, "TAS sim", "m/s", true_airspeed, getUnixTime());
}
dogmaphobic's avatar
dogmaphobic committed
1176
#endif
1177

1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195
/**
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
dogmaphobic's avatar
dogmaphobic committed
1196
#ifndef __mobile__
1197
void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
Lorenz Meier's avatar
Lorenz Meier committed
1198
                       float pitchspeed, float yawspeed, double lat, double lon, double alt,
1199
                       float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
1200
{
1201 1202 1203
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1204

1205
    if (_vehicle->hilMode())
1206
    {
1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224
        float q[4];

        double cosPhi_2 = cos(double(roll) / 2.0);
        double sinPhi_2 = sin(double(roll) / 2.0);
        double cosTheta_2 = cos(double(pitch) / 2.0);
        double sinTheta_2 = sin(double(pitch) / 2.0);
        double cosPsi_2 = cos(double(yaw) / 2.0);
        double sinPsi_2 = sin(double(yaw) / 2.0);
        q[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
                sinPhi_2 * sinTheta_2 * sinPsi_2);
        q[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
                cosPhi_2 * sinTheta_2 * sinPsi_2);
        q[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
                sinPhi_2 * cosTheta_2 * sinPsi_2);
        q[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
                sinPhi_2 * sinTheta_2 * cosPsi_2);

        mavlink_message_t msg;
1225 1226 1227 1228 1229 1230 1231
        mavlink_msg_hil_state_quaternion_pack_chan(mavlink->getSystemId(),
                                                   mavlink->getComponentId(),
                                                   _vehicle->priorityLink()->mavlinkChannel(),
                                                   &msg,
                                                   time_us, q, rollspeed, pitchspeed, yawspeed,
                                                   lat*1e7f, lon*1e7f, alt*1000, vx*100, vy*100, vz*100, ind_airspeed*100, true_airspeed*100, xacc*1000/9.81, yacc*1000/9.81, zacc*1000/9.81);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
1232 1233 1234 1235
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1236
        _vehicle->setHilMode(true);
1237 1238 1239
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1240
#endif
1241

1242 1243 1244
#ifndef __mobile__
float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
{
dogmaphobic's avatar
dogmaphobic committed
1245
    /* Calculate normally distributed variable noise with mean = 0 and variance = noise_var.  Calculated according to
1246 1247 1248 1249
    Box-Muller transform */
    static const float epsilon = std::numeric_limits<float>::min(); //used to ensure non-zero uniform numbers
    static float z0; //calculated normal distribution random variables with mu = 0, var = 1;
    float u1, u2;        //random variables generated from c++ rand();
dogmaphobic's avatar
dogmaphobic committed
1250

1251 1252 1253 1254 1255 1256 1257 1258 1259 1260
    /*Generate random variables in range (0 1] */
    do
    {
        //TODO seed rand() with srand(time) but srand(time should be called once on startup)
        //currently this will generate repeatable random noise
        u1 = rand() * (1.0 / RAND_MAX);
        u2 = rand() * (1.0 / RAND_MAX);
    }
    while ( u1 <= epsilon );  //Have a catch to ensure non-zero for log()

1261
    z0 = sqrt(-2.0 * log(u1)) * cos(2.0f * M_PI * u2); //calculate normally distributed variable with mu = 0, var = 1
dogmaphobic's avatar
dogmaphobic committed
1262

1263 1264
    //TODO add bias term that changes randomly to simulate accelerometer and gyro bias the exf should handle these
    //as well
1265
    float noise = z0 * sqrt(noise_var); //calculate normally distributed variable with mu = 0, std = var^2
dogmaphobic's avatar
dogmaphobic committed
1266

Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
1267
    //Finally guard against any case where the noise is not real
1268
    if(std::isfinite(noise)) {
1269
            return truth_meas + noise;
1270
    } else {
1271 1272 1273 1274 1275
        return truth_meas;
    }
}
#endif

1276 1277 1278 1279
/*
* @param abs_pressure Absolute Pressure (hPa)
* @param diff_pressure Differential Pressure  (hPa)
*/
dogmaphobic's avatar
dogmaphobic committed
1280
#ifndef __mobile__
Lorenz Meier's avatar
Lorenz Meier committed
1281
void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
1282
                                    float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed)
Lorenz Meier's avatar
Lorenz Meier committed
1283
{
1284 1285 1286
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1287

1288
    if (_vehicle->hilMode())
Lorenz Meier's avatar
Lorenz Meier committed
1289
    {
1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302
        float xacc_corrupt = addZeroMeanNoise(xacc, xacc_var);
        float yacc_corrupt = addZeroMeanNoise(yacc, yacc_var);
        float zacc_corrupt = addZeroMeanNoise(zacc, zacc_var);
        float rollspeed_corrupt = addZeroMeanNoise(rollspeed,rollspeed_var);
        float pitchspeed_corrupt = addZeroMeanNoise(pitchspeed,pitchspeed_var);
        float yawspeed_corrupt = addZeroMeanNoise(yawspeed,yawspeed_var);
        float xmag_corrupt = addZeroMeanNoise(xmag, xmag_var);
        float ymag_corrupt = addZeroMeanNoise(ymag, ymag_var);
        float zmag_corrupt = addZeroMeanNoise(zmag, zmag_var);
        float abs_pressure_corrupt = addZeroMeanNoise(abs_pressure,abs_pressure_var);
        float diff_pressure_corrupt = addZeroMeanNoise(diff_pressure, diff_pressure_var);
        float pressure_alt_corrupt = addZeroMeanNoise(pressure_alt, pressure_alt_var);
        float temperature_corrupt = addZeroMeanNoise(temperature,temperature_var);
1303

Lorenz Meier's avatar
Lorenz Meier committed
1304
        mavlink_message_t msg;
1305 1306 1307 1308 1309 1310 1311 1312
        mavlink_msg_hil_sensor_pack_chan(mavlink->getSystemId(),
                                         mavlink->getComponentId(),
                                         _vehicle->priorityLink()->mavlinkChannel(),
                                         &msg,
                                         time_us, xacc_corrupt, yacc_corrupt, zacc_corrupt, rollspeed_corrupt, pitchspeed_corrupt,
                                         yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
                                         diff_pressure_corrupt, pressure_alt_corrupt, temperature_corrupt, fields_changed);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
1313
        lastSendTimeSensors = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
1314 1315 1316 1317
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1318
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
1319 1320 1321
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1322
#endif
Lorenz Meier's avatar
Lorenz Meier committed
1323

dogmaphobic's avatar
dogmaphobic committed
1324
#ifndef __mobile__
1325 1326 1327
void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
                    float flow_comp_m_y, quint8 quality, float ground_distance)
{
1328 1329 1330
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1331

Don Gagne's avatar
Don Gagne committed
1332
    // FIXME: This needs to be updated for new mavlink_msg_hil_optical_flow_pack api
1333

Don Gagne's avatar
Don Gagne committed
1334 1335 1336 1337 1338 1339 1340
    Q_UNUSED(time_us);
    Q_UNUSED(flow_x);
    Q_UNUSED(flow_y);
    Q_UNUSED(flow_comp_m_x);
    Q_UNUSED(flow_comp_m_y);
    Q_UNUSED(quality);
    Q_UNUSED(ground_distance);
1341

1342
    if (_vehicle->hilMode())
1343
    {
Don Gagne's avatar
Don Gagne committed
1344
#if 0
1345
        mavlink_message_t msg;
1346 1347 1348 1349 1350
        mavlink_msg_hil_optical_flow_pack_chan(mavlink->getSystemId(),
                                               mavlink->getComponentId(),
                                               _vehicle->priorityLink()->mavlinkChannel(),
                                               &msg,
                                               time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
1351

1352
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
1353
        lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
Don Gagne's avatar
Don Gagne committed
1354
#endif
1355 1356 1357 1358
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1359
        _vehicle->setHilMode(true);
1360 1361 1362 1363
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }

}
dogmaphobic's avatar
dogmaphobic committed
1364
#endif
1365

dogmaphobic's avatar
dogmaphobic committed
1366
#ifndef __mobile__
1367
void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites)
Lorenz Meier's avatar
Lorenz Meier committed
1368
{
1369 1370 1371
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1372

1373 1374 1375 1376
    // Only send at 10 Hz max rate
    if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
        return;

1377
    if (_vehicle->hilMode())
Lorenz Meier's avatar
Lorenz Meier committed
1378
    {
Lorenz Meier's avatar
Lorenz Meier committed
1379 1380 1381
        float course = cog;
        // map to 0..2pi
        if (course < 0)
1382
            course += 2.0f * static_cast<float>(M_PI);
Lorenz Meier's avatar
Lorenz Meier committed
1383 1384 1385
        // scale from radians to degrees
        course = (course / M_PI) * 180.0f;

Lorenz Meier's avatar
Lorenz Meier committed
1386
        mavlink_message_t msg;
1387 1388 1389 1390 1391
        mavlink_msg_hil_gps_pack_chan(mavlink->getSystemId(),
                                      mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      time_us, fix_type, lat*1e7, lon*1e7, alt*1e3, eph*1e2, epv*1e2, vel*1e2, vn*1e2, ve*1e2, vd*1e2, course*1e2, satellites);
1392
        lastSendTimeGPS = QGC::groundTimeMilliseconds();
1393
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
Lorenz Meier's avatar
Lorenz Meier committed
1394 1395 1396 1397
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1398
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
1399 1400 1401
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1402
#endif
Lorenz Meier's avatar
Lorenz Meier committed
1403

1404 1405 1406
/**
* Connect flight gear link.
**/
dogmaphobic's avatar
dogmaphobic committed
1407
#ifndef __mobile__
1408 1409 1410 1411
void UAS::startHil()
{
    if (hilEnabled) return;
    hilEnabled = true;
1412
    sensorHil = false;
Don Gagne's avatar
Don Gagne committed
1413
    _vehicle->setHilMode(true);
1414
    qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
1415 1416
    // Connect HIL simulation link
    simulation->connectSimulation();
1417
}
dogmaphobic's avatar
dogmaphobic committed
1418
#endif
1419 1420 1421 1422

/**
* disable flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1423
#ifndef __mobile__
1424 1425
void UAS::stopHil()
{
1426 1427 1428 1429 1430
   if (simulation && simulation->isConnected()) {
       simulation->disconnectSimulation();
       _vehicle->setHilMode(false);
       qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
   }
1431
    hilEnabled = false;
1432
    sensorHil = false;
1433
}
dogmaphobic's avatar
dogmaphobic committed
1434
#endif
1435

1436
void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
1437
{
1438 1439 1440
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1441

1442 1443
    mavlink_message_t message;

1444 1445 1446 1447 1448 1449 1450 1451 1452 1453
    char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
    // Copy string into buffer, ensuring not to exceed the buffer size
    for (unsigned int i = 0; i < sizeof(param_id_cstr); i++)
    {
        if ((int)i < param_id.length())
        {
            param_id_cstr[i] = param_id.toLatin1()[i];
        }
    }

1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467
    mavlink_msg_param_map_rc_pack_chan(mavlink->getSystemId(),
                                       mavlink->getComponentId(),
                                       _vehicle->priorityLink()->mavlinkChannel(),
                                       &message,
                                       this->uasId,
                                       _vehicle->defaultComponentId(),
                                       param_id_cstr,
                                       -1,
                                       param_rc_channel_index,
                                       value0,
                                       scale,
                                       valueMin,
                                       valueMax);
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
dogmaphobic's avatar
dogmaphobic committed
1468
    //qDebug() << "Mavlink message sent";
1469
}
1470

1471 1472
void UAS::unsetRCToParameterMap()
{
1473 1474 1475
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1476

1477 1478
    char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};

1479 1480
    for (int i = 0; i < 3; i++) {
        mavlink_message_t message;
1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494
        mavlink_msg_param_map_rc_pack_chan(mavlink->getSystemId(),
                                           mavlink->getComponentId(),
                                           _vehicle->priorityLink()->mavlinkChannel(),
                                           &message,
                                           this->uasId,
                                           _vehicle->defaultComponentId(),
                                           param_id_cstr,
                                           -2,
                                           i,
                                           0.0f,
                                           0.0f,
                                           0.0f,
                                           0.0f);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
Don Gagne's avatar
Don Gagne committed
1495 1496
    }
}
1497

Don Gagne's avatar
Don Gagne committed
1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508
void UAS::shutdownVehicle(void)
{
#ifndef __mobile__
    stopHil();
    if (simulation) {
        // wait for the simulator to exit
        simulation->wait();
        simulation->disconnectSimulation();
        simulation->deleteLater();
    }
#endif
1509
    _vehicle = nullptr;
Don Gagne's avatar
Don Gagne committed
1510
}