UAS.cc 51.1 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

dogmaphobic's avatar
dogmaphobic committed
107
#ifndef __mobile__
108
    simulation(0),
dogmaphobic's avatar
dogmaphobic committed
109
#endif
110 111

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

125
#ifndef __mobile__
126
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
127
#endif
128

129 130 131 132 133 134 135 136 137 138
}

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

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

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


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

            // 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
195
            quint64 time = getUnixTime();
196 197 198 199 200
            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);

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

            break;
206

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

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

227 228 229 230
            // 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);
        }
231 232 233 234 235 236 237 238
            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;
239

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

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

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

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

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

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

            ++imagePacketsArrived;

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

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

340 341 342 343 344 345
        default:
            break;
        }
    }
}

346
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
347
{
348 349 350
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
351

352 353 354 355 356
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
357
    int pressureCal = 0;
358
    int escCal = 0;
dogmaphobic's avatar
dogmaphobic committed
359

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

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

417
void UAS::stopCalibration(void)
418
{
419 420 421
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
422

423 424 425 426 427 428 429 430 431 432
    _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
433 434
}

435 436
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
437 438 439
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
440

441
   int actuatorCal = 0;
442 443 444 445

    switch (calType) {
        case StartBusConfigActuators:
            actuatorCal = 1;
446 447 448 449
        break;
        case EndBusConfigActuators:
            actuatorCal = 0;
        break;
450 451
    }

452 453 454 455
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_UAVCAN,          // command id
                             true,                              // showError
                             actuatorCal);                      // actuators
456 457 458 459
}

void UAS::stopBusConfig(void)
{
460 461 462
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
463

464 465 466 467
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                             MAV_CMD_PREFLIGHT_UAVCAN,          // command id
                             true,                              // showError
                             0);                                // cancel
468 469
}

470 471
/**
* Check if time is smaller than 40 years, assuming no system without Unix
472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522
* 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
523
* the precise time stamp of this measurement augmented to UNIX time, but will
524
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
525
* reason why one would want this, except for system setups where the onboard
526
* clock is not present or broken and datasets should be collected that are still
527
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
528 529 530 531 532 533 534 535 536
* 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
537 538 539 540
* 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
541 542 543 544 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
* 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;
}

598
/**
599 600 601 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
* 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)
    {
660
        int imgColors = 255;
661 662 663 664 665

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

697 698
    // Restart statemachine
    imagePacketsArrived = 0;
699 700
    imagePackets = 0;
    imageRecBuffer.clear();
701 702 703 704 705
    return image;
}

void UAS::requestImage()
{
706 707 708
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
709

710
   qDebug() << "trying to get an image from the uas...";
711 712 713 714 715

    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
716 717 718 719 720 721 722
        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);
723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745
    }
}


/* MANAGEMENT */

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

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

751
    QVariant paramValue;
752 753

    // Insert with correct type
754

755 756
    switch (rawValue.param_type) {
        case MAV_PARAM_TYPE_REAL32:
Don Gagne's avatar
Don Gagne committed
757
            paramValue = QVariant(paramUnion.param_float);
758
            break;
759

760
        case MAV_PARAM_TYPE_UINT8:
Don Gagne's avatar
Don Gagne committed
761
            paramValue = QVariant(paramUnion.param_uint8);
762
            break;
763

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

768 769 770 771
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant(paramUnion.param_uint16);
            break;

772
        case MAV_PARAM_TYPE_INT16:
Don Gagne's avatar
Don Gagne committed
773
            paramValue = QVariant(paramUnion.param_int16);
774
            break;
775

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

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

784 785 786 787 788 789 790 791
        //-- 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

792 793
        default:
            qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
794
    }
795

796
    qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
797

798
    emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
799 800
}

801 802
/**
* Set the manual control commands.
803 804
* This can only be done if the system has manual inputs enabled and is armed.
*/
Gus Grubba's avatar
Gus Grubba committed
805
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
806
{
807
    if (!_vehicle || !_vehicle->priorityLink()) {
808 809
        return;
    }
810 811 812 813 814 815 816 817 818 819 820 821 822 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
    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);
944
    }
945
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
946 947
}

dogmaphobic's avatar
dogmaphobic committed
948
#ifndef __mobile__
949 950
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
951 952 953
    if (!_vehicle) {
        return;
    }
954
    const uint8_t base_mode = _vehicle->baseMode();
dogmaphobic's avatar
dogmaphobic committed
955

956
   // If system has manual inputs enabled and is armed
957
    if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
958 959
    {
        mavlink_message_t message;
960 961
        float q[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, q);
962

Lorenz Meier's avatar
Lorenz Meier committed
963 964
        float yawrate = 0.0f;

965
        // Do not control rates and throttle
966
        quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
967
        mask |= (1 << 6); // ignore throttle
968 969 970 971 972 973 974
        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
975
        quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
976
            (1 << 6) | (1 << 7) | (1 << 8);
977 978 979 980 981
        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);
982
        qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
983 984 985 986 987
    }
    else
    {
        qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first";
    }
988
}
dogmaphobic's avatar
dogmaphobic committed
989
#endif
990

991
/**
Jean Cyr's avatar
Jean Cyr committed
992
* Order the robot to start receiver pairing
993 994 995
*/
void UAS::pairRX(int rxType, int rxSubType)
{
996 997 998 999 1000 1001
    if (_vehicle) {
        _vehicle->sendMavCommand(_vehicle->defaultComponentId(),    // target component
                                 MAV_CMD_START_RX_PAIR,             // command id
                                 true,                              // showError
                                 rxType,
                                 rxSubType);
1002
    }
1003
}
dogmaphobic's avatar
dogmaphobic committed
1004

1005 1006 1007
/**
* If enabled, connect the JSBSim link.
*/
dogmaphobic's avatar
dogmaphobic committed
1008
#ifndef __mobile__
1009 1010
void UAS::enableHilJSBSim(bool enable, QString options)
{
1011
    auto* link = qobject_cast<QGCJSBSimLink*>(simulation);
1012
    if (!link) {
1013 1014 1015 1016 1017
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1018
        simulation = new QGCJSBSimLink(_vehicle, options);
1019 1020
    }
    // Connect Flight Gear Link
1021
    link = qobject_cast<QGCJSBSimLink*>(simulation);
1022
    link->setStartupArguments(options);
1023 1024 1025 1026 1027 1028 1029 1030 1031
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1032
#endif
1033 1034 1035 1036

/**
* If enabled, connect the X-plane gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1037
#ifndef __mobile__
1038 1039
void UAS::enableHilXPlane(bool enable)
{
1040
    auto* link = qobject_cast<QGCXPlaneLink*>(simulation);
1041
    if (!link) {
1042 1043 1044 1045
        if (simulation) {
            stopHil();
            delete simulation;
        }
1046
        simulation = new QGCXPlaneLink(_vehicle);
1047

1048
        float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1049 1050 1051
        xacc_var = noise_scaler * 0.2914f;
        yacc_var = noise_scaler * 0.2914f;
        zacc_var = noise_scaler * 0.9577f;
1052 1053 1054
        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
1055 1056 1057
        xmag_var = noise_scaler * 0.0786f;
        ymag_var = noise_scaler * 0.0566f;
        zmag_var = noise_scaler * 0.0333f;
1058 1059 1060 1061
        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;
1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072
    }
    // Connect X-Plane Link
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1073
#endif
1074

1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092
/**
* @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
1093
#ifndef __mobile__
1094 1095 1096 1097
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)
{
1098 1099 1100 1101
    Q_UNUSED(time_us);
    Q_UNUSED(xacc);
    Q_UNUSED(yacc);
    Q_UNUSED(zacc);
1102

1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122
        // 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
1123
#endif
1124

1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142
/**
* @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
1143
#ifndef __mobile__
1144
void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
Lorenz Meier's avatar
Lorenz Meier committed
1145
                       float pitchspeed, float yawspeed, double lat, double lon, double alt,
1146
                       float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
1147
{
1148 1149 1150
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1151

1152
    if (_vehicle->hilMode())
1153
    {
1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171
        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;
1172 1173 1174 1175 1176 1177 1178
        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);
1179 1180 1181 1182
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1183
        _vehicle->setHilMode(true);
1184 1185 1186
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1187
#endif
1188

1189 1190 1191
#ifndef __mobile__
float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
{
dogmaphobic's avatar
dogmaphobic committed
1192
    /* Calculate normally distributed variable noise with mean = 0 and variance = noise_var.  Calculated according to
1193 1194 1195 1196
    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
1197

1198 1199 1200 1201 1202 1203 1204 1205 1206 1207
    /*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()

1208
    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
1209

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

Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
1214
    //Finally guard against any case where the noise is not real
1215
    if(std::isfinite(noise)) {
1216
            return truth_meas + noise;
1217
    } else {
1218 1219 1220 1221 1222
        return truth_meas;
    }
}
#endif

1223 1224 1225 1226
/*
* @param abs_pressure Absolute Pressure (hPa)
* @param diff_pressure Differential Pressure  (hPa)
*/
dogmaphobic's avatar
dogmaphobic committed
1227
#ifndef __mobile__
Lorenz Meier's avatar
Lorenz Meier committed
1228
void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
1229
                                    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
1230
{
1231 1232 1233
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1234

1235
    if (_vehicle->hilMode())
Lorenz Meier's avatar
Lorenz Meier committed
1236
    {
1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249
        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);
1250

Lorenz Meier's avatar
Lorenz Meier committed
1251
        mavlink_message_t msg;
1252 1253 1254 1255 1256 1257 1258 1259
        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);
1260
        lastSendTimeSensors = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
1261 1262 1263 1264
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1265
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
1266 1267 1268
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1269
#endif
Lorenz Meier's avatar
Lorenz Meier committed
1270

dogmaphobic's avatar
dogmaphobic committed
1271
#ifndef __mobile__
1272 1273 1274
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)
{
1275 1276 1277
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1278

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

Don Gagne's avatar
Don Gagne committed
1281 1282 1283 1284 1285 1286 1287
    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);
1288

1289
    if (_vehicle->hilMode())
1290
    {
Don Gagne's avatar
Don Gagne committed
1291
#if 0
1292
        mavlink_message_t msg;
1293 1294 1295 1296 1297
        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);
1298

1299
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
1300
        lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
Don Gagne's avatar
Don Gagne committed
1301
#endif
1302 1303 1304 1305
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1306
        _vehicle->setHilMode(true);
1307 1308 1309 1310
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }

}
dogmaphobic's avatar
dogmaphobic committed
1311
#endif
1312

dogmaphobic's avatar
dogmaphobic committed
1313
#ifndef __mobile__
1314
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
1315
{
1316 1317 1318
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1319

1320 1321 1322 1323
    // Only send at 10 Hz max rate
    if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
        return;

1324
    if (_vehicle->hilMode())
Lorenz Meier's avatar
Lorenz Meier committed
1325
    {
Lorenz Meier's avatar
Lorenz Meier committed
1326 1327 1328
        float course = cog;
        // map to 0..2pi
        if (course < 0)
1329
            course += 2.0f * static_cast<float>(M_PI);
Lorenz Meier's avatar
Lorenz Meier committed
1330 1331 1332
        // scale from radians to degrees
        course = (course / M_PI) * 180.0f;

Lorenz Meier's avatar
Lorenz Meier committed
1333
        mavlink_message_t msg;
1334 1335 1336 1337 1338
        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);
1339
        lastSendTimeGPS = QGC::groundTimeMilliseconds();
1340
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
Lorenz Meier's avatar
Lorenz Meier committed
1341 1342 1343 1344
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1345
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
1346 1347 1348
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1349
#endif
Lorenz Meier's avatar
Lorenz Meier committed
1350

1351 1352 1353
/**
* Connect flight gear link.
**/
dogmaphobic's avatar
dogmaphobic committed
1354
#ifndef __mobile__
1355 1356 1357 1358
void UAS::startHil()
{
    if (hilEnabled) return;
    hilEnabled = true;
1359
    sensorHil = false;
Don Gagne's avatar
Don Gagne committed
1360
    _vehicle->setHilMode(true);
1361
    qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
1362 1363
    // Connect HIL simulation link
    simulation->connectSimulation();
1364
}
dogmaphobic's avatar
dogmaphobic committed
1365
#endif
1366 1367 1368 1369

/**
* disable flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1370
#ifndef __mobile__
1371 1372
void UAS::stopHil()
{
1373 1374 1375 1376 1377
   if (simulation && simulation->isConnected()) {
       simulation->disconnectSimulation();
       _vehicle->setHilMode(false);
       qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
   }
1378
    hilEnabled = false;
1379
    sensorHil = false;
1380
}
dogmaphobic's avatar
dogmaphobic committed
1381
#endif
1382

1383
void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
1384
{
1385 1386 1387
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1388

1389 1390
    mavlink_message_t message;

1391 1392 1393 1394 1395 1396 1397 1398 1399 1400
    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];
        }
    }

1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414
    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
1415
    //qDebug() << "Mavlink message sent";
1416
}
1417

1418 1419
void UAS::unsetRCToParameterMap()
{
1420 1421 1422
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1423

1424 1425
    char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};

1426 1427
    for (int i = 0; i < 3; i++) {
        mavlink_message_t message;
1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441
        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
1442 1443
    }
}
1444

Don Gagne's avatar
Don Gagne committed
1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455
void UAS::shutdownVehicle(void)
{
#ifndef __mobile__
    stopHil();
    if (simulation) {
        // wait for the simulator to exit
        simulation->wait();
        simulation->disconnectSimulation();
        simulation->deleteLater();
    }
#endif
1456
    _vehicle = nullptr;
Don Gagne's avatar
Don Gagne committed
1457
}