UAS.cc 79.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16
/*===================================================================
======================================================================*/

/**
 * @file
 *   @brief Represents one unmanned aerial vehicle
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

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

18 19
#include <cmath>
#include <qmath.h>
Don Gagne's avatar
Don Gagne committed
20

21 22 23
#include <limits>
#include <cstdlib>

24 25
#include "UAS.h"
#include "LinkInterface.h"
26
#include "HomePositionManager.h"
27 28 29 30 31
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
dogmaphobic's avatar
dogmaphobic committed
32
#ifndef __ios__
33
#include "SerialLink.h"
dogmaphobic's avatar
dogmaphobic committed
34
#endif
35
#include <Eigen/Geometry>
Don Gagne's avatar
Don Gagne committed
36
#include "FirmwarePluginManager.h"
37
#include "QGCLoggingCategory.h"
38
#include "Vehicle.h"
39
#include "Joystick.h"
40
#include "QGCApplication.h"
41

42
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
43

44 45
#define UAS_DEFAULT_BATTERY_WARNLEVEL 20

46 47
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
48
* by calling readSettings. This means the new UAS will have the same settings
49
* as the previous one created unless one calls deleteSettings in the code after
50
* creating the UAS.
51
*/
52

53
UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(),
54 55
    lipoFull(4.2f),
    lipoEmpty(3.5f),
56
    uasId(vehicle->id()),
57 58
    unknownPackets(),
    mavlink(protocol),
59 60 61
    receiveDropRate(0),
    sendDropRate(0),

62 63
    base_mode(0),
    custom_mode(0),
64 65
    status(-1),

66 67 68 69
    startVoltage(-1.0f),
    tickVoltage(10.5f),
    lastTickVoltageValue(13.0f),
    tickLowpassVoltage(12.0f),
70
    warnLevelPercent(UAS_DEFAULT_BATTERY_WARNLEVEL),
71
    currentVoltage(12.6f),
72
    lpVoltage(-1.0f),
dongfang's avatar
dongfang committed
73
    currentCurrent(0.4f),
74
    chargeLevel(-1),
75 76 77
    lowBattAlarm(false),

    startTime(QGC::groundTimeMilliseconds()),
78
    onboardTimeOffset(0),
79

80 81 82 83 84 85 86 87
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
88

89
    positionLock(false),
90 91
    isGlobalPositionKnown(false),

92 93 94
    latitude(0.0),
    longitude(0.0),
    altitudeAMSL(0.0),
95 96
    altitudeAMSLFT(0.0),
    altitudeWGS84(0.0),
97 98
    altitudeRelative(0.0),

99 100 101 102
    satRawHDOP(1e10f),
    satRawVDOP(1e10f),
    satRawCOG(0.0),

Don Gagne's avatar
Don Gagne committed
103 104 105 106 107
    globalEstimatorActive(false),

    latitude_gps(0.0),
    longitude_gps(0.0),
    altitude_gps(0.0),
108 109 110 111 112

    speedX(0.0),
    speedY(0.0),
    speedZ(0.0),

Don Gagne's avatar
Don Gagne committed
113 114
    airSpeed(std::numeric_limits<double>::quiet_NaN()),
    groundSpeed(std::numeric_limits<double>::quiet_NaN()),
115
#ifndef __mobile__
116
    fileManager(this, vehicle),
117
#endif
Don Gagne's avatar
Don Gagne committed
118

119 120 121
    attitudeKnown(false),
    attitudeStamped(false),
    lastAttitude(0),
122

123 124 125 126
    roll(0.0),
    pitch(0.0),
    yaw(0.0),

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

Don Gagne's avatar
Don Gagne committed
129 130 131
    blockHomePositionChanges(false),
    receivedMode(false),

132 133
    // Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
    // TODO: calibrate stand-still pixhawk variances
134
    xacc_var(0.6457f),
dogmaphobic's avatar
dogmaphobic committed
135
    yacc_var(0.7048f),
136
    zacc_var(0.97885f),
dogmaphobic's avatar
dogmaphobic committed
137 138 139
    rollspeed_var(0.8126f),
    pitchspeed_var(0.6145f),
    yawspeed_var(0.5852f),
140 141 142 143 144 145 146
    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),
147
    /*
148 149 150 151 152 153 154 155 156 157 158 159 160
    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),
161
    */
162

dogmaphobic's avatar
dogmaphobic committed
163
#ifndef __mobile__
164
    simulation(0),
dogmaphobic's avatar
dogmaphobic committed
165
#endif
166 167

    // The protected members.
168 169 170 171
    connectionLost(false),
    lastVoltageWarning(0),
    lastNonNullTime(0),
    onboardTimeOffsetInvalidCount(0),
172
    hilEnabled(false),
173 174
    sensorHil(false),
    lastSendTimeGPS(0),
175
    lastSendTimeSensors(0),
176
    lastSendTimeOpticalFlow(0),
177 178
    _vehicle(vehicle),
    _firmwarePluginManager(firmwarePluginManager)
179
{
dogmaphobic's avatar
dogmaphobic committed
180

181 182 183 184 185
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }
186

187
#ifndef __mobile__
188
    connect(mavlink, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), &fileManager, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
189
#endif
190

191
    color = UASInterface::getNextColor();
192 193
    connect(&statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
    statusTimeout.start(500);
194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213
}

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

/**
* Update the heartbeat.
*/
void UAS::updateState()
{
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
    if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
    {
        connectionLost = true;
214
        receivedMode = false;
215
        QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
216
        _say(audiostring.toLower(), GAudioOutput::AUDIO_SEVERITY_ALERT);
217 218 219 220 221 222 223 224 225 226 227 228
    }

    // Update connection loss time on each iteration
    if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
    {
        connectionLossTime = heartbeatInterval;
        emit heartbeatTimeout(true, heartbeatInterval/1000);
    }

    // Connection gained
    if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat))
    {
229
        QString audiostring = QString("Link regained to system %1").arg(this->getUASID());
230
        _say(audiostring.toLower(), GAudioOutput::AUDIO_SEVERITY_NOTICE);
231 232 233 234 235 236 237 238 239 240 241 242 243
        connectionLost = false;
        connectionLossTime = 0;
        emit heartbeatTimeout(false, 0);
    }

    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
    if (positionLock)
    {
        positionLock = false;
    }
}

244
void UAS::receiveMessage(mavlink_message_t message)
245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331
{
    if (!components.contains(message.compid))
    {
        QString componentName;

        switch (message.compid)
        {
        case MAV_COMP_ID_ALL:
        {
            componentName = "ANONYMOUS";
            break;
        }
        case MAV_COMP_ID_IMU:
        {
            componentName = "IMU #1";
            break;
        }
        case MAV_COMP_ID_CAMERA:
        {
            componentName = "CAMERA";
            break;
        }
        case MAV_COMP_ID_MISSIONPLANNER:
        {
            componentName = "MISSIONPLANNER";
            break;
        }
        }

        components.insert(message.compid, componentName);
    }

    //    qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;

    // 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
    if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
    {
        QString uasState;
        QString stateDescription;

        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
        if (componentID[message.msgid] == -1)
        {
            // Prefer the first component
            componentID[message.msgid] = message.compid;
        }
        else
        {
            // Got this message already
            if (componentID[message.msgid] != message.compid)
            {
                componentMulti[message.msgid] = true;
                wrongComponent = true;
            }
        }

        if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;


        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            lastHeartbeat = QGC::groundTimeUsecs();
            emit heartbeat(this);
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
332 333 334

            // 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
335
            quint64 time = getUnixTime();
336 337 338 339 340
            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);

341 342 343 344 345 346 347
            QString audiostring = QString("System %1").arg(uasId);
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;

348
            QString audiomodeText = _firmwarePluginManager->firmwarePluginForAutopilot((MAV_AUTOPILOT)state.autopilot, (MAV_TYPE)state.type)->flightMode(state.base_mode, state.custom_mode);
349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366

            if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);

                // Adjust for better audio
                if (uasState == QString("STANDBY")) uasState = QString("standing by");
                if (uasState == QString("EMERGENCY")) uasState = QString("emergency condition");
                if (uasState == QString("CRITICAL")) uasState = QString("critical condition");
                if (uasState == QString("SHUTDOWN")) uasState = QString("shutting down");

                stateAudio = uasState;
            }

367
            if (this->base_mode != state.base_mode || this->custom_mode != state.custom_mode)
368 369
            {
                modechanged = true;
370 371
                this->base_mode = state.base_mode;
                this->custom_mode = state.custom_mode;
dogmaphobic's avatar
dogmaphobic committed
372
                modeAudio = " is now in " + audiomodeText + " flight mode";
373 374
            }

375 376 377
            // We got the mode
            receivedMode = true;

378 379 380 381 382 383 384 385 386
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
387
                audiostring += modeAudio + stateAudio;
388 389 390 391
            }

            if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY))
            {
392
                _say(QString("Emergency for system %1").arg(this->getUASID()), GAudioOutput::AUDIO_SEVERITY_EMERGENCY);
393
                QTimer::singleShot(3000, qgcApp()->toolbox()->audioOutput(), SLOT(startEmergency()));
394 395 396
            }
            else if (modechanged || statechanged)
            {
397
                _say(audiostring.toLower());
398 399 400 401
            }
        }

            break;
402 403 404 405 406 407 408 409 410 411 412 413 414

        case MAVLINK_MSG_ID_BATTERY_STATUS:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_battery_status_t bat_status;
            mavlink_msg_battery_status_decode(&message, &bat_status);
            emit batteryConsumedChanged(this, (double)bat_status.current_consumed);
        }
            break;

415 416 417 418 419 420 421 422 423
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);

424
            // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
425
            quint64 time = getUnixTime();
426 427 428 429 430 431 432
            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);
433 434
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

435
            // Process CPU load.
436
            emit loadChanged(this,state.load/10.0f);
437
            emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
438

439
            if (state.voltage_battery > 0.0f && state.voltage_battery != UINT16_MAX) {
440 441
                // Battery charge/time remaining/voltage calculations
                currentVoltage = state.voltage_battery/1000.0f;
442 443
                filterVoltage(currentVoltage);
                tickLowpassVoltage = tickLowpassVoltage * 0.8f + 0.2f * currentVoltage;
444 445 446 447 448 449 450 451 452 453 454 455 456 457

                // We don't want to tick above the threshold
                if (tickLowpassVoltage > tickVoltage)
                {
                    lastTickVoltageValue = tickLowpassVoltage;
                }

                if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
                        /* warn if lower than treshold */
                        && (lpVoltage < tickVoltage)
                        /* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
                        && (currentVoltage > 3.3f)
                        /* warn only if current voltage is really still lower by a reasonable amount */
                        && ((currentVoltage - 0.2f) < tickVoltage)
458 459
                        /* warn only every 20 seconds */
                        && (QGC::groundTimeUsecs() - lastVoltageWarning) > 20000000)
460
                {
461
                    _say(QString("Low battery system %1: %2 volts").arg(getUASID()).arg(lpVoltage, 0, 'f', 1, QChar(' ')));
462 463 464 465 466 467 468 469
                    lastVoltageWarning = QGC::groundTimeUsecs();
                    lastTickVoltageValue = tickLowpassVoltage;
                }

                if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
                chargeLevel = state.battery_remaining;

                emit batteryChanged(this, lpVoltage, currentCurrent, getChargeLevel(), 0);
470 471
            }

472 473
            emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
            emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);
474

475 476 477
            // And if the battery current draw is measured, log that also.
            if (state.current_battery != -1)
            {
dongfang's avatar
dongfang committed
478 479
                currentCurrent = ((double)state.current_battery)/100.0f;
                emit valueChanged(uasId, name.arg("battery_current"), "A", currentCurrent, time);
480
            }
481 482

            // LOW BATTERY ALARM
483
            if (chargeLevel >= 0 && (getChargeLevel() < warnLevelPercent))
484
            {
dongfang's avatar
dongfang committed
485
                // An audio alarm. Does not generate any signals.
486 487 488 489 490 491 492 493 494 495 496 497 498 499
                startLowBattAlarm();
            }
            else
            {
                stopLowBattAlarm();
            }

            // control_sensors_enabled:
            // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
            emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11));
            emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12));
            emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13));
            emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14));

500 501 502 503 504 505 506 507 508 509 510
            // Trigger drop rate updates as needed. Here we convert the incoming
            // drop_rate_comm value from 1/100 of a percent in a uint16 to a true
            // percentage as a float. We also cap the incoming value at 100% as defined
            // by the MAVLink specifications.
            if (state.drop_rate_comm > 10000)
            {
                state.drop_rate_comm = 10000;
            }
            emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
            emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
        }
511 512 513 514 515 516 517 518 519 520 521 522
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
        {
            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);

            emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);

            if (!wrongComponent)
            {
                lastAttitude = time;
523 524 525
                setRoll(QGC::limitAngleToPMPIf(attitude.roll));
                setPitch(QGC::limitAngleToPMPIf(attitude.pitch));
                setYaw(QGC::limitAngleToPMPIf(attitude.yaw));
526

527 528 529 530 531 532 533 534 535 536 537 538 539 540 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
                attitudeKnown = true;
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
                emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
            }
        }
            break;
        case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
        {
            mavlink_attitude_quaternion_t attitude;
            mavlink_msg_attitude_quaternion_decode(&message, &attitude);
            quint64 time = getUnixReferenceTime(attitude.time_boot_ms);

            double a = attitude.q1;
            double b = attitude.q2;
            double c = attitude.q3;
            double d = attitude.q4;

            double aSq = a * a;
            double bSq = b * b;
            double cSq = c * c;
            double dSq = d * d;
            float dcm[3][3];
            dcm[0][0] = aSq + bSq - cSq - dSq;
            dcm[0][1] = 2.0 * (b * c - a * d);
            dcm[0][2] = 2.0 * (a * c + b * d);
            dcm[1][0] = 2.0 * (b * c + a * d);
            dcm[1][1] = aSq - bSq + cSq - dSq;
            dcm[1][2] = 2.0 * (c * d - a * b);
            dcm[2][0] = 2.0 * (b * d - a * c);
            dcm[2][1] = 2.0 * (a * b + c * d);
            dcm[2][2] = aSq - bSq - cSq + dSq;

            float phi, theta, psi;
            theta = asin(-dcm[2][0]);

            if (fabs(theta - M_PI_2) < 1.0e-3f) {
                phi = 0.0f;
                psi = (atan2(dcm[1][2] - dcm[0][1],
                        dcm[0][2] + dcm[1][1]) + phi);

            } else if (fabs(theta + M_PI_2) < 1.0e-3f) {
                phi = 0.0f;
                psi = atan2f(dcm[1][2] - dcm[0][1],
                          dcm[0][2] + dcm[1][1] - phi);

            } else {
                phi = atan2f(dcm[2][1], dcm[2][2]);
                psi = atan2f(dcm[1][0], dcm[0][0]);
            }

            emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(phi),
                                 QGC::limitAngleToPMPIf(theta),
                                 QGC::limitAngleToPMPIf(psi), time);

            if (!wrongComponent)
            {
                lastAttitude = time;
                setRoll(QGC::limitAngleToPMPIf(phi));
                setPitch(QGC::limitAngleToPMPIf(theta));
                setYaw(QGC::limitAngleToPMPIf(psi));
587 588

                attitudeKnown = true;
589
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
590
                emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610
            }
        }
            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;
        case MAVLINK_MSG_ID_VFR_HUD:
        {
            mavlink_vfr_hud_t hud;
            mavlink_msg_vfr_hud_decode(&message, &hud);
            quint64 time = getUnixTime();
            // Display updated values
            emit thrustChanged(this, hud.throttle/100.0);

            if (!attitudeKnown)
            {
611
                setYaw(QGC::limitAngleToPMPId((((double)hud.heading)/180.0)*M_PI));
612
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
613 614
            }

615 616 617 618 619
            setAltitudeAMSL(hud.alt);
            setGroundSpeed(hud.groundspeed);
            if (!isnan(hud.airspeed))
                setAirSpeed(hud.airspeed);
            speedZ = -hud.climb;
620
            emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
621
            emit speedChanged(this, groundSpeed, airSpeed, time);
622 623 624 625 626 627 628 629 630 631 632 633
        }
            break;
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
            //std::cerr << std::endl;
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
        {
            mavlink_local_position_ned_t pos;
            mavlink_msg_local_position_ned_decode(&message, &pos);
            quint64 time = getUnixTime(pos.time_boot_ms);

            if (!wrongComponent)
            {
634 635 636
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
637 638

                // Emit
639
                emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658

                positionLock = true;
            }
        }
            break;
        case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
        {
            mavlink_global_vision_position_estimate_t pos;
            mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
            quint64 time = getUnixTime(pos.usec);
            emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
        }
            break;
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
            //std::cerr << std::endl;
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
        {
            mavlink_global_position_int_t pos;
            mavlink_msg_global_position_int_decode(&message, &pos);
659

660
            quint64 time = getUnixTime();
661

662 663
            setLatitude(pos.lat/(double)1E7);
            setLongitude(pos.lon/(double)1E7);
664
            setAltitudeWGS84(pos.alt/1000.0);
665
            setAltitudeRelative(pos.relative_alt/1000.0);
666

667
            globalEstimatorActive = true;
668

669 670 671
            speedX = pos.vx/100.0;
            speedY = pos.vy/100.0;
            speedZ = pos.vz/100.0;
672

673 674
            emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), getAltitudeWGS84(), time);
            emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
675
            // We had some frame mess here, global and local axes were mixed.
676
            emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
677

678 679
            setGroundSpeed(qSqrt(speedX*speedX+speedY*speedY));
            emit speedChanged(this, groundSpeed, airSpeed, time);
680 681 682 683 684 685 686 687 688 689 690

            positionLock = true;
            isGlobalPositionKnown = true;
        }
            break;
        case MAVLINK_MSG_ID_GPS_RAW_INT:
        {
            mavlink_gps_raw_int_t pos;
            mavlink_msg_gps_raw_int_decode(&message, &pos);

            quint64 time = getUnixTime(pos.time_usec);
691

692 693 694 695
            // TODO: track localization state not only for gps but also for other loc. sources
            int loc_type = pos.fix_type;
            if (loc_type == 1)
            {
696
                loc_type = 0;
697
            }
698
            setSatelliteCount(pos.satellites_visible);
699 700 701

            if (pos.fix_type > 2)
            {
702 703
                positionLock = true;
                isGlobalPositionKnown = true;
704

705
                latitude_gps  = pos.lat/(double)1E7;
706
                longitude_gps = pos.lon/(double)1E7;
707
                altitude_gps  = pos.alt/1000.0;
708

709
                // If no GLOBAL_POSITION_INT messages ever received, use these raw GPS values instead.
710
                if (!globalEstimatorActive) {
711 712
                    setLatitude(latitude_gps);
                    setLongitude(longitude_gps);
713 714 715
                    setAltitudeWGS84(altitude_gps);
                    emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), getAltitudeWGS84(), time);
                    emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
716

717 718 719
                    float vel = pos.vel/100.0f;
                    // Smaller than threshold and not NaN
                    if ((vel < 1000000) && !isnan(vel) && !isinf(vel)) {
720
                        setGroundSpeed(vel);
721 722
                        emit speedChanged(this, groundSpeed, airSpeed, time);
                    } else {
723
                        emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_NOTICE, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
724
                    }
725 726
                }
            }
727

728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748
            double dtmp;
            //-- Raw GPS data
            dtmp = pos.eph == 0xFFFF ? 1e10f : pos.eph / 100.0;
            if(dtmp != satRawHDOP)
            {
                satRawHDOP = dtmp;
                emit satRawHDOPChanged(satRawHDOP);
            }
            dtmp = pos.epv == 0xFFFF ? 1e10f : pos.epv / 100.0;
            if(dtmp != satRawVDOP)
            {
                satRawVDOP = dtmp;
                emit satRawVDOPChanged(satRawVDOP);
            }
            dtmp = pos.cog == 0xFFFF ? 0.0 : pos.cog / 100.0;
            if(dtmp != satRawCOG)
            {
                satRawCOG = dtmp;
                emit satRawCOGChanged(satRawCOG);
            }

749 750 751
            // Emit this signal after the above signals. This way a trigger on gps lock signal which then asks for vehicle position
            // gets a good position.
            emit localizationChanged(this, loc_type);
752 753 754 755 756 757 758 759 760 761
        }
            break;
        case MAVLINK_MSG_ID_GPS_STATUS:
        {
            mavlink_gps_status_t pos;
            mavlink_msg_gps_status_decode(&message, &pos);
            for(int i = 0; i < (int)pos.satellites_visible; i++)
            {
                emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast<bool>(pos.satellite_used[i]));
            }
762
            setSatelliteCount(pos.satellites_visible);
763 764 765 766 767 768 769 770 771
        }
            break;
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
        {
            mavlink_gps_global_origin_t pos;
            mavlink_msg_gps_global_origin_decode(&message, &pos);
            emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
        }
            break;
772

773 774
        case MAVLINK_MSG_ID_PARAM_VALUE:
        {
775 776 777
            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);
778 779 780
            // 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);
781 782 783
            mavlink_param_union_t paramVal;
            paramVal.param_float = rawValue.param_value;
            paramVal.type = rawValue.param_type;
784

785 786
            processParamValueMsg(message, parameterName,rawValue,paramVal);
         }
787 788 789 790 791 792 793 794 795
            break;
        case MAVLINK_MSG_ID_COMMAND_ACK:
        {
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
            switch (ack.result)
            {
            case MAV_RESULT_ACCEPTED:
            {
796 797
                // Do not confirm each command positively, as it spams the console.
                // emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_INFO, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
798 799 800 801
            }
                break;
            case MAV_RESULT_TEMPORARILY_REJECTED:
            {
802
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_WARNING, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
803 804 805 806
            }
                break;
            case MAV_RESULT_DENIED:
            {
807
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Denied CMD: %1").arg(ack.command));
808 809 810 811
            }
                break;
            case MAV_RESULT_UNSUPPORTED:
            {
812
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_WARNING, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
813 814 815 816
            }
                break;
            case MAV_RESULT_FAILED:
            {
817
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Failed CMD: %1").arg(ack.command));
818 819 820 821
            }
                break;
            }
        }
822
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
823
        {
824 825 826 827
            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);
828
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
829
            emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, out.thrust, time);
830 831

            // For plotting emit roll sp, pitch sp and yaw sp values
832 833 834
            emit valueChanged(uasId, "roll sp", "rad", roll, time);
            emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
            emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
835 836
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
837

838
        case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
839 840 841 842 843
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
844 845 846 847
            mavlink_position_target_local_ned_t p;
            mavlink_msg_position_target_local_ned_decode(&message, &p);
            quint64 time = getUnixTimeFromMs(p.time_boot_ms);
            emit positionSetPointsChanged(uasId, p.x, p.y, p.z, 0/* XXX remove yaw and move it to attitude */, time);
848 849
        }
            break;
850
        case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
851
        {
852 853 854
            mavlink_set_position_target_local_ned_t p;
            mavlink_msg_set_position_target_local_ned_decode(&message, &p);
            emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, 0/* XXX remove yaw and move it to attitude */);
855 856 857 858 859
        }
            break;
        case MAVLINK_MSG_ID_STATUSTEXT:
        {
            QByteArray b;
860
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
861
            mavlink_msg_statustext_get_text(&message, b.data());
dogmaphobic's avatar
dogmaphobic committed
862

863 864
            // Ensure NUL-termination
            b[b.length()-1] = '\0';
865 866 867
            QString text = QString(b);
            int severity = mavlink_msg_statustext_get_severity(&message);

dogmaphobic's avatar
dogmaphobic committed
868 869
        // If the message is NOTIFY or higher severity, or starts with a '#',
        // then read it aloud.
870
            if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
871
            {
872
                text.remove("#");
873
                emit textMessageReceived(uasId, message.compid, severity, text);
874
                _say(text.toLower(), severity);
875 876 877 878 879 880 881
            }
            else
            {
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
        }
            break;
882

883 884 885 886 887 888 889 890 891 892 893 894
        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();
895 896
            imagePacketsArrived = 0;

897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912
        }
            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
913
                break;
914 915 916 917 918 919 920 921 922 923 924 925 926
            }

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

            ++imagePacketsArrived;

            // emit signal if all packets arrived
927
            if (imagePacketsArrived >= imagePackets)
928 929
            {
                // Restart statemachine
Don Gagne's avatar
Don Gagne committed
930 931
                imagePackets = 0;
                imagePacketsArrived = 0;
932 933 934 935 936 937
                emit imageReady(this);
            }
        }
            break;

        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
938 939 940 941
        {
            mavlink_nav_controller_output_t p;
            mavlink_msg_nav_controller_output_decode(&message,&p);
            setDistToWaypoint(p.wp_dist);
942 943
            setBearingToWaypoint(p.nav_bearing);
            emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error);
944
            emit NavigationControllerDataChanged(this, p.nav_roll, p.nav_pitch, p.nav_bearing, p.target_bearing, p.wp_dist);
945 946
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963

        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;

964 965 966 967 968 969
        default:
            break;
        }
    }
}

970
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
971
{
972 973 974
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
975

976 977 978 979 980
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
981
    int escCal = 0;
dogmaphobic's avatar
dogmaphobic committed
982

983 984 985 986 987 988 989 990 991 992 993 994 995
    switch (calType) {
        case StartCalibrationGyro:
            gyroCal = 1;
            break;
        case StartCalibrationMag:
            magCal = 1;
            break;
        case StartCalibrationAirspeed:
            airspeedCal = 1;
            break;
        case StartCalibrationRadio:
            radioCal = 1;
            break;
Don Gagne's avatar
Don Gagne committed
996 997 998
        case StartCalibrationCopyTrims:
            radioCal = 2;
            break;
999 1000 1001
        case StartCalibrationAccel:
            accelCal = 1;
            break;
1002 1003 1004
        case StartCalibrationLevel:
            accelCal = 2;
            break;
1005 1006 1007
        case StartCalibrationEsc:
            escCal = 1;
            break;
1008 1009 1010
        case StartCalibrationUavcanEsc:
            escCal = 2;
            break;
1011
    }
dogmaphobic's avatar
dogmaphobic committed
1012

1013
    mavlink_message_t msg;
1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
                                  0,                                // target component
                                  MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                  0,                                // 0=first transmission of command
                                  gyroCal,                          // gyro cal
                                  magCal,                           // mag cal
                                  0,                                // ground pressure
                                  radioCal,                         // radio cal
                                  accelCal,                         // accel cal
                                  airspeedCal,                      // airspeed cal
1027
                                  escCal);                          // esc cal
1028
    _vehicle->sendMessage(msg);
1029 1030
}

1031
void UAS::stopCalibration(void)
1032
{
1033 1034 1035
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1036

1037
    mavlink_message_t msg;
1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
                                  0,                                // target component
                                  MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                  0,                                // 0=first transmission of command
                                  0,                                // gyro cal
                                  0,                                // mag cal
                                  0,                                // ground pressure
                                  0,                                // radio cal
                                  0,                                // accel cal
                                  0,                                // airspeed cal
                                  0);                               // unused
1052
    _vehicle->sendMessage(msg);
1053 1054
}

1055 1056
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
1057 1058 1059
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1060

1061
   int actuatorCal = 0;
1062 1063 1064 1065

    switch (calType) {
        case StartBusConfigActuators:
            actuatorCal = 1;
1066 1067 1068 1069
        break;
        case EndBusConfigActuators:
            actuatorCal = 0;
        break;
1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086
    }

    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
                                  0,                                // target component
                                  MAV_CMD_PREFLIGHT_UAVCAN,    // command id
                                  0,                                // 0=first transmission of command
                                  actuatorCal,                      // actuators
                                  0,
                                  0,
                                  0,
                                  0,
                                  0,
                                  0);
1087
    _vehicle->sendMessage(msg);
1088 1089 1090 1091
}

void UAS::stopBusConfig(void)
{
1092 1093 1094
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1095

1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
                                  0,                                // target component
                                  MAV_CMD_PREFLIGHT_UAVCAN,    // command id
                                  0,                                // 0=first transmission of command
                                  0,
                                  0,
                                  0,
                                  0,
                                  0,
                                  0,
                                  0);
1111
    _vehicle->sendMessage(msg);
1112 1113
}

1114 1115
/**
* Check if time is smaller than 40 years, assuming no system without Unix
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166
* 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
1167
* the precise time stamp of this measurement augmented to UNIX time, but will
1168
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
1169
* reason why one would want this, except for system setups where the onboard
1170
* clock is not present or broken and datasets should be collected that are still
1171
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
1172 1173 1174 1175 1176 1177 1178 1179 1180
* 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
1181 1182 1183 1184
* 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
1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244
* 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;
}

/**
 * @param value battery voltage
 */
1245
float UAS::filterVoltage(float value)
1246
{
1247 1248 1249 1250 1251 1252
    if (lpVoltage < 0.0f) {
        lpVoltage = value;
    }

    lpVoltage = lpVoltage * 0.6f + value * 0.4f;
    return lpVoltage;
1253 1254
}

1255
/**
1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316
* 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)
    {
1317
        int imgColors = 255;
1318 1319 1320 1321 1322

        // 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
1323
        QByteArray tmpImage(header.toStdString().c_str(), header.length());
1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335
        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"))
        {
1336
            qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348
            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))
        {
1349
            qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
1350
            return QImage();
1351 1352
        }
    }
1353

1354 1355
    // Restart statemachine
    imagePacketsArrived = 0;
1356 1357
    imagePackets = 0;
    imageRecBuffer.clear();
1358 1359 1360 1361 1362
    return image;
}

void UAS::requestImage()
{
1363 1364 1365
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1366

1367
   qDebug() << "trying to get an image from the uas...";
1368 1369 1370 1371 1372

    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
1373
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, MAVLINK_DATA_STREAM_IMG_JPEG, 0, 0, 0, 0, 0, 50);
1374
        _vehicle->sendMessage(msg);
1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397
    }
}


/* MANAGEMENT */

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

1398
//TODO update this to use the parameter manager / param data model instead
1399
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue,  mavlink_param_union_t& paramUnion)
1400 1401 1402
{
    int compId = msg.compid;

1403
    QVariant paramValue;
1404 1405

    // Insert with correct type
1406

1407 1408
    switch (rawValue.param_type) {
        case MAV_PARAM_TYPE_REAL32:
Don Gagne's avatar
Don Gagne committed
1409
            paramValue = QVariant(paramUnion.param_float);
1410
            break;
1411

1412
        case MAV_PARAM_TYPE_UINT8:
Don Gagne's avatar
Don Gagne committed
1413
            paramValue = QVariant(paramUnion.param_uint8);
1414
            break;
1415

1416
        case MAV_PARAM_TYPE_INT8:
Don Gagne's avatar
Don Gagne committed
1417
            paramValue = QVariant(paramUnion.param_int8);
1418
            break;
1419

1420
        case MAV_PARAM_TYPE_INT16:
Don Gagne's avatar
Don Gagne committed
1421
            paramValue = QVariant(paramUnion.param_int16);
1422
            break;
1423

1424
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
1425
            paramValue = QVariant(paramUnion.param_uint32);
1426
            break;
dogmaphobic's avatar
dogmaphobic committed
1427

1428
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
1429
            paramValue = QVariant(paramUnion.param_int32);
1430
            break;
1431

1432 1433
        default:
            qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
1434
    }
1435

1436
    qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
1437

1438
    emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
1439 1440 1441 1442
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{
1443 1444 1445
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1446

1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460
    mavlink_message_t msg;
    mavlink_command_long_t cmd;
    cmd.command = (uint16_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
    cmd.target_system = uasId;
    cmd.target_component = component;
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1461
    _vehicle->sendMessage(msg);
1462 1463
}

1464 1465
/**
* Set the manual control commands.
1466 1467
* This can only be done if the system has manual inputs enabled and is armed.
*/
1468
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
1469
{
1470 1471 1472
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1473

1474
    // Store the previous manual commands
1475 1476 1477 1478 1479 1480
    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
1481

1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498
    // 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;
    } else if ((!isnan(roll) && roll != manualRollAngle) || (!isnan(pitch) && pitch != manualPitchAngle) ||
             (!isnan(yaw) && yaw != manualYawAngle) || (!isnan(thrust) && thrust != manualThrust) ||
             buttons != manualButtons) {
        sendCommand = true;

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

1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510
    // 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;

1511
        if (joystickMode == Vehicle::JoystickModeAttitude) {
1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528
            // 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(mavlink->getSystemId(),
                mavlink->getComponentId(),
                &message,
                QGC::groundTimeUsecs(),
                this->uasId,
                0,
                typeMask,
                attitudeQuaternion,
                0,
                0,
                0,
                thrust
                );
1529
        } else if (joystickMode == Vehicle::JoystickModePosition) {
1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558
            // 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(mavlink->getSystemId(),
                    mavlink->getComponentId(),
                    &message,
                    QGC::groundTimeUsecs(),
                    this->uasId,
                    0,
                    MAV_FRAME_LOCAL_NED,
                    typeMask,
                    px,
                    py,
                    pz,
                    0,
                    0,
                    0,
                    0,
                    0,
                    0,
                    yaw,
                    0
                    );
1559
        } else if (joystickMode == Vehicle::JoystickModeForce) {
1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586
            // 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(mavlink->getSystemId(),
                    mavlink->getComponentId(),
                    &message,
                    QGC::groundTimeUsecs(),
                    this->uasId,
                    0,
                    MAV_FRAME_LOCAL_NED,
                    typeMask,
                    0,
                    0,
                    0,
                    0,
                    0,
                    0,
                    fx,
                    fy,
                    fz,
                    0,
                    0
                    );
1587
        } else if (joystickMode == Vehicle::JoystickModeVelocity) {
1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618
            // 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(mavlink->getSystemId(),
                    mavlink->getComponentId(),
                    &message,
                    QGC::groundTimeUsecs(),
                    this->uasId,
                    0,
                    MAV_FRAME_LOCAL_NED,
                    typeMask,
                    0,
                    0,
                    0,
                    vx,
                    vy,
                    vz,
                    0,
                    0,
                    0,
                    0,
                    yawrate
                    );
1619
        } else if (joystickMode == Vehicle::JoystickModeRC) {
1620

1621 1622 1623 1624 1625 1626 1627 1628 1629
            // Save the new manual control inputs
            manualRollAngle = roll;
            manualPitchAngle = pitch;
            manualYawAngle = yaw;
            manualThrust = thrust;
            manualButtons = buttons;

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

1631 1632 1633 1634 1635 1636 1637
            // 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;

1638
            //qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
dogmaphobic's avatar
dogmaphobic committed
1639

1640 1641
            // Send the MANUAL_COMMAND message
            mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
1642
        }
1643

1644
        _vehicle->sendMessage(message);
1645 1646
        // Emit an update in control values to other UI elements, like the HSI display
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
1647 1648 1649
    }
}

dogmaphobic's avatar
dogmaphobic committed
1650
#ifndef __mobile__
1651 1652
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
1653 1654 1655
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1656

1657
   // If system has manual inputs enabled and is armed
1658
    if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
1659 1660
    {
        mavlink_message_t message;
1661 1662
        float q[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, q);
1663

Lorenz Meier's avatar
Lorenz Meier committed
1664 1665
        float yawrate = 0.0f;

1666
        // Do not control rates and throttle
1667
        quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
1668 1669 1670 1671
        mask |= (1 << 6); // ignore throttle
        mavlink_msg_set_attitude_target_pack(mavlink->getSystemId(), mavlink->getComponentId(),
                                             &message, QGC::groundTimeMilliseconds(), this->uasId, 0,
                                             mask, q, 0, 0, 0, 0);
1672
        _vehicle->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
1673
        quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
1674
            (1 << 6) | (1 << 7) | (1 << 8);
1675 1676
        mavlink_msg_set_position_target_local_ned_pack(mavlink->getSystemId(), mavlink->getComponentId(),
                                                       &message, QGC::groundTimeMilliseconds(), this->uasId, 0,
Lorenz Meier's avatar
Lorenz Meier committed
1677
                                                       MAV_FRAME_LOCAL_NED, position_mask, x, y, z, 0, 0, 0, 0, 0, 0, yaw, yawrate);
1678
        _vehicle->sendMessage(message);
1679
        qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
1680 1681 1682 1683 1684 1685 1686

        //emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
    }
    else
    {
        qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first";
    }
1687
}
dogmaphobic's avatar
dogmaphobic committed
1688
#endif
1689

1690
/**
Jean Cyr's avatar
Jean Cyr committed
1691
* Order the robot to start receiver pairing
1692 1693 1694
*/
void UAS::pairRX(int rxType, int rxSubType)
{
1695 1696 1697
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1698

1699 1700 1701
    mavlink_message_t msg;

    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_START_RX_PAIR, 0, rxType, rxSubType, 0, 0, 0, 0, 0);
1702
    _vehicle->sendMessage(msg);
1703 1704
}

1705 1706 1707
/**
* If enabled, connect the flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1708
#ifndef __mobile__
1709
void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration)
1710
{
1711
    Q_UNUSED(configuration);
1712

1713
    QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
1714
    if (!link) {
1715 1716 1717 1718 1719
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1720
        simulation = new QGCFlightGearLink(_vehicle, options);
1721
    }
1722

1723
    float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1724 1725 1726
    xacc_var = noise_scaler * 0.2914f;
    yacc_var = noise_scaler * 0.2914f;
    zacc_var = noise_scaler * 0.9577f;
1727 1728 1729
    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
1730 1731 1732
    xmag_var = noise_scaler * 0.0786f;
    ymag_var = noise_scaler * 0.0566f;
    zmag_var = noise_scaler * 0.0333f;
1733 1734 1735 1736
    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;
1737

1738 1739 1740
    // Connect Flight Gear Link
    link = dynamic_cast<QGCFlightGearLink*>(simulation);
    link->setStartupArguments(options);
Thomas Gubler's avatar
Thomas Gubler committed
1741
    link->sensorHilEnabled(sensorHil);
1742 1743
    // FIXME: this signal is not on the base hil configuration widget, only on the FG widget
    //QObject::connect(configuration, SIGNAL(barometerOffsetChanged(float)), link, SLOT(setBarometerOffset(float)));
1744 1745 1746 1747 1748 1749 1750 1751 1752
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1753
#endif
1754 1755 1756 1757

/**
* If enabled, connect the JSBSim link.
*/
dogmaphobic's avatar
dogmaphobic committed
1758
#ifndef __mobile__
1759 1760 1761
void UAS::enableHilJSBSim(bool enable, QString options)
{
    QGCJSBSimLink* link = dynamic_cast<QGCJSBSimLink*>(simulation);
1762
    if (!link) {
1763 1764 1765 1766 1767
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1768
        simulation = new QGCJSBSimLink(_vehicle, options);
1769 1770 1771 1772
    }
    // Connect Flight Gear Link
    link = dynamic_cast<QGCJSBSimLink*>(simulation);
    link->setStartupArguments(options);
1773 1774 1775 1776 1777 1778 1779 1780 1781
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1782
#endif
1783 1784 1785 1786

/**
* If enabled, connect the X-plane gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1787
#ifndef __mobile__
1788 1789 1790
void UAS::enableHilXPlane(bool enable)
{
    QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
1791
    if (!link) {
1792 1793 1794 1795
        if (simulation) {
            stopHil();
            delete simulation;
        }
1796
        simulation = new QGCXPlaneLink(_vehicle);
1797

1798
        float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1799 1800 1801
        xacc_var = noise_scaler * 0.2914f;
        yacc_var = noise_scaler * 0.2914f;
        zacc_var = noise_scaler * 0.9577f;
1802 1803 1804
        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
1805 1806 1807
        xmag_var = noise_scaler * 0.0786f;
        ymag_var = noise_scaler * 0.0566f;
        zmag_var = noise_scaler * 0.0333f;
1808 1809 1810 1811
        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;
1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822
    }
    // Connect X-Plane Link
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1823
#endif
1824

1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842
/**
* @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
1843
#ifndef __mobile__
1844 1845 1846 1847
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)
{
1848 1849 1850 1851
    Q_UNUSED(time_us);
    Q_UNUSED(xacc);
    Q_UNUSED(yacc);
    Q_UNUSED(zacc);
1852

1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872
        // 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
1873
#endif
1874

1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892
/**
* @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
1893
#ifndef __mobile__
1894
void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
Lorenz Meier's avatar
Lorenz Meier committed
1895
                       float pitchspeed, float yawspeed, double lat, double lon, double alt,
1896
                       float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
1897
{
1898 1899 1900
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1901

1902
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
1903
    {
1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921
        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;
1922
        mavlink_msg_hil_state_quaternion_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
1923 1924
                                   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);
1925
        _vehicle->sendMessage(msg);
1926 1927 1928 1929
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1930
        _vehicle->setHilMode(true);
1931 1932 1933
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1934
#endif
1935

1936 1937 1938
#ifndef __mobile__
float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
{
dogmaphobic's avatar
dogmaphobic committed
1939
    /* Calculate normally distributed variable noise with mean = 0 and variance = noise_var.  Calculated according to
1940 1941 1942 1943
    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
1944

1945 1946 1947 1948 1949 1950 1951 1952 1953 1954
    /*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()

1955
    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
1956

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

1961
    //Finally gaurd against any case where the noise is not real
1962
    if(std::isfinite(noise)) {
1963
            return truth_meas + noise;
1964
    } else {
1965 1966 1967 1968 1969
        return truth_meas;
    }
}
#endif

1970 1971 1972 1973
/*
* @param abs_pressure Absolute Pressure (hPa)
* @param diff_pressure Differential Pressure  (hPa)
*/
dogmaphobic's avatar
dogmaphobic committed
1974
#ifndef __mobile__
Lorenz Meier's avatar
Lorenz Meier committed
1975
void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
1976
                                    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
1977
{
1978 1979 1980
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1981

1982
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
Lorenz Meier's avatar
Lorenz Meier committed
1983
    {
1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996
        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);
1997

Lorenz Meier's avatar
Lorenz Meier committed
1998
        mavlink_message_t msg;
1999
        mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
2000
                                   time_us, xacc_corrupt, yacc_corrupt, zacc_corrupt, rollspeed_corrupt, pitchspeed_corrupt,
dogmaphobic's avatar
dogmaphobic committed
2001
                                    yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
2002
                                    diff_pressure_corrupt, pressure_alt_corrupt, temperature_corrupt, fields_changed);
2003
        _vehicle->sendMessage(msg);
2004
        lastSendTimeSensors = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
2005 2006 2007 2008
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
2009
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
2010 2011 2012
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
2013
#endif
Lorenz Meier's avatar
Lorenz Meier committed
2014

dogmaphobic's avatar
dogmaphobic committed
2015
#ifndef __mobile__
2016 2017 2018
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)
{
2019 2020 2021
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2022

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

Don Gagne's avatar
Don Gagne committed
2025 2026 2027 2028 2029 2030 2031
    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);
2032

2033 2034
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
    {
Don Gagne's avatar
Don Gagne committed
2035
#if 0
2036 2037
        mavlink_message_t msg;
        mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
Don Gagne's avatar
Don Gagne committed
2038
                                   time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
2039

2040
        _vehicle->sendMessage(msg);
2041
        lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
Don Gagne's avatar
Don Gagne committed
2042
#endif
2043 2044 2045 2046
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
2047
        _vehicle->setHilMode(true);
2048 2049 2050 2051
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }

}
dogmaphobic's avatar
dogmaphobic committed
2052
#endif
2053

dogmaphobic's avatar
dogmaphobic committed
2054
#ifndef __mobile__
2055
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
2056
{
2057 2058 2059
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2060

2061 2062 2063 2064
    // Only send at 10 Hz max rate
    if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
        return;

2065
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
Lorenz Meier's avatar
Lorenz Meier committed
2066
    {
Lorenz Meier's avatar
Lorenz Meier committed
2067 2068 2069
        float course = cog;
        // map to 0..2pi
        if (course < 0)
2070
            course += 2.0f * static_cast<float>(M_PI);
Lorenz Meier's avatar
Lorenz Meier committed
2071 2072 2073
        // scale from radians to degrees
        course = (course / M_PI) * 180.0f;

Lorenz Meier's avatar
Lorenz Meier committed
2074
        mavlink_message_t msg;
2075 2076
        mavlink_msg_hil_gps_pack(mavlink->getSystemId(), mavlink->getComponentId(), &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);
2077
        lastSendTimeGPS = QGC::groundTimeMilliseconds();
2078
        _vehicle->sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
2079 2080 2081 2082
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
2083
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
2084 2085 2086
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
2087
#endif
Lorenz Meier's avatar
Lorenz Meier committed
2088

2089 2090 2091
/**
* Connect flight gear link.
**/
dogmaphobic's avatar
dogmaphobic committed
2092
#ifndef __mobile__
2093 2094 2095 2096
void UAS::startHil()
{
    if (hilEnabled) return;
    hilEnabled = true;
2097
    sensorHil = false;
Don Gagne's avatar
Don Gagne committed
2098
    _vehicle->setHilMode(true);
2099
    qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
2100 2101
    // Connect HIL simulation link
    simulation->connectSimulation();
2102
}
dogmaphobic's avatar
dogmaphobic committed
2103
#endif
2104 2105 2106 2107

/**
* disable flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
2108
#ifndef __mobile__
2109 2110
void UAS::stopHil()
{
2111 2112 2113 2114 2115
   if (simulation && simulation->isConnected()) {
       simulation->disconnectSimulation();
       _vehicle->setHilMode(false);
       qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
   }
2116
    hilEnabled = false;
2117
    sensorHil = false;
2118
}
dogmaphobic's avatar
dogmaphobic committed
2119
#endif
2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140

/**
* @rerturn the map of the components
*/
QMap<int, QString> UAS::getComponents()
{
    return components;
}

/**
 * @return charge level in percent - 0 - 100
 */
float UAS::getChargeLevel()
{
    return chargeLevel;
}

void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
2141
        _say(tr("System %1 has low battery").arg(getUASID()));
2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
    if (lowBattAlarm)
    {
        lowBattAlarm = false;
    }
}
2153

2154
void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
2155
{
2156 2157 2158
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2159

2160 2161
    mavlink_message_t message;

2162 2163 2164 2165 2166 2167 2168 2169 2170 2171
    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];
        }
    }

2172 2173 2174 2175 2176
    mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &message,
                                  this->uasId,
                                  0,
2177
                                  param_id_cstr,
2178 2179
                                  -1,
                                  param_rc_channel_index,
2180 2181 2182 2183
                                  value0,
                                  scale,
                                  valueMin,
                                  valueMax);
2184
    _vehicle->sendMessage(message);
2185 2186
    qDebug() << "Mavlink message sent";
}
2187

2188 2189
void UAS::unsetRCToParameterMap()
{
2190 2191 2192
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2193

2194 2195
    char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};

2196 2197 2198 2199 2200 2201 2202
    for (int i = 0; i < 3; i++) {
        mavlink_message_t message;
        mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
                                      mavlink->getComponentId(),
                                      &message,
                                      this->uasId,
                                      0,
2203
                                      param_id_cstr,
2204 2205 2206
                                      -2,
                                      i,
                                      0.0f,
2207 2208
                                      0.0f,
                                      0.0f,
2209
                                      0.0f);
2210
        _vehicle->sendMessage(message);
Don Gagne's avatar
Don Gagne committed
2211 2212
    }
}
2213 2214 2215

void UAS::_say(const QString& text, int severity)
{
dogmaphobic's avatar
dogmaphobic committed
2216
    if (!qgcApp()->runningUnitTests())
2217
        qgcApp()->toolbox()->audioOutput()->say(text, severity);
2218
}
Don Gagne's avatar
Don Gagne committed
2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232

void UAS::shutdownVehicle(void)
{
#ifndef __mobile__
    stopHil();
    if (simulation) {
        // wait for the simulator to exit
        simulation->wait();
        simulation->disconnectSimulation();
        simulation->deleteLater();
    }
#endif
    _vehicle = NULL;
}