UAS.cc 70.9 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10 11 12 13 14 15 16 17 18 19 20 21 22 23

/**
 * @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
24

25 26
#include <cmath>
#include <qmath.h>
Don Gagne's avatar
Don Gagne committed
27

28 29 30
#include <limits>
#include <cstdlib>

31 32
#include "UAS.h"
#include "LinkInterface.h"
33
#include "HomePositionManager.h"
34 35 36 37 38
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
dogmaphobic's avatar
dogmaphobic committed
39
#ifndef __ios__
40
#include "SerialLink.h"
dogmaphobic's avatar
dogmaphobic committed
41
#endif
Don Gagne's avatar
Don Gagne committed
42
#include "FirmwarePluginManager.h"
43
#include "QGCLoggingCategory.h"
44
#include "Vehicle.h"
45
#include "Joystick.h"
46
#include "QGCApplication.h"
47
#include "MissionCommands.h"
48

49
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
50

51 52
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
53
* by calling readSettings. This means the new UAS will have the same settings
54
* as the previous one created unless one calls deleteSettings in the code after
55
* creating the UAS.
56
*/
57

58
UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(),
59 60
    lipoFull(4.2f),
    lipoEmpty(3.5f),
61
    uasId(vehicle->id()),
62 63
    unknownPackets(),
    mavlink(protocol),
64 65 66 67 68 69
    receiveDropRate(0),
    sendDropRate(0),

    status(-1),

    startTime(QGC::groundTimeMilliseconds()),
70
    onboardTimeOffset(0),
71

72 73 74 75 76 77 78 79
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
80 81 82

    isGlobalPositionKnown(false),

83 84 85
    latitude(0.0),
    longitude(0.0),
    altitudeAMSL(0.0),
86
    altitudeAMSLFT(0.0),
87 88
    altitudeRelative(0.0),

89 90 91 92
    satRawHDOP(1e10f),
    satRawVDOP(1e10f),
    satRawCOG(0.0),

Don Gagne's avatar
Don Gagne committed
93 94 95 96 97
    globalEstimatorActive(false),

    latitude_gps(0.0),
    longitude_gps(0.0),
    altitude_gps(0.0),
98 99 100 101 102

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

Don Gagne's avatar
Don Gagne committed
103 104
    airSpeed(std::numeric_limits<double>::quiet_NaN()),
    groundSpeed(std::numeric_limits<double>::quiet_NaN()),
105
#ifndef __mobile__
106
    fileManager(this, vehicle),
107
#endif
Don Gagne's avatar
Don Gagne committed
108

109 110 111
    attitudeKnown(false),
    attitudeStamped(false),
    lastAttitude(0),
112

113 114 115 116
    roll(0.0),
    pitch(0.0),
    yaw(0.0),

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

Don Gagne's avatar
Don Gagne committed
119 120 121
    blockHomePositionChanges(false),
    receivedMode(false),

122 123
    // Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
    // TODO: calibrate stand-still pixhawk variances
124
    xacc_var(0.6457f),
dogmaphobic's avatar
dogmaphobic committed
125
    yacc_var(0.7048f),
126
    zacc_var(0.97885f),
dogmaphobic's avatar
dogmaphobic committed
127 128 129
    rollspeed_var(0.8126f),
    pitchspeed_var(0.6145f),
    yawspeed_var(0.5852f),
130 131 132 133 134 135 136
    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),
137
    /*
138 139 140 141 142 143 144 145 146 147 148 149 150
    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),
151
    */
152

dogmaphobic's avatar
dogmaphobic committed
153
#ifndef __mobile__
154
    simulation(0),
dogmaphobic's avatar
dogmaphobic committed
155
#endif
156 157

    // The protected members.
158 159 160 161
    connectionLost(false),
    lastVoltageWarning(0),
    lastNonNullTime(0),
    onboardTimeOffsetInvalidCount(0),
162
    hilEnabled(false),
163 164
    sensorHil(false),
    lastSendTimeGPS(0),
165
    lastSendTimeSensors(0),
166
    lastSendTimeOpticalFlow(0),
167 168
    _vehicle(vehicle),
    _firmwarePluginManager(firmwarePluginManager)
169
{
dogmaphobic's avatar
dogmaphobic committed
170

171 172 173 174 175
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }
176

177
#ifndef __mobile__
178
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
179
#endif
180

181 182 183 184 185 186 187 188 189 190 191
    color = UASInterface::getNextColor();
}

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

192
void UAS::receiveMessage(mavlink_message_t message)
193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
{
    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;
            }
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
278 279 280

            // 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
281
            quint64 time = getUnixTime();
282 283 284 285 286
            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);

287 288 289 290 291 292 293 294
            if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
            {
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
            }

295 296
            // We got the mode
            receivedMode = true;
297 298 299
        }

            break;
300

301 302 303 304 305 306 307 308 309
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
            mavlink_sys_status_t state;
            mavlink_msg_sys_status_decode(&message, &state);

310
            // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
311
            quint64 time = getUnixTime();
312 313 314 315 316 317 318
            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);
319 320
            emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);

321
            // Process CPU load.
322
            emit loadChanged(this,state.load/10.0f);
323
            emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
324 325 326 327 328 329 330 331

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

332 333 334 335 336 337 338 339 340 341 342
            // 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);
        }
343 344 345 346 347 348 349 350 351 352 353 354
            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;
355 356 357
                setRoll(QGC::limitAngleToPMPIf(attitude.roll));
                setPitch(QGC::limitAngleToPMPIf(attitude.pitch));
                setYaw(QGC::limitAngleToPMPIf(attitude.yaw));
358

359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418
                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));
419 420

                attitudeKnown = true;
421
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
422
                emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442
            }
        }
            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)
            {
443
                setYaw(QGC::limitAngleToPMPId((((double)hud.heading)/180.0)*M_PI));
444
                emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
445 446
            }

447 448
            setAltitudeAMSL(hud.alt);
            setGroundSpeed(hud.groundspeed);
449
            if (!qIsNaN(hud.airspeed))
450 451
                setAirSpeed(hud.airspeed);
            speedZ = -hud.climb;
Don Gagne's avatar
Don Gagne committed
452
            emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
453
            emit speedChanged(this, groundSpeed, airSpeed, time);
454 455 456 457 458 459 460 461 462 463 464 465
        }
            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)
            {
466 467 468
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
469 470

                // Emit
471
                emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488
            }
        }
            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);
489

490
            quint64 time = getUnixTime();
491

492 493
            setLatitude(pos.lat/(double)1E7);
            setLongitude(pos.lon/(double)1E7);
494
            setAltitudeRelative(pos.relative_alt/1000.0);
495

496
            globalEstimatorActive = true;
497

498 499 500
            speedX = pos.vx/100.0;
            speedY = pos.vy/100.0;
            speedZ = pos.vz/100.0;
501

Don Gagne's avatar
Don Gagne committed
502 503
            emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), time);
            emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
504
            // We had some frame mess here, global and local axes were mixed.
505
            emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
506

507 508
            setGroundSpeed(qSqrt(speedX*speedX+speedY*speedY));
            emit speedChanged(this, groundSpeed, airSpeed, time);
509 510 511 512 513 514 515 516 517 518

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

520 521 522 523
            // TODO: track localization state not only for gps but also for other loc. sources
            int loc_type = pos.fix_type;
            if (loc_type == 1)
            {
524
                loc_type = 0;
525
            }
526
            setSatelliteCount(pos.satellites_visible);
527 528 529

            if (pos.fix_type > 2)
            {
530
                isGlobalPositionKnown = true;
531

532
                latitude_gps  = pos.lat/(double)1E7;
533
                longitude_gps = pos.lon/(double)1E7;
534
                altitude_gps  = pos.alt/1000.0;
535

536
                // If no GLOBAL_POSITION_INT messages ever received, use these raw GPS values instead.
537
                if (!globalEstimatorActive) {
538 539
                    setLatitude(latitude_gps);
                    setLongitude(longitude_gps);
Don Gagne's avatar
Don Gagne committed
540 541
                    emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), time);
                    emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
542

543 544
                    float vel = pos.vel/100.0f;
                    // Smaller than threshold and not NaN
545
                    if ((vel < 1000000) && !qIsNaN(vel) && !qIsInf(vel)) {
546
                        setGroundSpeed(vel);
547 548
                        emit speedChanged(this, groundSpeed, airSpeed, time);
                    } else {
549
                        emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_NOTICE, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
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
            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);
            }

575 576 577
            // 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);
578 579 580 581 582 583 584 585 586 587
        }
            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]));
            }
588
            setSatelliteCount(pos.satellites_visible);
589 590 591 592 593 594 595 596 597
        }
            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;
598

599 600
        case MAVLINK_MSG_ID_PARAM_VALUE:
        {
601 602 603
            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);
604 605 606
            // 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);
607 608 609
            mavlink_param_union_t paramVal;
            paramVal.param_float = rawValue.param_value;
            paramVal.type = rawValue.param_type;
610

611 612
            processParamValueMsg(message, parameterName,rawValue,paramVal);
         }
613
            break;
614
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
615
        {
616 617 618 619
            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);
620
            quint64 time = getUnixTimeFromMs(out.time_boot_ms);
621
            emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, out.thrust, time);
622 623

            // For plotting emit roll sp, pitch sp and yaw sp values
624 625 626
            emit valueChanged(uasId, "roll sp", "rad", roll, time);
            emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
            emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
627 628
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
629

630
        case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
631 632 633 634 635
        {
            if (multiComponentSourceDetected && wrongComponent)
            {
                break;
            }
636 637 638 639
            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);
640 641
        }
            break;
642
        case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
643
        {
644 645 646
            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 */);
647 648 649 650 651
        }
            break;
        case MAVLINK_MSG_ID_STATUSTEXT:
        {
            QByteArray b;
652
            b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
653
            mavlink_msg_statustext_get_text(&message, b.data());
dogmaphobic's avatar
dogmaphobic committed
654

655 656
            // Ensure NUL-termination
            b[b.length()-1] = '\0';
657 658 659
            QString text = QString(b);
            int severity = mavlink_msg_statustext_get_severity(&message);

dogmaphobic's avatar
dogmaphobic committed
660 661
        // If the message is NOTIFY or higher severity, or starts with a '#',
        // then read it aloud.
662
            if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
663
            {
664
                text.remove("#");
665
                emit textMessageReceived(uasId, message.compid, severity, text);
666
                _say(text.toLower(), severity);
667 668 669 670 671 672 673
            }
            else
            {
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
        }
            break;
674

675 676 677 678 679 680 681 682 683 684 685 686
        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();
687 688
            imagePacketsArrived = 0;

689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704
        }
            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
705
                break;
706 707 708 709 710 711 712 713 714 715 716 717 718
            }

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

            ++imagePacketsArrived;

            // emit signal if all packets arrived
719
            if (imagePacketsArrived >= imagePackets)
720 721
            {
                // Restart statemachine
Don Gagne's avatar
Don Gagne committed
722 723
                imagePackets = 0;
                imagePacketsArrived = 0;
724 725 726 727 728 729
                emit imageReady(this);
            }
        }
            break;

        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
730 731 732 733
        {
            mavlink_nav_controller_output_t p;
            mavlink_msg_nav_controller_output_decode(&message,&p);
            setDistToWaypoint(p.wp_dist);
734 735
            setBearingToWaypoint(p.nav_bearing);
            emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error);
736
            emit NavigationControllerDataChanged(this, p.nav_roll, p.nav_pitch, p.nav_bearing, p.target_bearing, p.wp_dist);
737 738
        }
            break;
dogmaphobic's avatar
dogmaphobic committed
739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755

        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;

756 757 758 759 760 761
        default:
            break;
        }
    }
}

762
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
763
{
764 765 766
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
767

768 769 770 771 772
    int gyroCal = 0;
    int magCal = 0;
    int airspeedCal = 0;
    int radioCal = 0;
    int accelCal = 0;
773
    int escCal = 0;
dogmaphobic's avatar
dogmaphobic committed
774

775 776 777 778 779 780 781 782 783 784 785 786 787
    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
788 789 790
        case StartCalibrationCopyTrims:
            radioCal = 2;
            break;
791 792 793
        case StartCalibrationAccel:
            accelCal = 1;
            break;
794 795 796
        case StartCalibrationLevel:
            accelCal = 2;
            break;
797 798 799
        case StartCalibrationEsc:
            escCal = 1;
            break;
800 801 802
        case StartCalibrationUavcanEsc:
            escCal = 2;
            break;
803
    }
dogmaphobic's avatar
dogmaphobic committed
804

805
    mavlink_message_t msg;
806 807 808 809
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
810
                                  _vehicle->defaultComponentId(),   // target component
811 812 813 814 815 816 817 818
                                  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
819
                                  escCal);                          // esc cal
820
    _vehicle->sendMessageOnPriorityLink(msg);
821 822
}

823
void UAS::stopCalibration(void)
824
{
825 826 827
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
828

829
    mavlink_message_t msg;
830 831 832 833
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
834
                                  _vehicle->defaultComponentId(),   // target component
835 836 837 838 839 840 841 842 843
                                  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
844
    _vehicle->sendMessageOnPriorityLink(msg);
845 846
}

847 848
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
849 850 851
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
852

853
   int actuatorCal = 0;
854 855 856 857

    switch (calType) {
        case StartBusConfigActuators:
            actuatorCal = 1;
858 859 860 861
        break;
        case EndBusConfigActuators:
            actuatorCal = 0;
        break;
862 863 864 865 866 867 868
    }

    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
869 870
                                  _vehicle->defaultComponentId(),   // target component
                                  MAV_CMD_PREFLIGHT_UAVCAN,         // command id
871 872 873 874 875 876 877 878
                                  0,                                // 0=first transmission of command
                                  actuatorCal,                      // actuators
                                  0,
                                  0,
                                  0,
                                  0,
                                  0,
                                  0);
879
    _vehicle->sendMessageOnPriorityLink(msg);
880 881 882 883
}

void UAS::stopBusConfig(void)
{
884 885 886
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
887

888 889 890 891 892
    mavlink_message_t msg;
    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  uasId,
893 894
                                  _vehicle->defaultComponentId(),   // target component
                                  MAV_CMD_PREFLIGHT_UAVCAN,         // command id
895 896 897 898 899 900 901 902
                                  0,                                // 0=first transmission of command
                                  0,
                                  0,
                                  0,
                                  0,
                                  0,
                                  0,
                                  0);
903
    _vehicle->sendMessageOnPriorityLink(msg);
904 905
}

906 907
/**
* Check if time is smaller than 40 years, assuming no system without Unix
908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958
* 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
959
* the precise time stamp of this measurement augmented to UNIX time, but will
960
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
961
* reason why one would want this, except for system setups where the onboard
962
* clock is not present or broken and datasets should be collected that are still
963
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
964 965 966 967 968 969 970 971 972
* 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
973 974 975 976
* 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
977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033
* 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;
}

1034
/**
1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095
* 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)
    {
1096
        int imgColors = 255;
1097 1098 1099 1100 1101

        // 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
1102
        QByteArray tmpImage(header.toStdString().c_str(), header.length());
1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114
        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"))
        {
1115
            qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127
            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))
        {
1128
            qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
1129
            return QImage();
1130 1131
        }
    }
1132

1133 1134
    // Restart statemachine
    imagePacketsArrived = 0;
1135 1136
    imagePackets = 0;
    imageRecBuffer.clear();
1137 1138 1139 1140 1141
    return image;
}

void UAS::requestImage()
{
1142 1143 1144
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1145

1146
   qDebug() << "trying to get an image from the uas...";
1147 1148 1149 1150 1151

    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
1152
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, MAVLINK_DATA_STREAM_IMG_JPEG, 0, 0, 0, 0, 0, 50);
1153
        _vehicle->sendMessage(msg);
1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176
    }
}


/* MANAGEMENT */

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

1177
//TODO update this to use the parameter manager / param data model instead
1178
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue,  mavlink_param_union_t& paramUnion)
1179 1180 1181
{
    int compId = msg.compid;

1182
    QVariant paramValue;
1183 1184

    // Insert with correct type
1185

1186 1187
    switch (rawValue.param_type) {
        case MAV_PARAM_TYPE_REAL32:
Don Gagne's avatar
Don Gagne committed
1188
            paramValue = QVariant(paramUnion.param_float);
1189
            break;
1190

1191
        case MAV_PARAM_TYPE_UINT8:
Don Gagne's avatar
Don Gagne committed
1192
            paramValue = QVariant(paramUnion.param_uint8);
1193
            break;
1194

1195
        case MAV_PARAM_TYPE_INT8:
Don Gagne's avatar
Don Gagne committed
1196
            paramValue = QVariant(paramUnion.param_int8);
1197
            break;
1198

1199 1200 1201 1202
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant(paramUnion.param_uint16);
            break;

1203
        case MAV_PARAM_TYPE_INT16:
Don Gagne's avatar
Don Gagne committed
1204
            paramValue = QVariant(paramUnion.param_int16);
1205
            break;
1206

1207
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
1208
            paramValue = QVariant(paramUnion.param_uint32);
1209
            break;
dogmaphobic's avatar
dogmaphobic committed
1210

1211
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
1212
            paramValue = QVariant(paramUnion.param_int32);
1213
            break;
1214

1215 1216 1217 1218 1219 1220 1221 1222
        //-- Note: These are not handled above:
        //
        //   MAV_PARAM_TYPE_UINT64
        //   MAV_PARAM_TYPE_INT64
        //   MAV_PARAM_TYPE_REAL64
        //
        //   No space in message (the only storage allocation is a "float") and not present in mavlink_param_union_t

1223 1224
        default:
            qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
1225
    }
1226

1227
    qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
1228

1229
    emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
1230 1231 1232 1233
}

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

1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251
    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);
1252
    _vehicle->sendMessage(msg);
1253 1254
}

1255 1256
/**
* Set the manual control commands.
1257 1258
* This can only be done if the system has manual inputs enabled and is armed.
*/
1259
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
1260
{
1261 1262 1263
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1264

1265
    // Store the previous manual commands
1266 1267 1268 1269 1270 1271
    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
1272

1273 1274 1275 1276 1277 1278 1279 1280 1281
    // 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;
1282 1283
    } else if ((!qIsNaN(roll) && roll != manualRollAngle) || (!qIsNaN(pitch) && pitch != manualPitchAngle) ||
             (!qIsNaN(yaw) && yaw != manualYawAngle) || (!qIsNaN(thrust) && thrust != manualThrust) ||
1284 1285 1286 1287 1288 1289
             buttons != manualButtons) {
        sendCommand = true;

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

1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301
    // 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;

1302
        if (joystickMode == Vehicle::JoystickModeAttitude) {
1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319
            // 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
                );
1320
        } else if (joystickMode == Vehicle::JoystickModePosition) {
1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349
            // 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
                    );
1350
        } else if (joystickMode == Vehicle::JoystickModeForce) {
1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377
            // 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
                    );
1378
        } else if (joystickMode == Vehicle::JoystickModeVelocity) {
1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409
            // 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
                    );
1410
        } else if (joystickMode == Vehicle::JoystickModeRC) {
1411

1412 1413 1414 1415 1416 1417 1418 1419 1420
            // 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
1421

1422 1423 1424 1425 1426 1427 1428
            // 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;

1429
            //qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
dogmaphobic's avatar
dogmaphobic committed
1430

1431 1432
            // Send the MANUAL_COMMAND message
            mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
1433
        }
1434

1435
        _vehicle->sendMessage(message);
1436 1437
        // Emit an update in control values to other UI elements, like the HSI display
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
1438 1439 1440
    }
}

dogmaphobic's avatar
dogmaphobic committed
1441
#ifndef __mobile__
1442 1443
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
1444 1445 1446
    if (!_vehicle) {
        return;
    }
1447
    const uint8_t base_mode = _vehicle->baseMode();
dogmaphobic's avatar
dogmaphobic committed
1448

1449
   // If system has manual inputs enabled and is armed
1450
    if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
1451 1452
    {
        mavlink_message_t message;
1453 1454
        float q[4];
        mavlink_euler_to_quaternion(roll, pitch, yaw, q);
1455

Lorenz Meier's avatar
Lorenz Meier committed
1456 1457
        float yawrate = 0.0f;

1458
        // Do not control rates and throttle
1459
        quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
1460 1461 1462 1463
        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);
1464
        _vehicle->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
1465
        quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
1466
            (1 << 6) | (1 << 7) | (1 << 8);
1467 1468
        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
1469
                                                       MAV_FRAME_LOCAL_NED, position_mask, x, y, z, 0, 0, 0, 0, 0, 0, yaw, yawrate);
1470
        _vehicle->sendMessage(message);
1471
        qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
1472 1473 1474 1475 1476 1477 1478

        //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";
    }
1479
}
dogmaphobic's avatar
dogmaphobic committed
1480
#endif
1481

1482
/**
Jean Cyr's avatar
Jean Cyr committed
1483
* Order the robot to start receiver pairing
1484 1485 1486
*/
void UAS::pairRX(int rxType, int rxSubType)
{
1487 1488 1489
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1490

1491 1492 1493
    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);
1494
    _vehicle->sendMessage(msg);
1495 1496
}

1497 1498 1499
/**
* If enabled, connect the flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1500
#ifndef __mobile__
1501
void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration)
1502
{
1503
    Q_UNUSED(configuration);
1504

1505
    QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
1506
    if (!link) {
1507 1508 1509 1510 1511
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1512
        simulation = new QGCFlightGearLink(_vehicle, options);
1513
    }
1514

1515
    float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1516 1517 1518
    xacc_var = noise_scaler * 0.2914f;
    yacc_var = noise_scaler * 0.2914f;
    zacc_var = noise_scaler * 0.9577f;
1519 1520 1521
    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
1522 1523 1524
    xmag_var = noise_scaler * 0.0786f;
    ymag_var = noise_scaler * 0.0566f;
    zmag_var = noise_scaler * 0.0333f;
1525 1526 1527 1528
    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;
1529

1530 1531 1532
    // Connect Flight Gear Link
    link = dynamic_cast<QGCFlightGearLink*>(simulation);
    link->setStartupArguments(options);
Thomas Gubler's avatar
Thomas Gubler committed
1533
    link->sensorHilEnabled(sensorHil);
1534 1535
    // 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)));
1536 1537 1538 1539 1540 1541 1542 1543 1544
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1545
#endif
1546 1547 1548 1549

/**
* If enabled, connect the JSBSim link.
*/
dogmaphobic's avatar
dogmaphobic committed
1550
#ifndef __mobile__
1551 1552 1553
void UAS::enableHilJSBSim(bool enable, QString options)
{
    QGCJSBSimLink* link = dynamic_cast<QGCJSBSimLink*>(simulation);
1554
    if (!link) {
1555 1556 1557 1558 1559
        // Delete wrong sim
        if (simulation) {
            stopHil();
            delete simulation;
        }
1560
        simulation = new QGCJSBSimLink(_vehicle, options);
1561 1562 1563 1564
    }
    // Connect Flight Gear Link
    link = dynamic_cast<QGCJSBSimLink*>(simulation);
    link->setStartupArguments(options);
1565 1566 1567 1568 1569 1570 1571 1572 1573
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1574
#endif
1575 1576 1577 1578

/**
* If enabled, connect the X-plane gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1579
#ifndef __mobile__
1580 1581 1582
void UAS::enableHilXPlane(bool enable)
{
    QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
1583
    if (!link) {
1584 1585 1586 1587
        if (simulation) {
            stopHil();
            delete simulation;
        }
1588
        simulation = new QGCXPlaneLink(_vehicle);
1589

1590
        float noise_scaler = 0.0001f;
Lorenz Meier's avatar
Lorenz Meier committed
1591 1592 1593
        xacc_var = noise_scaler * 0.2914f;
        yacc_var = noise_scaler * 0.2914f;
        zacc_var = noise_scaler * 0.9577f;
1594 1595 1596
        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
1597 1598 1599
        xmag_var = noise_scaler * 0.0786f;
        ymag_var = noise_scaler * 0.0566f;
        zmag_var = noise_scaler * 0.0333f;
1600 1601 1602 1603
        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;
1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614
    }
    // Connect X-Plane Link
    if (enable)
    {
        startHil();
    }
    else
    {
        stopHil();
    }
}
dogmaphobic's avatar
dogmaphobic committed
1615
#endif
1616

1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634
/**
* @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
1635
#ifndef __mobile__
1636 1637 1638 1639
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)
{
1640 1641 1642 1643
    Q_UNUSED(time_us);
    Q_UNUSED(xacc);
    Q_UNUSED(yacc);
    Q_UNUSED(zacc);
1644

1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664
        // 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
1665
#endif
1666

1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684
/**
* @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
1685
#ifndef __mobile__
1686
void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
Lorenz Meier's avatar
Lorenz Meier committed
1687
                       float pitchspeed, float yawspeed, double lat, double lon, double alt,
1688
                       float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
1689
{
1690 1691 1692
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1693

1694
    if (_vehicle->hilMode())
1695
    {
1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713
        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;
1714
        mavlink_msg_hil_state_quaternion_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
1715 1716
                                   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);
1717
        _vehicle->sendMessage(msg);
1718 1719 1720 1721
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1722
        _vehicle->setHilMode(true);
1723 1724 1725
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1726
#endif
1727

1728 1729 1730
#ifndef __mobile__
float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
{
dogmaphobic's avatar
dogmaphobic committed
1731
    /* Calculate normally distributed variable noise with mean = 0 and variance = noise_var.  Calculated according to
1732 1733 1734 1735
    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
1736

1737 1738 1739 1740 1741 1742 1743 1744 1745 1746
    /*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()

1747
    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
1748

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

1753
    //Finally gaurd against any case where the noise is not real
1754
    if(std::isfinite(noise)) {
1755
            return truth_meas + noise;
1756
    } else {
1757 1758 1759 1760 1761
        return truth_meas;
    }
}
#endif

1762 1763 1764 1765
/*
* @param abs_pressure Absolute Pressure (hPa)
* @param diff_pressure Differential Pressure  (hPa)
*/
dogmaphobic's avatar
dogmaphobic committed
1766
#ifndef __mobile__
Lorenz Meier's avatar
Lorenz Meier committed
1767
void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
1768
                                    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
1769
{
1770 1771 1772
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1773

1774
    if (_vehicle->hilMode())
Lorenz Meier's avatar
Lorenz Meier committed
1775
    {
1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788
        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);
1789

Lorenz Meier's avatar
Lorenz Meier committed
1790
        mavlink_message_t msg;
1791
        mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
1792
                                   time_us, xacc_corrupt, yacc_corrupt, zacc_corrupt, rollspeed_corrupt, pitchspeed_corrupt,
dogmaphobic's avatar
dogmaphobic committed
1793
                                    yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
1794
                                    diff_pressure_corrupt, pressure_alt_corrupt, temperature_corrupt, fields_changed);
1795
        _vehicle->sendMessage(msg);
1796
        lastSendTimeSensors = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
1797 1798 1799 1800
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1801
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
1802 1803 1804
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1805
#endif
Lorenz Meier's avatar
Lorenz Meier committed
1806

dogmaphobic's avatar
dogmaphobic committed
1807
#ifndef __mobile__
1808 1809 1810
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)
{
1811 1812 1813
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1814

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

Don Gagne's avatar
Don Gagne committed
1817 1818 1819 1820 1821 1822 1823
    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);
1824

1825
    if (_vehicle->hilMode())
1826
    {
Don Gagne's avatar
Don Gagne committed
1827
#if 0
1828 1829
        mavlink_message_t msg;
        mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
Don Gagne's avatar
Don Gagne committed
1830
                                   time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
1831

1832
        _vehicle->sendMessage(msg);
1833
        lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
Don Gagne's avatar
Don Gagne committed
1834
#endif
1835 1836 1837 1838
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1839
        _vehicle->setHilMode(true);
1840 1841 1842 1843
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }

}
dogmaphobic's avatar
dogmaphobic committed
1844
#endif
1845

dogmaphobic's avatar
dogmaphobic committed
1846
#ifndef __mobile__
1847
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
1848
{
1849 1850 1851
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1852

1853 1854 1855 1856
    // Only send at 10 Hz max rate
    if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
        return;

1857
    if (_vehicle->hilMode())
Lorenz Meier's avatar
Lorenz Meier committed
1858
    {
Lorenz Meier's avatar
Lorenz Meier committed
1859 1860 1861
        float course = cog;
        // map to 0..2pi
        if (course < 0)
1862
            course += 2.0f * static_cast<float>(M_PI);
Lorenz Meier's avatar
Lorenz Meier committed
1863 1864 1865
        // scale from radians to degrees
        course = (course / M_PI) * 180.0f;

Lorenz Meier's avatar
Lorenz Meier committed
1866
        mavlink_message_t msg;
1867 1868
        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);
1869
        lastSendTimeGPS = QGC::groundTimeMilliseconds();
1870
        _vehicle->sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
1871 1872 1873 1874
    }
    else
    {
        // Attempt to set HIL mode
Don Gagne's avatar
Don Gagne committed
1875
        _vehicle->setHilMode(true);
Lorenz Meier's avatar
Lorenz Meier committed
1876 1877 1878
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    }
}
dogmaphobic's avatar
dogmaphobic committed
1879
#endif
Lorenz Meier's avatar
Lorenz Meier committed
1880

1881 1882 1883
/**
* Connect flight gear link.
**/
dogmaphobic's avatar
dogmaphobic committed
1884
#ifndef __mobile__
1885 1886 1887 1888
void UAS::startHil()
{
    if (hilEnabled) return;
    hilEnabled = true;
1889
    sensorHil = false;
Don Gagne's avatar
Don Gagne committed
1890
    _vehicle->setHilMode(true);
1891
    qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
1892 1893
    // Connect HIL simulation link
    simulation->connectSimulation();
1894
}
dogmaphobic's avatar
dogmaphobic committed
1895
#endif
1896 1897 1898 1899

/**
* disable flight gear link.
*/
dogmaphobic's avatar
dogmaphobic committed
1900
#ifndef __mobile__
1901 1902
void UAS::stopHil()
{
1903 1904 1905 1906 1907
   if (simulation && simulation->isConnected()) {
       simulation->disconnectSimulation();
       _vehicle->setHilMode(false);
       qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
   }
1908
    hilEnabled = false;
1909
    sensorHil = false;
1910
}
dogmaphobic's avatar
dogmaphobic committed
1911
#endif
1912 1913 1914 1915 1916 1917 1918 1919 1920

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

1921
void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
1922
{
1923 1924 1925
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1926

1927 1928
    mavlink_message_t message;

1929 1930 1931 1932 1933 1934 1935 1936 1937 1938
    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];
        }
    }

1939 1940 1941 1942 1943
    mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &message,
                                  this->uasId,
                                  0,
1944
                                  param_id_cstr,
1945 1946
                                  -1,
                                  param_rc_channel_index,
1947 1948 1949 1950
                                  value0,
                                  scale,
                                  valueMin,
                                  valueMax);
1951
    _vehicle->sendMessage(message);
dogmaphobic's avatar
dogmaphobic committed
1952
    //qDebug() << "Mavlink message sent";
1953
}
1954

1955 1956
void UAS::unsetRCToParameterMap()
{
1957 1958 1959
    if (!_vehicle) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1960

1961 1962
    char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};

1963 1964 1965 1966 1967 1968 1969
    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,
1970
                                      param_id_cstr,
1971 1972 1973
                                      -2,
                                      i,
                                      0.0f,
1974 1975
                                      0.0f,
                                      0.0f,
1976
                                      0.0f);
1977
        _vehicle->sendMessage(message);
Don Gagne's avatar
Don Gagne committed
1978 1979
    }
}
1980 1981 1982

void UAS::_say(const QString& text, int severity)
{
1983 1984
    Q_UNUSED(severity);
    qgcApp()->toolbox()->audioOutput()->say(text);
1985
}
Don Gagne's avatar
Don Gagne committed
1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999

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