UAS.cc 82.2 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5 6 7 8 9 10 11 12 13 14
======================================================================*/

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

#include <QList>
#include <QMessageBox>
#include <QTimer>
15
#include <QSettings>
pixhawk's avatar
pixhawk committed
16 17 18
#include <iostream>
#include <QDebug>
#include <cmath>
19
#include <qmath.h>
pixhawk's avatar
pixhawk committed
20 21 22
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
23
#include "QGC.h"
pixhawk's avatar
pixhawk committed
24
#include "GAudioOutput.h"
25
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
26
#include "QGCMAVLink.h"
27 28
#include "LinkManager.h"
#include "SerialLink.h"
pixhawk's avatar
pixhawk committed
29

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lm's avatar
lm committed
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
    uasId(id),
    startTime(QGC::groundTimeMilliseconds()),
    commStatus(COMM_DISCONNECTED),
    name(""),
    autopilot(-1),
    links(new QList<LinkInterface*>()),
    unknownPackets(),
    mavlink(protocol),
    waypointManager(this),
    thrustSum(0),
    thrustMax(10),
    startVoltage(0),
    warnVoltage(9.5f),
    warnLevelPercent(20.0f),
    currentVoltage(12.0f),
    lpVoltage(12.0f),
    batteryRemainingEstimateEnabled(true),
    mode(-1),
    status(-1),
    navMode(-1),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    receiveDropRate(0),
    sendDropRate(0),
    lowBattAlarm(false),
    positionLock(false),
    localX(0.0),
    localY(0.0),
    localZ(0.0),
    latitude(0.0),
    longitude(0.0),
    altitude(0.0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),
    statusTimeout(new QTimer(this)),
    paramsOnceRequested(false),
    airframe(QGC_AIRFRAME_EASYSTAR),
    attitudeKnown(false),
    paramManager(NULL),
    attitudeStamped(false),
    lastAttitude(0),
    simulation(new QGCFlightGearLink(this)),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),
    systemIsArmed(false)
pixhawk's avatar
pixhawk committed
84
{
85
    color = UASInterface::getNextColor();
lm's avatar
lm committed
86
    setBatterySpecs(QString("9V,9.5V,12.6V"));
87
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
88
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
89
    statusTimeout->start(500);
90
    readSettings();
91 92 93 94

    // Initial signals
    emit disarmed();
    emit armingChanged(false);
pixhawk's avatar
pixhawk committed
95 96 97 98
}

UAS::~UAS()
{
99
    writeSettings();
pixhawk's avatar
pixhawk committed
100
    delete links;
101
    links=NULL;
pixhawk's avatar
pixhawk committed
102 103
}

104 105 106 107 108
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
109 110
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
111
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
112 113 114 115 116 117 118 119 120
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
121 122
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
123
    if (settings.contains("BATTERY_SPECS")) {
124 125
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
126 127 128
    settings.endGroup();
}

129
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
130 131 132 133
{
    return uasId;
}

134 135
void UAS::updateState()
{
136 137
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
138 139
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
140 141 142 143
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

144 145
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
146 147
    if (positionLock)
    {
148
        positionLock = false;
149 150 151
    }
    else
    {
lm's avatar
lm committed
152
        if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
153
        {
154 155 156 157 158
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
159 160
void UAS::setSelected()
{
161
    if (UASManager::instance()->getActiveUAS() != this) {
162 163 164 165 166 167 168 169
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
170 171
}

172 173
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
174 175
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
176 177
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
lm's avatar
lm committed
178 179
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
180 181 182
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
183 184
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
lm's avatar
lm committed
185 186
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
187 188 189
    }
}

pixhawk's avatar
pixhawk committed
190 191
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
192
    if (!link) return;
193 194
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
195
        addLink(link);
196
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
197
    }
198 199 200 201
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
202

203
    //    qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
pixhawk's avatar
pixhawk committed
204

LM's avatar
LM committed
205 206 207 208
    // 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))
209
    {
pixhawk's avatar
pixhawk committed
210 211
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
212

213 214
        switch (message.msgid)
        {
pixhawk's avatar
pixhawk committed
215
        case MAVLINK_MSG_ID_HEARTBEAT:
216
        {
217
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
218
            emit heartbeat(this);
219 220
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
pixhawk's avatar
pixhawk committed
221
            // Set new type if it has changed
222
            if (this->type != state.type)
223
            {
224
                this->type = state.type;
225 226 227 228
                if (airframe == 0)
                {
                    switch (type)
                    {
lm's avatar
lm committed
229
                    case MAV_TYPE_FIXED_WING:
230 231
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
lm's avatar
lm committed
232
                    case MAV_TYPE_QUADROTOR:
233 234 235 236 237 238 239
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
                    default:
                        // Do nothing
                        break;
                    }
                }
240
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
241 242
                emit systemTypeSet(this, type);
            }
243

244 245 246 247 248 249 250 251 252 253 254 255 256 257 258
            bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;

            if (systemIsArmed != currentlyArmed)
            {
                systemIsArmed = currentlyArmed;
                emit armingChanged(systemIsArmed);
                if (systemIsArmed)
                {
                    emit armed();
                }
                else
                {
                    emit disarmed();
                }
            }
259

260 261 262 263 264 265
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
266 267


268 269 270 271 272 273 274
            if (state.system_status != this->status)
            {
                statechanged = true;
                this->status = state.system_status;
                getStatusForCode((int)state.system_status, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                emit statusChanged(this->status);
275

276
                shortStateText = uasState;
277

278 279
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
280

281
            if (this->mode != static_cast<int>(state.base_mode))
282 283
            {
                modechanged = true;
284
                this->mode = static_cast<int>(state.base_mode);
285
                shortModeText = getShortModeTextFor(this->mode);
286

287
                emit modeChanged(this->getUASID(), shortModeText, "");
LM's avatar
LM committed
288

289 290
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
291

292
            if (navMode != state.custom_mode)
293
            {
294 295
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
296 297
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
298

299 300 301 302 303 304 305 306 307 308 309
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
310

311 312 313 314 315 316 317
            if ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)
            {
                GAudioOutput::instance()->startEmergency();
            }
            else if (modechanged || statechanged)
            {
                GAudioOutput::instance()->stopEmergency();
318
                GAudioOutput::instance()->say(audiostring.toLower());
319
            }
lm's avatar
lm committed
320

321 322 323 324 325
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
326
}
327

328 329 330 331 332 333 334 335 336 337
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
338

339
                emit loadChanged(this,state.load/10.0f);
LM's avatar
LM committed
340 341


342

343
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
344
                lpVoltage = filterVoltage(currentVoltage);
LM's avatar
LM committed
345

LM's avatar
LM committed
346 347
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
348
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
349
                {
350
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
351 352 353
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
354
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
355

LM's avatar
LM committed
356
                // LOW BATTERY ALARM
357 358
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
359
                    startLowBattAlarm();
360 361 362
                }
                else
                {
LM's avatar
LM committed
363 364
                    stopLowBattAlarm();
                }
365

LM's avatar
LM committed
366
                // COMMUNICATIONS DROP RATE
367 368
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
369
            }
LM's avatar
LM committed
370
            break;
pixhawk's avatar
pixhawk committed
371
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
372 373 374
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
375
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
376
                lastAttitude = time;
LM's avatar
LM committed
377 378 379 380
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396
//                // Emit in angles

//                // Convert yaw angle to compass value
//                // in 0 - 360 deg range
//                float compass = (yaw/M_PI)*180.0+360.0f;
//                if (compass > -10000 && compass < 10000)
//                {
//                    while (compass > 360.0f) {
//                        compass -= 360.0f;
//                    }
//                }
//                else
//                {
//                    // Set to 0, since it is an invalid value
//                    compass = 0.0f;
//                }
lm's avatar
lm committed
397

LM's avatar
LM committed
398
                attitudeKnown = true;
399
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
400
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
401
            }
LM's avatar
LM committed
402
            break;
lm's avatar
lm committed
403 404 405 406
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
407
                emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
lm's avatar
lm committed
408 409
            }
            break;
410 411
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
412 413 414 415 416 417
                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);

418 419
                if (!attitudeKnown)
                {
LM's avatar
LM committed
420 421 422
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
423

LM's avatar
LM committed
424
                emit altitudeChanged(uasId, hud.alt);
LM's avatar
LM committed
425
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
426 427
            }
            break;
lm's avatar
lm committed
428
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
429
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
430
            //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;
LM's avatar
LM committed
431
            {
lm's avatar
lm committed
432 433
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
434
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
435 436 437 438 439 440 441 442 443 444 445 446
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);

                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
447
                isLocalPositionKnown = true;
lm's avatar
lm committed
448
            }
LM's avatar
LM committed
449
            break;
450
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
451 452
            //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;
LM's avatar
LM committed
453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470
            {
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
                quint64 time = getUnixTime();
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                speedX = pos.vx/100.0;
                speedY = pos.vy/100.0;
                speedZ = pos.vz/100.0;
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
471
                isGlobalPositionKnown = true;
LM's avatar
LM committed
472 473
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
474
            }
LM's avatar
LM committed
475
            break;
476 477
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
478 479 480 481 482
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

                // SANITY CHECK
                // only accept values in a realistic range
483 484
                // quint64 time = getUnixTime(pos.time_usec);
                quint64 time = getUnixTime(pos.time_usec);
LM's avatar
LM committed
485

LM's avatar
LM committed
486
                if (pos.fix_type > 2) {
LM's avatar
LM committed
487 488 489 490 491 492 493 494 495 496 497 498
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
                    positionLock = true;

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt) {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
lm's avatar
lm committed
499
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
500
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
501 502 503 504

                    float vel = pos.vel/100.0f;

                    if (vel < 1000000 && !isnan(vel) && !isinf(vel)) {
lm's avatar
lm committed
505
                        // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
506 507 508
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
LM's avatar
LM committed
509
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
510
                    }
lm's avatar
lm committed
511 512
                }
            }
LM's avatar
LM committed
513
            break;
514 515
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
516 517
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
518 519
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
520 521
                    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]));
                }
522
            }
LM's avatar
LM committed
523
            break;
524
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
525
            {
526 527
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
528
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
529 530
            }
            break;
531 532
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
533 534 535 536 537 538 539 540 541 542 543 544 545
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
                emit remoteControlChannelRawChanged(0, channels.chan1_raw);
                emit remoteControlChannelRawChanged(1, channels.chan2_raw);
                emit remoteControlChannelRawChanged(2, channels.chan3_raw);
                emit remoteControlChannelRawChanged(3, channels.chan4_raw);
                emit remoteControlChannelRawChanged(4, channels.chan5_raw);
                emit remoteControlChannelRawChanged(5, channels.chan6_raw);
                emit remoteControlChannelRawChanged(6, channels.chan7_raw);
                emit remoteControlChannelRawChanged(7, channels.chan8_raw);
            }
            break;
546 547
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
548 549 550 551 552 553 554 555 556 557 558
                mavlink_rc_channels_scaled_t channels;
                mavlink_msg_rc_channels_scaled_decode(&message, &channels);
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
                emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f);
lm's avatar
lm committed
559
            }
LM's avatar
LM committed
560
            break;
561 562
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
563 564
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
565
                QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
LM's avatar
LM committed
566 567
                QString parameterName = QString(bytes);
                int component = message.compid;
568 569
                mavlink_param_union_t val;
                val.param_float = value.param_value;
570
                val.type = value.param_type;
571

LM's avatar
LM committed
572
                // Insert component if necessary
573 574
                if (!parameters.contains(component))
                {
575
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
576
                }
577

LM's avatar
LM committed
578 579
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
580

581 582 583
                // Insert with correct type
                switch (value.param_type)
                {
584
                case MAVLINK_TYPE_FLOAT:
585 586 587 588
                    {
                    // Variant
                    QVariant param(val.param_float);
                    parameters.value(component)->insert(parameterName, param);
589
                    // Emit change
590 591 592 593
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
594
                    break;
595
                case MAVLINK_TYPE_UINT32_T:
596 597 598 599
                    {
                    // Variant
                    QVariant param(val.param_uint32);
                    parameters.value(component)->insert(parameterName, param);
600
                    // Emit change
601 602 603 604
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
605
                    break;
606
                case MAVLINK_TYPE_INT32_T:
607 608 609 610
                    {
                    // Variant
                    QVariant param(val.param_int32);
                    parameters.value(component)->insert(parameterName, param);
611
                    // Emit change
612 613 614 615
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
616 617 618 619
                    break;
                default:
                    qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
                }
LM's avatar
LM committed
620 621
            }
            break;
622 623 624
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
625 626
            if (ack.result == 1)
            {
627
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
628 629 630
            }
            else
            {
631
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
632 633
            }
            break;
LM's avatar
LM committed
634
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
635
            {
LM's avatar
LM committed
636 637
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
638
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
LM's avatar
LM committed
639
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
LM's avatar
LM committed
640 641
            }
            break;
lm's avatar
lm committed
642
        case MAVLINK_MSG_ID_MISSION_COUNT:
643
            {
lm's avatar
lm committed
644 645
                mavlink_mission_count_t wpc;
                mavlink_msg_mission_count_decode(&message, &wpc);
646
                if (wpc.target_system == mavlink->getSystemId())
647
                {
LM's avatar
LM committed
648 649
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
650 651 652 653
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
654
            }
LM's avatar
LM committed
655
            break;
pixhawk's avatar
pixhawk committed
656

lm's avatar
lm committed
657
        case MAVLINK_MSG_ID_MISSION_ITEM:
658
            {
lm's avatar
lm committed
659 660
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
661
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
662
                if(wp.target_system == mavlink->getSystemId())
663
                {
LM's avatar
LM committed
664 665
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
666 667 668 669
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
670
            }
LM's avatar
LM committed
671
            break;
pixhawk's avatar
pixhawk committed
672

lm's avatar
lm committed
673
        case MAVLINK_MSG_ID_MISSION_ACK:
674
            {
lm's avatar
lm committed
675 676
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
677 678
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
679 680
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
681
            }
LM's avatar
LM committed
682
            break;
683

lm's avatar
lm committed
684
        case MAVLINK_MSG_ID_MISSION_REQUEST:
685
            {
lm's avatar
lm committed
686 687
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
688
                if(wpr.target_system == mavlink->getSystemId())
689
                {
LM's avatar
LM committed
690 691
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
692 693 694 695
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
696
            }
LM's avatar
LM committed
697
            break;
pixhawk's avatar
pixhawk committed
698

lm's avatar
lm committed
699
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
700
            {
lm's avatar
lm committed
701 702
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
703 704 705 706 707 708
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
                QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
                GAudioOutput::instance()->say(text);
                emit textMessageReceived(message.sysid, message.compid, 0, text);
            }
            break;
pixhawk's avatar
pixhawk committed
709

lm's avatar
lm committed
710
        case MAVLINK_MSG_ID_MISSION_CURRENT:
711
            {
lm's avatar
lm committed
712 713
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
714 715 716
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
717

718 719
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
720 721 722 723 724
                mavlink_local_position_setpoint_t p;
                mavlink_msg_local_position_setpoint_decode(&message, &p);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
            }
            break;
725 726
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
727 728
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
729
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
730 731 732 733 734 735 736 737
                //b.append('\0');
                QString text = QString(b);
                int severity = mavlink_msg_statustext_get_severity(&message);
                //qDebug() << "RECEIVED STATUS:" << text;false
                //emit statusTextReceived(severity, text);
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
            break;
738
#ifdef MAVLINK_ENABLED_PIXHAWK
739 740
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
741 742 743 744 745 746 747 748 749 750 751
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                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;
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
752

753 754
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
755 756 757 758 759 760 761 762 763 764 765
                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;
766 767
                }

768 769
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
770 771 772 773 774
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
775

LM's avatar
LM committed
776
                ++imagePacketsArrived;
777

LM's avatar
LM committed
778 779 780 781 782 783 784 785
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
786
            }
LM's avatar
LM committed
787
            break;
788
#endif
lm's avatar
lm committed
789 790 791 792 793 794 795 796
//        case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
//        {
//            mavlink_object_detection_event_t event;
//            mavlink_msg_object_detection_event_decode(&message, &event);
//            QString str(event.name);
//            emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
//        }
//        break;
797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815
        // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
//        case MAVLINK_MSG_ID_MEMORY_VECT:
//        {
//            mavlink_memory_vect_t vect;
//            mavlink_msg_memory_vect_decode(&message, &vect);
//            QString str("mem_%1");
//            quint64 time = getUnixTime(0);
//            int16_t *mem0 = (int16_t *)&vect.value[0];
//            uint16_t *mem1 = (uint16_t *)&vect.value[0];
//            int32_t *mem2 = (int32_t *)&vect.value[0];
//            // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
//            float *mem4 = (float *)&vect.value[0];
//            if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
//            if ( vect.ver == 1)
//            {
//                switch (vect.type) {
//                default:
//                case 0:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
816
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
817 818 819
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
820
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
821 822 823
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
824
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
825 826 827
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
828
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
829 830 831
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
832
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
833 834 835
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
836
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
837 838 839
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
840
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
841 842 843 844 845
//                    break;
//                }
//            }
//        }
//        break;
lm's avatar
lm committed
846
#ifdef MAVLINK_ENABLED_UALBERTA
847 848
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
849 850 851
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
lm's avatar
lm committed
852 853 854 855 856 857
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
LM's avatar
LM committed
858 859
            }
            break;
860 861
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
862 863
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
864 865 866 867 868 869
                QVector<uint16_t> aileron;
                QVector<uint16_t> elevator;
                QVector<uint16_t> rudder;
                QVector<uint16_t> gyro;
                QVector<uint16_t> pitch;
                QVector<uint16_t> throttle;
LM's avatar
LM committed
870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888

                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
                    aileron << radioMsg.aileron[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
                    elevator << radioMsg.elevator[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
                    rudder << radioMsg.rudder[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
                    gyro << radioMsg.gyro[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
                    pitch << radioMsg.pitch[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
                    throttle << radioMsg.throttle[i];

                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;
889

890
#endif
LM's avatar
LM committed
891
            // Messages to ignore
892
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
893 894 895 896 897 898 899
        case MAVLINK_MSG_ID_RAW_IMU:
        case MAVLINK_MSG_ID_SCALED_IMU:
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
        case MAVLINK_MSG_ID_RAW_PRESSURE:
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
        case MAVLINK_MSG_ID_OPTICAL_FLOW:
900
            break;
lm's avatar
lm committed
901
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
902 903 904
            {
                mavlink_debug_vect_t debug;
                mavlink_msg_debug_vect_decode(&message, &debug);
905
                debug.name[MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN-1] = '\0';
LM's avatar
LM committed
906 907 908 909 910 911 912
                QString name(debug.name);
                quint64 time = getUnixTime(debug.time_usec);
                emit valueChanged(uasId, name+".x", "raw", debug.x, time);
                emit valueChanged(uasId, name+".y", "raw", debug.y, time);
                emit valueChanged(uasId, name+".z", "raw", debug.z, time);
            }
            break;
LM's avatar
LM committed
913
        case MAVLINK_MSG_ID_DEBUG:
914
            break;
915 916 917 918
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
919 920 921 922 923 924 925
                    unknownPackets.append(message.msgid);
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
                    GAudioOutput::instance()->say(errString+tr(", please check console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
                    std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                    //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast<int>(message.acid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                }
lm's avatar
lm committed
926
            }
LM's avatar
LM committed
927
            break;
pixhawk's avatar
pixhawk committed
928 929 930 931
        }
    }
}

932 933
void UAS::setHomePosition(double lat, double lon, double alt)
{
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 959 960 961 962 963 964 965 966
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Warning);
    msgBox.setText("Setting new World Coordinate Frame Origin");
    msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));


    if (ret == QMessageBox::Yes)
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
        // Wait 15 ms
        QGC::SLEEP::usleep(15000);
        // Send again
        sendMessage(msg);

        // Send new home position to UAS
        mavlink_set_gps_global_origin_t home;
        home.target_system = uasId;
        home.latitude = lat*1E7;
        home.longitude = lon*1E7;
        home.altitude = alt*1000;
        qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
        mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
        sendMessage(msg);
    }
967 968
}

969 970 971 972 973 974 975 976 977 978 979 980 981 982
void UAS::setLocalOriginAtCurrentGPSPosition()
{
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Warning);
    msgBox.setText("Setting new World Coordinate Frame Origin");
    msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));


983 984
    if (ret == QMessageBox::Yes)
    {
985 986 987 988 989 990 991 992
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
        // Wait 15 ms
        QGC::SLEEP::usleep(15000);
        // Send again
        sendMessage(msg);
993 994 995
    }
}

pixhawk's avatar
pixhawk committed
996 997
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
998
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
999
    mavlink_message_t msg;
LM's avatar
LM committed
1000
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0);
pixhawk's avatar
pixhawk committed
1001
    sendMessage(msg);
1002
#else
lm's avatar
lm committed
1003 1004 1005 1006
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1007
#endif
pixhawk's avatar
pixhawk committed
1008 1009
}

pixhawk's avatar
pixhawk committed
1010 1011
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1012
#ifdef MAVLINK_ENABLED_PIXHAWK
1013
    mavlink_message_t msg;
1014
    mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
1015
    sendMessage(msg);
lm's avatar
lm committed
1016
#else
1017 1018 1019 1020
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1021 1022 1023 1024
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1025
{
1026 1027
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1028
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
1029
    sendMessage(msg);
lm's avatar
lm committed
1030 1031
}

1032
void UAS::startDataRecording()
lm's avatar
lm committed
1033
{
1034
    mavlink_message_t msg;
1035
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0);
1036
    sendMessage(msg);
lm's avatar
lm committed
1037 1038 1039 1040
}

void UAS::stopDataRecording()
{
1041
    mavlink_message_t msg;
1042
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0);
1043
    sendMessage(msg);
lm's avatar
lm committed
1044 1045
}

pixhawk's avatar
pixhawk committed
1046 1047
void UAS::startMagnetometerCalibration()
{
1048 1049
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1050
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0);
1051
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1052 1053 1054 1055
}

void UAS::startGyroscopeCalibration()
{
1056 1057
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1058
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
1059
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1060 1061 1062 1063
}

void UAS::startPressureCalibration()
{
1064 1065
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1066
    mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0);
1067
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1068 1069
}

LM's avatar
LM committed
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 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114
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;
    }
}

1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127
/**
 * @warning If attitudeStamped is enabled, this function will not actually return the precise time stamp
 *          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 still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
 *          RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
 */
quint64 UAS::getUnixTimeFromMs(quint64 time)
{
    return getUnixTime(time*1000);
}

LM's avatar
LM committed
1128 1129 1130 1131 1132 1133 1134 1135
/**
 * @warning If attitudeStamped is enabled, this function will not actually return the precise time stamp
 *          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 still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
 *          RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
 */
1136 1137
quint64 UAS::getUnixTime(quint64 time)
{
1138
    quint64 ret = 0;
LM's avatar
LM committed
1139 1140
    if (attitudeStamped)
    {
1141
        ret = lastAttitude;
LM's avatar
LM committed
1142
    }
1143 1144
    if (time == 0)
    {
1145
        ret = QGC::groundTimeMilliseconds();
1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162
    }
    // 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
1163
#ifndef _MSC_VER
1164
    else if (time < 1261440000000000LLU)
1165
#else
LM's avatar
LM committed
1166
        else if (time < 1261440000000000)
1167
#endif
LM's avatar
LM committed
1168 1169
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1170 1171
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1172
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1173
        }
1174
        ret = time/1000 + onboardTimeOffset;
1175 1176 1177
    }
    else
    {
1178 1179
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1180
        ret = time/1000;
1181
    }
1182
    return ret;
1183 1184
}

1185 1186
QList<QString> UAS::getParameterNames(int component)
{
1187 1188
    if (parameters.contains(component))
    {
1189
        return parameters.value(component)->keys();
1190 1191 1192
    }
    else
    {
1193 1194 1195 1196 1197 1198 1199 1200 1201
        return QList<QString>();
    }
}

QList<int> UAS::getComponentIds()
{
    return parameters.keys();
}

pixhawk's avatar
pixhawk committed
1202
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1203
{
LM's avatar
LM committed
1204 1205 1206 1207 1208
    //this->mode = mode; //no call assignament, update receive message from UAS
    mavlink_message_t msg;
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
    sendMessage(msg);
    qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1209 1210 1211 1212 1213
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1214 1215 1216 1217
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1218
            sendMessage(link, message);
1219 1220 1221
        }
        else
        {
1222 1223 1224
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1225 1226 1227
    }
}

1228 1229 1230 1231
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1232

1233 1234 1235 1236
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1237
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1238 1239 1240 1241 1242 1243
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1244
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1245 1246
                        sendMessage(serial, message);
                    }
1247 1248 1249 1250 1251 1252
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1253 1254
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1255
    if(!link) return;
pixhawk's avatar
pixhawk committed
1256 1257 1258
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1259
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1260 1261
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
1262
    // If link is connected
1263 1264
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1265 1266 1267 1268 1269 1270 1271 1272
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1273
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1274
{
1275
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1276 1277
}

1278 1279
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1280 1281
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1282 1283
    switch (mode)
    {
lm's avatar
lm committed
1284
    case 0:
1285
        return QString("PREFLIGHT");
1286 1287 1288 1289
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar