UAS.cc 79.9 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
}

/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
UAS::~UAS()
{
202
#ifndef __mobile__
203
    stopHil();
Don Gagne's avatar
Don Gagne committed
204 205 206
    if (simulation) {
        // wait for the simulator to exit
        simulation->wait();
207
        simulation->disconnectSimulation();
Don Gagne's avatar
Don Gagne committed
208 209
        simulation->deleteLater();
    }
210
#endif
211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230
}

/**
* @ 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;
231
        receivedMode = false;
232
        QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
233
        _say(audiostring.toLower(), GAudioOutput::AUDIO_SEVERITY_ALERT);
234 235 236 237 238 239 240 241 242 243 244 245
    }

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

    // Connection gained
    if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat))
    {
246
        QString audiostring = QString("Link regained to system %1").arg(this->getUASID());
247
        _say(audiostring.toLower(), GAudioOutput::AUDIO_SEVERITY_NOTICE);
248 249 250 251 252 253 254 255 256 257 258 259 260
        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;
    }
}

261
void UAS::receiveMessage(mavlink_message_t message)
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 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348
{
    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);
349 350 351

            // 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
352
            quint64 time = getUnixTime();
353 354 355 356 357
            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);

358 359 360 361 362 363 364
            QString audiostring = QString("System %1").arg(uasId);
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;

365
            QString audiomodeText = _firmwarePluginManager->firmwarePluginForAutopilot((MAV_AUTOPILOT)state.autopilot, (MAV_TYPE)state.type)->flightMode(state.base_mode, state.custom_mode);
366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383

            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;
            }

384
            if (this->base_mode != state.base_mode || this->custom_mode != state.custom_mode)
385 386
            {
                modechanged = true;
387 388
                this->base_mode = state.base_mode;
                this->custom_mode = state.custom_mode;
dogmaphobic's avatar
dogmaphobic committed
389
                modeAudio = " is now in " + audiomodeText + " flight mode";
390 391
            }

392 393 394
            // We got the mode
            receivedMode = true;

395 396 397 398 399 400 401 402 403
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
404
                audiostring += modeAudio + stateAudio;
405 406 407 408
            }

            if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY))
            {
409
                _say(QString("Emergency for system %1").arg(this->getUASID()), GAudioOutput::AUDIO_SEVERITY_EMERGENCY);
410
                QTimer::singleShot(3000, qgcApp()->toolbox()->audioOutput(), SLOT(startEmergency()));
411 412 413
            }
            else if (modechanged || statechanged)
            {
414
                _say(audiostring.toLower());
415 416 417 418
            }
        }

            break;
419 420 421 422 423 424 425 426 427 428 429 430 431

        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;

432 433 434 435 436 437 438 439 440
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);

441
            // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
442
            quint64 time = getUnixTime();
443 444 445 446 447 448 449
            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);
450 451
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

452
            // Process CPU load.
453
            emit loadChanged(this,state.load/10.0f);
454
            emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
455

456
            if (state.voltage_battery > 0.0f && state.voltage_battery != UINT16_MAX) {
457 458
                // Battery charge/time remaining/voltage calculations
                currentVoltage = state.voltage_battery/1000.0f;
459 460
                filterVoltage(currentVoltage);
                tickLowpassVoltage = tickLowpassVoltage * 0.8f + 0.2f * currentVoltage;
461 462 463 464 465 466 467 468 469 470 471 472 473 474

                // 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)
475 476
                        /* warn only every 20 seconds */
                        && (QGC::groundTimeUsecs() - lastVoltageWarning) > 20000000)
477
                {
478
                    _say(QString("Low battery system %1: %2 volts").arg(getUASID()).arg(lpVoltage, 0, 'f', 1, QChar(' ')));
479 480 481 482 483 484 485 486
                    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);
487 488
            }

489 490
            emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
            emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);
491

492 493 494
            // And if the battery current draw is measured, log that also.
            if (state.current_battery != -1)
            {
dongfang's avatar
dongfang committed
495 496
                currentCurrent = ((double)state.current_battery)/100.0f;
                emit valueChanged(uasId, name.arg("battery_current"), "A", currentCurrent, time);
497
            }
498 499

            // LOW BATTERY ALARM
500
            if (chargeLevel >= 0 && (getChargeLevel() < warnLevelPercent))
501
            {
dongfang's avatar
dongfang committed
502
                // An audio alarm. Does not generate any signals.
503 504 505 506 507 508 509 510 511 512 513 514 515 516
                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));

517 518 519 520 521 522 523 524 525 526 527
            // 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);
        }
528 529 530 531 532 533 534 535 536 537 538 539
            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;
540 541 542
                setRoll(QGC::limitAngleToPMPIf(attitude.roll));
                setPitch(QGC::limitAngleToPMPIf(attitude.pitch));
                setYaw(QGC::limitAngleToPMPIf(attitude.yaw));
543

544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
                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));
604 605

                attitudeKnown = true;
606
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
607
                emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627
            }
        }
            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)
            {
628
                setYaw(QGC::limitAngleToPMPId((((double)hud.heading)/180.0)*M_PI));
629
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
630 631
            }

632 633 634 635 636
            setAltitudeAMSL(hud.alt);
            setGroundSpeed(hud.groundspeed);
            if (!isnan(hud.airspeed))
                setAirSpeed(hud.airspeed);
            speedZ = -hud.climb;
637
            emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
638
            emit speedChanged(this, groundSpeed, airSpeed, time);
639 640 641 642 643 644 645 646 647 648 649 650
        }
            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)
            {
651 652 653
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
654 655

                // Emit
656
                emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675

                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);
676

677
            quint64 time = getUnixTime();
678

679 680
            setLatitude(pos.lat/(double)1E7);
            setLongitude(pos.lon/(double)1E7);
681
            setAltitudeWGS84(pos.alt/1000.0);
682
            setAltitudeRelative(pos.relative_alt/1000.0);
683

684
            globalEstimatorActive = true;
685

686 687 688
            speedX = pos.vx/100.0;
            speedY = pos.vy/100.0;
            speedZ = pos.vz/100.0;
689

690 691
            emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), getAltitudeWGS84(), time);
            emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
692
            // We had some frame mess here, global and local axes were mixed.
693
            emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
694

695 696
            setGroundSpeed(qSqrt(speedX*speedX+speedY*speedY));
            emit speedChanged(this, groundSpeed, airSpeed, time);
697 698 699 700 701 702 703 704 705 706 707

            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);
708

709 710 711 712
            // TODO: track localization state not only for gps but also for other loc. sources
            int loc_type = pos.fix_type;
            if (loc_type == 1)
            {
713
                loc_type = 0;
714
            }
715
            setSatelliteCount(pos.satellites_visible);
716 717 718

            if (pos.fix_type > 2)
            {
719 720
                positionLock = true;
                isGlobalPositionKnown = true;
721

722
                latitude_gps  = pos.lat/(double)1E7;
723
                longitude_gps = pos.lon/(double)1E7;
724
                altitude_gps  = pos.alt/1000.0;
725

726
                // If no GLOBAL_POSITION_INT messages ever received, use these raw GPS values instead.
727
                if (!globalEstimatorActive) {
728 729
                    setLatitude(latitude_gps);
                    setLongitude(longitude_gps);
730 731 732
                    setAltitudeWGS84(altitude_gps);
                    emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), getAltitudeWGS84(), time);
                    emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
733

734 735 736
                    float vel = pos.vel/100.0f;
                    // Smaller than threshold and not NaN
                    if ((vel < 1000000) && !isnan(vel) && !isinf(vel)) {
737
                        setGroundSpeed(vel);
738 739
                        emit speedChanged(this, groundSpeed, airSpeed, time);
                    } else {
740
                        emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_NOTICE, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
741
                    }
742 743
                }
            }
744

745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765
            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);
            }

766 767 768
            // 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);
769 770 771 772 773 774 775 776 777 778
        }
            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]));
            }
779
            setSatelliteCount(pos.satellites_visible);
780 781 782 783 784 785 786 787 788
        }
            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;
789

790 791
        case MAVLINK_MSG_ID_PARAM_VALUE:
        {
792 793 794
            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);
795 796 797
            // 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);
798 799 800
            mavlink_param_union_t paramVal;
            paramVal.param_float = rawValue.param_value;
            paramVal.type = rawValue.param_type;
801

802 803
            processParamValueMsg(message, parameterName,rawValue,paramVal);
         }
804 805 806 807 808 809 810 811 812
            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:
            {
813 814
                // 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));
815 816 817 818
            }
                break;
            case MAV_RESULT_TEMPORARILY_REJECTED:
            {
819
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_WARNING, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
820 821 822 823
            }
                break;
            case MAV_RESULT_DENIED:
            {
824
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Denied CMD: %1").arg(ack.command));
825 826 827 828
            }
                break;
            case MAV_RESULT_UNSUPPORTED:
            {
829
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_WARNING, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
830 831 832 833
            }
                break;
            case MAV_RESULT_FAILED:
            {
834
                emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Failed CMD: %1").arg(ack.command));
835 836 837 838
            }
                break;
            }
        }
839
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
840
        {
841 842 843 844
            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);
845
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
846
            emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, out.thrust, time);
847 848

            // For plotting emit roll sp, pitch sp and yaw sp values
849 850 851
            emit valueChanged(uasId, "roll sp", "rad", roll, time);
            emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
            emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
852 853
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
854

855
        case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
856 857 858 859 860
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
861 862 863 864
            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);
865 866
        }
            break;
867
        case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
868
        {
869 870 871
            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 */);
872 873 874 875 876
        }
            break;
        case MAVLINK_MSG_ID_STATUSTEXT:
        {
            QByteArray b;
877
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
878
            mavlink_msg_statustext_get_text(&message, b.data());
dogmaphobic's avatar
dogmaphobic committed
879

880 881
            // Ensure NUL-termination
            b[b.length()-1] = '\0';
882 883 884
            QString text = QString(b);
            int severity = mavlink_msg_statustext_get_severity(&message);

dogmaphobic's avatar
dogmaphobic committed
885 886
        // If the message is NOTIFY or higher severity, or starts with a '#',
        // then read it aloud.
887
            if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
888
            {
889
                text.remove("#");
890
                emit textMessageReceived(uasId, message.compid, severity, text);
891
                _say(text.toLower(), severity);
892 893 894 895 896 897 898
            }
            else
            {
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
        }
            break;
899

900 901 902 903 904 905 906 907 908 909 910 911
        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();
912 913
            imagePacketsArrived = 0;

914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929
        }
            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
930
                break;
931 932 933 934 935 936 937 938 939 940 941 942 943
            }

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

            ++imagePacketsArrived;

            // emit signal if all packets arrived
944
            if (imagePacketsArrived >= imagePackets)
945 946
            {
                // Restart statemachine
Don Gagne's avatar
Don Gagne committed
947 948
                imagePackets = 0;
                imagePacketsArrived = 0;
949 950 951 952 953 954
                emit imageReady(this);
            }
        }
            break;

        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
955 956 957 958
        {
            mavlink_nav_controller_output_t p;
            mavlink_msg_nav_controller_output_decode(&message,&p);
            setDistToWaypoint(p.wp_dist);
959 960
            setBearingToWaypoint(p.nav_bearing);
            emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error);
961
            emit NavigationControllerDataChanged(this, p.nav_roll, p.nav_pitch, p.nav_bearing, p.target_bearing, p.wp_dist);
962 963
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980

        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;

981 982 983 984 985 986
        default:
            break;
        }
    }
}

987
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
988
{
989 990 991
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
992

993 994 995 996 997
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
998
    int escCal = 0;
dogmaphobic's avatar
dogmaphobic committed
999

1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012
    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
1013 1014 1015
        case StartCalibrationCopyTrims:
            radioCal = 2;
            break;
1016 1017 1018
        case StartCalibrationAccel:
            accelCal = 1;
            break;
1019 1020 1021
        case StartCalibrationLevel:
            accelCal = 2;
            break;
1022 1023 1024
        case StartCalibrationEsc:
            escCal = 1;
            break;
1025 1026 1027
        case StartCalibrationUavcanEsc:
            escCal = 2;
            break;
1028
    }
dogmaphobic's avatar
dogmaphobic committed
1029

1030
    mavlink_message_t msg;
1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043
    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
1044
                                  escCal);                          // esc cal
1045
    _vehicle->sendMessage(msg);
1046 1047
}

1048
void UAS::stopCalibration(void)
1049
{
1050 1051 1052
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1053

1054
    mavlink_message_t msg;
1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068
    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
1069
    _vehicle->sendMessage(msg);
1070 1071
}

1072 1073
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
1074 1075 1076
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1077

1078
   int actuatorCal = 0;
1079 1080 1081 1082

    switch (calType) {
        case StartBusConfigActuators:
            actuatorCal = 1;
1083 1084 1085 1086
        break;
        case EndBusConfigActuators:
            actuatorCal = 0;
        break;
1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103
    }

    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);
1104
    _vehicle->sendMessage(msg);
1105 1106 1107 1108
}

void UAS::stopBusConfig(void)
{
1109 1110 1111
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1112

1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127
    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);
1128
    _vehicle->sendMessage(msg);
1129 1130
}

1131 1132
/**
* Check if time is smaller than 40 years, assuming no system without Unix
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 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183
* 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
1184
* the precise time stamp of this measurement augmented to UNIX time, but will
1185
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
1186
* reason why one would want this, except for system setups where the onboard
1187
* clock is not present or broken and datasets should be collected that are still
1188
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
1189 1190 1191 1192 1193 1194 1195 1196 1197
* 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
1198 1199 1200 1201
* 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
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 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261
* 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
 */
1262
float UAS::filterVoltage(float value)
1263
{
1264 1265 1266 1267 1268 1269
    if (lpVoltage < 0.0f) {
        lpVoltage = value;
    }

    lpVoltage = lpVoltage * 0.6f + value * 0.4f;
    return lpVoltage;
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 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333
* 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)
    {
1334
        int imgColors = 255;
1335 1336 1337 1338 1339

        // 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
1340
        QByteArray tmpImage(header.toStdString().c_str(), header.length());
1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352
        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"))
        {
1353
            qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365
            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))
        {
1366
            qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
1367
            return QImage();
1368 1369
        }
    }
1370

1371 1372
    // Restart statemachine
    imagePacketsArrived = 0;
1373 1374
    imagePackets = 0;
    imageRecBuffer.clear();
1375 1376 1377 1378 1379
    return image;
}

void UAS::requestImage()
{
1380 1381 1382
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1383

1384
   qDebug() << "trying to get an image from the uas...";
1385 1386 1387 1388 1389

    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
1390
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, MAVLINK_DATA_STREAM_IMG_JPEG, 0, 0, 0, 0, 0, 50);
1391
        _vehicle->sendMessage(msg);
1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414
    }
}


/* MANAGEMENT */

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

1415
//TODO update this to use the parameter manager / param data model instead
1416
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue,  mavlink_param_union_t& paramUnion)
1417 1418 1419
{
    int compId = msg.compid;

1420
    QVariant paramValue;
1421 1422

    // Insert with correct type
1423

1424 1425
    switch (rawValue.param_type) {
        case MAV_PARAM_TYPE_REAL32:
Don Gagne's avatar
Don Gagne committed
1426
            paramValue = QVariant(paramUnion.param_float);
1427
            break;
1428

1429
        case MAV_PARAM_TYPE_UINT8:
Don Gagne's avatar
Don Gagne committed
1430
            paramValue = QVariant(paramUnion.param_uint8);
1431
            break;
1432

1433
        case MAV_PARAM_TYPE_INT8:
Don Gagne's avatar
Don Gagne committed
1434
            paramValue = QVariant(paramUnion.param_int8);
1435
            break;
1436

1437
        case MAV_PARAM_TYPE_INT16:
Don Gagne's avatar
Don Gagne committed
1438
            paramValue = QVariant(paramUnion.param_int16);
1439
            break;
1440

1441
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
1442
            paramValue = QVariant(paramUnion.param_uint32);
1443
            break;
dogmaphobic's avatar
dogmaphobic committed
1444

1445
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
1446
            paramValue = QVariant(paramUnion.param_int32);
1447
            break;
1448

1449 1450
        default:
            qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
1451
    }
1452

1453
    qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
1454

1455
    emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
1456 1457 1458 1459
}

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

1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477
    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);
1478
    _vehicle->sendMessage(msg);
1479 1480
}

1481 1482
/**
* Set the manual control commands.
1483 1484
* This can only be done if the system has manual inputs enabled and is armed.
*/
1485
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
1486
{
1487 1488 1489
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1490

1491
    // Store the previous manual commands
1492 1493 1494 1495 1496 1497
    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
1498

1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515
    // 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;
    }
1516

1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527
    // 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;

1528
        if (joystickMode == Vehicle::JoystickModeAttitude) {
1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545
            // 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
                );
1546
        } else if (joystickMode == Vehicle::JoystickModePosition) {
1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575
            // 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
                    );
1576
        } else if (joystickMode == Vehicle::JoystickModeForce) {
1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603
            // 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
                    );
1604
        } else if (joystickMode == Vehicle::JoystickModeVelocity) {
1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635
            // 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
                    );
1636
        } else if (joystickMode == Vehicle::JoystickModeRC) {
1637

1638 1639 1640 1641 1642 1643 1644 1645 1646
            // 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
1647

1648 1649 1650 1651 1652 1653 1654
            // 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;

1655
            //qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
dogmaphobic's avatar
dogmaphobic committed
1656

1657 1658
            // Send the MANUAL_COMMAND message
            mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
1659
        }
1660

1661
        _vehicle->sendMessage(message);
1662 1663
        // Emit an update in control values to other UI elements, like the HSI display
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
1664 1665 1666
    }
}

dogmaphobic's avatar
dogmaphobic committed
1667
#ifndef __mobile__
1668 1669
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
1670 1671 1672
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1673

1674
   // If system has manual inputs enabled and is armed
1675
    if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
1676 1677
    {
        mavlink_message_t message;
1678 1679
        float q[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, q);
1680

Lorenz Meier's avatar
Lorenz Meier committed
1681 1682
        float yawrate = 0.0f;

1683
        // Do not control rates and throttle
1684
        quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
1685 1686 1687 1688
        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);
1689
        _vehicle->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
1690
        quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
1691
            (1 << 6) | (1 << 7) | (1 << 8);
1692 1693
        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
1694
                                                       MAV_FRAME_LOCAL_NED, position_mask, x, y, z, 0, 0, 0, 0, 0, 0, yaw, yawrate);
1695
        _vehicle->sendMessage(message);
1696
        qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
1697 1698 1699 1700 1701 1702 1703

        //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";
    }
1704
}
dogmaphobic's avatar
dogmaphobic committed
1705
#endif
1706

1707
/**
Jean Cyr's avatar
Jean Cyr committed
1708
* Order the robot to start receiver pairing
1709 1710 1711
*/
void UAS::pairRX(int rxType, int rxSubType)
{
1712 1713 1714
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1715

1716 1717 1718
    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);
1719
    _vehicle->sendMessage(msg);
1720 1721
}

1722 1723 1724
/**
* If enabled, connect the flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1725
#ifndef __mobile__
1726
void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration)
1727
{
1728
    Q_UNUSED(configuration);
1729

1730
    QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
1731
    if (!link) {
1732 1733 1734 1735 1736
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1737
        simulation = new QGCFlightGearLink(_vehicle, options);
1738
    }
1739

1740
    float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1741 1742 1743
    xacc_var = noise_scaler * 0.2914f;
    yacc_var = noise_scaler * 0.2914f;
    zacc_var = noise_scaler * 0.9577f;
1744 1745 1746
    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
1747 1748 1749
    xmag_var = noise_scaler * 0.0786f;
    ymag_var = noise_scaler * 0.0566f;
    zmag_var = noise_scaler * 0.0333f;
1750 1751 1752 1753
    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;
1754

1755 1756 1757
    // Connect Flight Gear Link
    link = dynamic_cast<QGCFlightGearLink*>(simulation);
    link->setStartupArguments(options);
Thomas Gubler's avatar
Thomas Gubler committed
1758
    link->sensorHilEnabled(sensorHil);
1759 1760
    // 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)));
1761 1762 1763 1764 1765 1766 1767 1768 1769
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1770
#endif
1771 1772 1773 1774

/**
* If enabled, connect the JSBSim link.
*/
dogmaphobic's avatar
dogmaphobic committed
1775
#ifndef __mobile__
1776 1777 1778
void UAS::enableHilJSBSim(bool enable, QString options)
{
    QGCJSBSimLink* link = dynamic_cast<QGCJSBSimLink*>(simulation);
1779
    if (!link) {
1780 1781 1782 1783 1784
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1785
        simulation = new QGCJSBSimLink(_vehicle, options);
1786 1787 1788 1789
    }
    // Connect Flight Gear Link
    link = dynamic_cast<QGCJSBSimLink*>(simulation);
    link->setStartupArguments(options);
1790 1791 1792 1793 1794 1795 1796 1797 1798
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1799
#endif
1800 1801 1802 1803

/**
* If enabled, connect the X-plane gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1804
#ifndef __mobile__
1805 1806 1807
void UAS::enableHilXPlane(bool enable)
{
    QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
1808
    if (!link) {
1809 1810 1811 1812
        if (simulation) {
            stopHil();
            delete simulation;
        }
1813
        simulation = new QGCXPlaneLink(_vehicle);
1814

1815
        float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1816 1817 1818
        xacc_var = noise_scaler * 0.2914f;
        yacc_var = noise_scaler * 0.2914f;
        zacc_var = noise_scaler * 0.9577f;
1819 1820 1821
        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
1822 1823 1824
        xmag_var = noise_scaler * 0.0786f;
        ymag_var = noise_scaler * 0.0566f;
        zmag_var = noise_scaler * 0.0333f;
1825 1826 1827 1828
        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;
1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839
    }
    // Connect X-Plane Link
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1840
#endif
1841

1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859
/**
* @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
1860
#ifndef __mobile__
1861 1862 1863 1864
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)
{
1865 1866 1867 1868
    Q_UNUSED(time_us);
    Q_UNUSED(xacc);
    Q_UNUSED(yacc);
    Q_UNUSED(zacc);
1869

1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889
        // 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
1890
#endif
1891

1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909
/**
* @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
1910
#ifndef __mobile__
1911
void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
Lorenz Meier's avatar
Lorenz Meier committed
1912
                       float pitchspeed, float yawspeed, double lat, double lon, double alt,
1913
                       float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
1914
{
1915 1916 1917
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1918

1919
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
1920
    {
1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938
        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;
1939
        mavlink_msg_hil_state_quaternion_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
1940 1941
                                   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);
1942
        _vehicle->sendMessage(msg);
1943 1944 1945 1946
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1947
        _vehicle->setHilMode(true);
1948 1949 1950
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1951
#endif
1952

1953 1954 1955
#ifndef __mobile__
float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
{
dogmaphobic's avatar
dogmaphobic committed
1956
    /* Calculate normally distributed variable noise with mean = 0 and variance = noise_var.  Calculated according to
1957 1958 1959 1960
    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
1961

1962 1963 1964 1965 1966 1967 1968 1969 1970 1971
    /*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()

1972
    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
1973

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

1978
    //Finally gaurd against any case where the noise is not real
1979
    if(std::isfinite(noise)) {
1980
            return truth_meas + noise;
1981
    } else {
1982 1983 1984 1985 1986
        return truth_meas;
    }
}
#endif

1987 1988 1989 1990
/*
* @param abs_pressure Absolute Pressure (hPa)
* @param diff_pressure Differential Pressure  (hPa)
*/
dogmaphobic's avatar
dogmaphobic committed
1991
#ifndef __mobile__
Lorenz Meier's avatar
Lorenz Meier committed
1992
void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
1993
                                    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
1994
{
1995 1996 1997
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1998

1999
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
Lorenz Meier's avatar
Lorenz Meier committed
2000
    {
2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013
        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);
2014

Lorenz Meier's avatar
Lorenz Meier committed
2015
        mavlink_message_t msg;
2016
        mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
2017
                                   time_us, xacc_corrupt, yacc_corrupt, zacc_corrupt, rollspeed_corrupt, pitchspeed_corrupt,
dogmaphobic's avatar
dogmaphobic committed
2018
                                    yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
2019
                                    diff_pressure_corrupt, pressure_alt_corrupt, temperature_corrupt, fields_changed);
2020
        _vehicle->sendMessage(msg);
2021
        lastSendTimeSensors = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
2022 2023 2024 2025
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
2026
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
2027 2028 2029
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
2030
#endif
Lorenz Meier's avatar
Lorenz Meier committed
2031

dogmaphobic's avatar
dogmaphobic committed
2032
#ifndef __mobile__
2033 2034 2035
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)
{
2036 2037 2038
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2039

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

Don Gagne's avatar
Don Gagne committed
2042 2043 2044 2045 2046 2047 2048
    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);
2049

2050 2051
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
    {
Don Gagne's avatar
Don Gagne committed
2052
#if 0
2053 2054
        mavlink_message_t msg;
        mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
Don Gagne's avatar
Don Gagne committed
2055
                                   time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
2056

2057
        _vehicle->sendMessage(msg);
2058
        lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
Don Gagne's avatar
Don Gagne committed
2059
#endif
2060 2061 2062 2063
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
2064
        _vehicle->setHilMode(true);
2065 2066 2067 2068
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }

}
dogmaphobic's avatar
dogmaphobic committed
2069
#endif
2070

dogmaphobic's avatar
dogmaphobic committed
2071
#ifndef __mobile__
2072
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
2073
{
2074 2075 2076
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2077

2078 2079 2080 2081
    // Only send at 10 Hz max rate
    if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
        return;

2082
    if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
Lorenz Meier's avatar
Lorenz Meier committed
2083
    {
Lorenz Meier's avatar
Lorenz Meier committed
2084 2085 2086
        float course = cog;
        // map to 0..2pi
        if (course < 0)
2087
            course += 2.0f * static_cast<float>(M_PI);
Lorenz Meier's avatar
Lorenz Meier committed
2088 2089 2090
        // scale from radians to degrees
        course = (course / M_PI) * 180.0f;

Lorenz Meier's avatar
Lorenz Meier committed
2091
        mavlink_message_t msg;
2092 2093
        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);
2094
        lastSendTimeGPS = QGC::groundTimeMilliseconds();
2095
        _vehicle->sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
2096 2097 2098 2099
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
2100
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
2101 2102 2103
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
2104
#endif
Lorenz Meier's avatar
Lorenz Meier committed
2105

2106 2107 2108
/**
* Connect flight gear link.
**/
dogmaphobic's avatar
dogmaphobic committed
2109
#ifndef __mobile__
2110 2111 2112 2113
void UAS::startHil()
{
    if (hilEnabled) return;
    hilEnabled = true;
2114
    sensorHil = false;
Don Gagne's avatar
Don Gagne committed
2115
    _vehicle->setHilMode(true);
2116
    qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
2117 2118
    // Connect HIL simulation link
    simulation->connectSimulation();
2119
}
dogmaphobic's avatar
dogmaphobic committed
2120
#endif
2121 2122 2123 2124

/**
* disable flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
2125
#ifndef __mobile__
2126 2127
void UAS::stopHil()
{
2128 2129 2130 2131 2132
   if (simulation && simulation->isConnected()) {
       simulation->disconnectSimulation();
       _vehicle->setHilMode(false);
       qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
   }
2133
    hilEnabled = false;
2134
    sensorHil = false;
2135
}
dogmaphobic's avatar
dogmaphobic committed
2136
#endif
2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157

/**
* @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)
    {
2158
        _say(tr("System %1 has low battery").arg(getUASID()));
2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169
        lowBattAlarm = true;
    }
}

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

2171
void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
2172
{
2173 2174 2175
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2176

2177 2178
    mavlink_message_t message;

2179 2180 2181 2182 2183 2184 2185 2186 2187 2188
    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];
        }
    }

2189 2190 2191 2192 2193
    mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &message,
                                  this->uasId,
                                  0,
2194
                                  param_id_cstr,
2195 2196
                                  -1,
                                  param_rc_channel_index,
2197 2198 2199 2200
                                  value0,
                                  scale,
                                  valueMin,
                                  valueMax);
2201
    _vehicle->sendMessage(message);
2202 2203
    qDebug() << "Mavlink message sent";
}
2204

2205 2206
void UAS::unsetRCToParameterMap()
{
2207 2208 2209
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2210

2211 2212
    char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};

2213 2214 2215 2216 2217 2218 2219
    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,
2220
                                      param_id_cstr,
2221 2222 2223
                                      -2,
                                      i,
                                      0.0f,
2224 2225
                                      0.0f,
                                      0.0f,
2226
                                      0.0f);
2227
        _vehicle->sendMessage(message);
Don Gagne's avatar
Don Gagne committed
2228 2229
    }
}
2230 2231 2232

void UAS::_say(const QString& text, int severity)
{
dogmaphobic's avatar
dogmaphobic committed
2233
    if (!qgcApp()->runningUnitTests())
2234
        qgcApp()->toolbox()->audioOutput()->say(text, severity);
2235
}