UAS.cc 80.8 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
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),
47
batteryRemainingEstimateEnabled(true),
LM's avatar
LM committed
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
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),
75
airframe(QGC_AIRFRAME_EASYSTAR),
LM's avatar
LM committed
76
attitudeKnown(false),
LM's avatar
LM committed
77
paramManager(NULL),
LM's avatar
LM committed
78
attitudeStamped(false),
lm's avatar
lm committed
79
lastAttitude(0),
lm's avatar
lm committed
80
simulation(new QGCFlightGearLink(this)),
81 82
isLocalPositionKnown(false),
isGlobalPositionKnown(false)
pixhawk's avatar
pixhawk committed
83
{
84
    color = UASInterface::getNextColor();
lm's avatar
lm committed
85
    setBatterySpecs(QString("9V,9.5V,12.6V"));
86
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
87
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
88
    statusTimeout->start(500);
89
    readSettings();
pixhawk's avatar
pixhawk committed
90 91 92 93
}

UAS::~UAS()
{
94
    writeSettings();
pixhawk's avatar
pixhawk committed
95
    delete links;
96
    links=NULL;
pixhawk's avatar
pixhawk committed
97 98
}

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

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

124
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
125 126 127 128
{
    return uasId;
}

129 130
void UAS::updateState()
{
131 132
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
133 134
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
135 136 137 138
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

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

pixhawk's avatar
pixhawk committed
154 155
void UAS::setSelected()
{
156
    if (UASManager::instance()->getActiveUAS() != this) {
157 158 159 160 161 162 163 164
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

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

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

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

LM's avatar
LM committed
200 201 202 203
    // 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))
204
    {
pixhawk's avatar
pixhawk committed
205 206
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
207

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

239 240 241
            // FIXME update
            //emit armingChanged(uasId, );

242 243 244 245 246 247
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
248 249


250 251 252 253 254 255 256
            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);
257

258
                shortStateText = uasState;
259

260 261
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
262

263
            if (this->mode != static_cast<int>(state.base_mode))
264 265
            {
                modechanged = true;
266
                this->mode = static_cast<int>(state.base_mode);
267
                shortModeText = getShortModeTextFor(this->mode);
268

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

271 272
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
273

274
            if (navMode != state.custom_mode)
275
            {
276 277
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
278 279
                navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
            }
280

281 282 283 284 285 286 287 288 289 290 291
            // AUDIO
            if (modechanged && statechanged)
            {
                // Output both messages
                audiostring += modeAudio + " and " + stateAudio;
            }
            else if (modechanged || statechanged)
            {
                // Output the one message
                audiostring += modeAudio + stateAudio + navModeAudio;
            }
292

293 294 295 296 297 298 299
            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();
300
                GAudioOutput::instance()->say(audiostring.toLower());
301
            }
lm's avatar
lm committed
302

303 304 305 306 307
//            if (state.system_status == MAV_STATE_POWEROFF)
//            {
//                emit systemRemoved(this);
//                emit systemRemoved();
//            }
308
}
309

310 311 312 313 314 315 316 317 318 319
            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);
320

321
                emit loadChanged(this,state.load/10.0f);
lm's avatar
lm committed
322
                // FIXME REMOVE LATER emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
323

324
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
325 326 327
                lpVoltage = filterVoltage(currentVoltage);
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
328
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
329
                {
330
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
331 332 333
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
334
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
335

LM's avatar
LM committed
336
                // LOW BATTERY ALARM
337 338
                if (lpVoltage < warnVoltage)
                {
LM's avatar
LM committed
339
                    startLowBattAlarm();
340 341 342
                }
                else
                {
LM's avatar
LM committed
343 344
                    stopLowBattAlarm();
                }
345

LM's avatar
LM committed
346
                // COMMUNICATIONS DROP RATE
347 348
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
349
            }
LM's avatar
LM committed
350
            break;
pixhawk's avatar
pixhawk committed
351
        case MAVLINK_MSG_ID_ATTITUDE:
LM's avatar
LM committed
352 353 354
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
355
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
356
                lastAttitude = time;
LM's avatar
LM committed
357 358 359 360 361 362 363 364 365
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

                // Emit in angles

                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
lm's avatar
lm committed
366 367 368 369 370
                if (compass > -10000 && compass < 10000)
                {
                    while (compass > 360.0f) {
                        compass -= 360.0f;
                    }
LM's avatar
LM committed
371
                }
lm's avatar
lm committed
372

LM's avatar
LM committed
373
                attitudeKnown = true;
374
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
375
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
376
            }
LM's avatar
LM committed
377
            break;
lm's avatar
lm committed
378 379 380 381
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
382
                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
383 384
            }
            break;
385 386
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
387 388 389 390 391 392
                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);

393 394
                if (!attitudeKnown)
                {
LM's avatar
LM committed
395 396 397
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
398

LM's avatar
LM committed
399
                emit altitudeChanged(uasId, hud.alt);
LM's avatar
LM committed
400
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
LM's avatar
LM committed
401 402
            }
            break;
lm's avatar
lm committed
403
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
lm's avatar
lm committed
404
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
405
            //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
406
            {
lm's avatar
lm committed
407 408
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
409
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
410 411 412 413 414 415 416 417 418 419 420 421
                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;
422
                isLocalPositionKnown = true;
lm's avatar
lm committed
423
            }
LM's avatar
LM committed
424
            break;
425
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
426 427
            //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
428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445
            {
                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;
446
                isGlobalPositionKnown = true;
LM's avatar
LM committed
447 448
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
449
            }
LM's avatar
LM committed
450
            break;
451 452
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
453 454 455 456 457
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

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

LM's avatar
LM committed
461
                if (pos.fix_type > 2) {
LM's avatar
LM committed
462 463 464 465 466 467 468 469 470 471 472 473
                    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
474
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
LM's avatar
LM committed
475
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
476 477 478 479

                    float vel = pos.vel/100.0f;

                    if (vel < 1000000 && !isnan(vel) && !isinf(vel)) {
lm's avatar
lm committed
480
                        // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
481 482 483
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
LM's avatar
LM committed
484
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
485
                    }
lm's avatar
lm committed
486 487
                }
            }
LM's avatar
LM committed
488
            break;
489 490
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
491 492
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
493 494
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
495 496
                    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]));
                }
497
            }
LM's avatar
LM committed
498
            break;
499
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
500
            {
501 502
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
503
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
504 505
            }
            break;
506 507
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
508 509 510 511 512 513 514 515 516 517 518 519 520
                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;
521 522
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
523 524 525 526 527 528 529 530 531 532 533
                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
534
            }
LM's avatar
LM committed
535
            break;
536 537
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
538 539 540 541 542
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
                QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
                QString parameterName = QString(bytes);
                int component = message.compid;
543 544
                mavlink_param_union_t val;
                val.param_float = value.param_value;
545
                val.type = value.param_type;
546

LM's avatar
LM committed
547
                // Insert component if necessary
548 549
                if (!parameters.contains(component))
                {
550
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
551
                }
552

LM's avatar
LM committed
553 554
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
555

556 557 558
                // Insert with correct type
                switch (value.param_type)
                {
559
                case MAVLINK_TYPE_FLOAT:
560 561 562 563
                    {
                    // Variant
                    QVariant param(val.param_float);
                    parameters.value(component)->insert(parameterName, param);
564
                    // Emit change
565 566 567 568
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
569
                    break;
570
                case MAVLINK_TYPE_UINT32_T:
571 572 573 574
                    {
                    // Variant
                    QVariant param(val.param_uint32);
                    parameters.value(component)->insert(parameterName, param);
575
                    // Emit change
576 577 578 579
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
580
                    break;
581
                case MAVLINK_TYPE_INT32_T:
582 583 584 585
                    {
                    // Variant
                    QVariant param(val.param_int32);
                    parameters.value(component)->insert(parameterName, param);
586
                    // Emit change
587 588 589 590
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
                    qDebug() << "RECEIVED PARAM:" << param;
                }
591 592 593 594
                    break;
                default:
                    qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
                }
LM's avatar
LM committed
595 596
            }
            break;
597 598 599
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
600 601
            if (ack.result == 1)
            {
602
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
603 604 605
            }
            else
            {
606
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
607 608
            }
            break;
LM's avatar
LM committed
609
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
610
            {
LM's avatar
LM committed
611 612
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
613
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
LM's avatar
LM committed
614
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
LM's avatar
LM committed
615 616
            }
            break;
lm's avatar
lm committed
617
        case MAVLINK_MSG_ID_MISSION_COUNT:
618
            {
lm's avatar
lm committed
619 620
                mavlink_mission_count_t wpc;
                mavlink_msg_mission_count_decode(&message, &wpc);
621 622
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
623 624
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
625 626 627 628
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
629
            }
LM's avatar
LM committed
630
            break;
pixhawk's avatar
pixhawk committed
631

lm's avatar
lm committed
632
        case MAVLINK_MSG_ID_MISSION_ITEM:
633
            {
lm's avatar
lm committed
634 635
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
LM's avatar
LM committed
636
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
637 638
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
639 640
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
641 642 643 644
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
645
            }
LM's avatar
LM committed
646
            break;
pixhawk's avatar
pixhawk committed
647

lm's avatar
lm committed
648
        case MAVLINK_MSG_ID_MISSION_ACK:
649
            {
lm's avatar
lm committed
650 651
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
652 653
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
654 655
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
656
            }
LM's avatar
LM committed
657
            break;
658

lm's avatar
lm committed
659
        case MAVLINK_MSG_ID_MISSION_REQUEST:
660
            {
lm's avatar
lm committed
661 662
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
663 664
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
665 666
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
667 668 669 670
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
671
            }
LM's avatar
LM committed
672
            break;
pixhawk's avatar
pixhawk committed
673

lm's avatar
lm committed
674
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
675
            {
lm's avatar
lm committed
676 677
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
LM's avatar
LM committed
678 679 680 681 682 683
                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
684

lm's avatar
lm committed
685
        case MAVLINK_MSG_ID_MISSION_CURRENT:
686
            {
lm's avatar
lm committed
687 688
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
LM's avatar
LM committed
689 690 691
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
692

693 694
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
695 696 697 698 699
                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;
700 701
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
702 703
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
704
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
705 706 707 708 709 710 711 712
                //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;
713
#ifdef MAVLINK_ENABLED_PIXHAWK
714 715
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
716 717 718 719 720 721 722 723 724 725 726
                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;
727

728 729
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
730 731 732 733 734 735 736 737 738 739 740
                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;
741 742
                }

743 744
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
745 746 747 748 749
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
750

LM's avatar
LM committed
751
                ++imagePacketsArrived;
752

LM's avatar
LM committed
753 754 755 756 757 758 759 760
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
761
            }
LM's avatar
LM committed
762
            break;
763
#endif
lm's avatar
lm committed
764 765 766 767 768 769 770 771
//        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;
772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790
        // 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
791
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
792 793 794
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
795
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
796 797 798
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
799
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
800 801 802
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
lm's avatar
lm committed
803
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
804 805 806
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
807
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
808 809 810
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
811
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
812 813 814
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
lm's avatar
lm committed
815
//                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
816 817 818 819 820
//                    break;
//                }
//            }
//        }
//        break;
lm's avatar
lm committed
821
#ifdef MAVLINK_ENABLED_UALBERTA
822 823
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
824 825 826
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
lm's avatar
lm committed
827 828 829 830 831 832
                // 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
833 834
            }
            break;
835 836
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
837 838
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
839 840 841 842 843 844
                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
845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863

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

865
#endif
LM's avatar
LM committed
866
            // Messages to ignore
867
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
lm's avatar
lm committed
868 869 870 871 872 873 874 875
        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:
        case MAVLINK_MSG_ID_DEBUG_VECT:
LM's avatar
LM committed
876
        case MAVLINK_MSG_ID_DEBUG:
877
            break;
878 879 880 881
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
882 883 884 885 886 887 888
                    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
889
            }
LM's avatar
LM committed
890
            break;
pixhawk's avatar
pixhawk committed
891 892 893 894
        }
    }
}

895 896
void UAS::setHomePosition(double lat, double lon, double alt)
{
897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929
    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);
    }
930 931
}

932 933 934 935 936 937 938 939 940 941 942 943 944 945
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()));


946 947
    if (ret == QMessageBox::Yes)
    {
948 949 950 951 952 953 954 955
        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);
956 957 958
    }
}

pixhawk's avatar
pixhawk committed
959 960
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
961
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
962
    mavlink_message_t msg;
LM's avatar
LM committed
963
    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
964
    sendMessage(msg);
965
#else
lm's avatar
lm committed
966 967 968 969
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
970
#endif
pixhawk's avatar
pixhawk committed
971 972
}

pixhawk's avatar
pixhawk committed
973 974
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
975
#ifdef MAVLINK_ENABLED_PIXHAWK
976 977 978
    mavlink_message_t msg;
    mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
    sendMessage(msg);
lm's avatar
lm committed
979
#else
980 981 982 983
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
984 985 986 987
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
988
{
989 990
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
991
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1);
992
    sendMessage(msg);
lm's avatar
lm committed
993 994
}

995
void UAS::startDataRecording()
lm's avatar
lm committed
996
{
997
    mavlink_message_t msg;
998
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2);
999
    sendMessage(msg);
lm's avatar
lm committed
1000 1001 1002 1003
}

void UAS::stopDataRecording()
{
1004
    mavlink_message_t msg;
1005
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0);
1006
    sendMessage(msg);
lm's avatar
lm committed
1007 1008
}

pixhawk's avatar
pixhawk committed
1009 1010
void UAS::startMagnetometerCalibration()
{
1011 1012
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1013
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0);
1014
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1015 1016 1017 1018
}

void UAS::startGyroscopeCalibration()
{
1019 1020
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1021
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0);
1022
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1023 1024 1025 1026
}

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

LM's avatar
LM committed
1033 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
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;
    }
}

1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090
/**
 * @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
1091 1092 1093 1094 1095 1096 1097 1098
/**
 * @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!
 */
1099 1100
quint64 UAS::getUnixTime(quint64 time)
{
1101
    quint64 ret = 0;
LM's avatar
LM committed
1102 1103
    if (attitudeStamped)
    {
1104
        ret = lastAttitude;
LM's avatar
LM committed
1105
    }
1106 1107
    if (time == 0)
    {
1108
        ret = QGC::groundTimeMilliseconds();
1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125
    }
    // 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
1126
#ifndef _MSC_VER
1127
    else if (time < 1261440000000000LLU)
1128
#else
LM's avatar
LM committed
1129
        else if (time < 1261440000000000)
1130
#endif
LM's avatar
LM committed
1131 1132
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1133 1134
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1135
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1136
        }
1137
        ret = time/1000 + onboardTimeOffset;
1138 1139 1140
    }
    else
    {
1141 1142
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1143
        ret = time/1000;
1144
    }
1145
    return ret;
1146 1147
}

1148 1149
QList<QString> UAS::getParameterNames(int component)
{
1150 1151
    if (parameters.contains(component))
    {
1152
        return parameters.value(component)->keys();
1153 1154 1155
    }
    else
    {
1156 1157 1158 1159 1160 1161 1162 1163 1164
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1165
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1166
{
1167
    if (mode >= (int)MAV_MODE_PREFLIGHT && mode < (int)MAV_MODE_ENUM_END)
1168
    {
1169
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1170
        mavlink_message_t msg;
1171
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
pixhawk's avatar
pixhawk committed
1172
        sendMessage(msg);
lm's avatar
lm committed
1173
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1174 1175 1176
    }
    else
    {
1177 1178
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1179 1180 1181 1182 1183
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1184 1185 1186 1187
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1188
            sendMessage(link, message);
1189 1190 1191
        }
        else
        {
1192 1193 1194
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1195 1196 1197
    }
}

1198 1199 1200 1201
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1202

1203 1204 1205 1206
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1207
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1208 1209 1210 1211 1212 1213
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1214
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1215 1216
                        sendMessage(serial, message);
                    }
1217 1218 1219 1220 1221 1222
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1223 1224
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1225
    if(!link) return;
pixhawk's avatar
pixhawk committed
1226 1227 1228
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1229
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1230 1231
    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
1232
    // If link is connected
1233 1234
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1235 1236 1237 1238 1239 1240 1241 1242
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1243
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1244
{
1245
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1246 1247
}

1248 1249
QString UAS::getNavModeText(int mode)
{
lm's avatar
lm committed
1250 1251
    if (autopilot == MAV_AUTOPILOT_PIXHAWK)
    {
1252 1253
    switch (mode)
    {
lm's avatar
lm committed
1254
    case 0:
1255
        return QString("PREFLIGHT");
1256 1257 1258 1259
        break;
    default:
        return QString("UNKNOWN");
    }
lm's avatar
lm committed
1260 1261 1262 1263 1264 1265 1266 1267 1268
    }
    else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        return QString("UNKNOWN");
    }
    else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
    {
        return QString("UNKNOWN");
    }
1269 1270
    // If nothing matches, return unknown
    return QString("UNKNOWN");
1271 1272
}

pixhawk's avatar
pixhawk committed
1273 1274
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1275 1276
    switch (statusCode)
    {
lm's avatar
lm committed
1277
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1278
        uasState = tr("UNINIT");
1279
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1280
        break;
lm's avatar
lm committed
1281
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1282
        uasState = tr("BOOT");
1283
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1284
        break;
lm's avatar
lm committed
1285
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1286
        uasState = tr("CALIBRATING");
1287
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1288
        break;
lm's avatar
lm committed
1289
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1290
        uasState = tr("ACTIVE");
1291
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1292
        break;
lm's avatar
lm committed
1293 1294
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1295
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1296 1297
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1298
        uasState = tr("CRITICAL");
1299
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1300
        break;
lm's avatar
lm committed
1301
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1302
        uasState = tr("EMERGENCY");
1303
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1304
        break;
James Goppert's avatar
James Goppert committed
1305
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1306 1307 1308
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1309

lm's avatar
lm committed
1310
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1311
        uasState = tr("SHUTDOWN");
1312
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1313
        break;
1314

lm's avatar
lm committed
1315
    default:
pixhawk's avatar
pixhawk committed
1316
        uasState = tr("UNKNOWN");
1317
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1318 1319 1320 1321
        break;
    }
}

1322 1323
QImage UAS::getImage()
{
LM's avatar
LM committed
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 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370
#ifdef MAVLINK_ENABLED_PIXHAWK

    qDebug() << "IMAGE TYPE:" << imageType;

    // RAW greyscale
    if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
    {
        // TODO FIXME Fabian
        // RAW hardcoded to 22x22
        int imgWidth = 22;
        int imgHeight = 22;
        int imgColors = 255;
        //const int headerSize = 15;

        // Construct PGM header
        QString header("P5\n%1 %2\n%3\n");
        header = header.arg(imgWidth).arg(imgHeight).arg(imgColors);

        QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size());
        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"))
        {
            qDebug()<< "could not create extracted image";
            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))
        {
           qDebug() << "Loading data from image buffer failed!";
        }
    }
1371 1372
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1373
    //imageRecBuffer.clear();
1374
    return image;
1375 1376
#else
	return QImage();
LM's avatar
LM committed
1377
#endif
1378

1379 1380 1381 1382
}

void UAS::requestImage()
{
1383
#ifdef MAVLINK_ENABLED_PIXHAWK
1384 1385
    qDebug() << "trying to get an image from the uas...";

1386 1387 1388
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1389 1390 1391 1392
        mavlink_message_t msg;
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50);
        sendMessage(msg);
    }
1393
#endif
1394
}
pixhawk's avatar
pixhawk committed
1395 1396 1397 1398 1399 1400 1401 1402 1403


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1404
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1405
{
1406 1407
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1408
        return 0;
1409 1410 1411
    }
    else
    {
pixhawk's avatar
pixhawk committed
1412 1413 1414 1415
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1416
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1417 1418 1419 1420
{
    return commStatus;
}

1421 1422 1423
void UAS::requestParameters()
{
    mavlink_message_t msg;
1424
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1425
    sendMessage(msg);
1426 1427
}

1428
void UAS::writeParametersToStorage()
1429
{
1430
    mavlink_message_t msg;
1431
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1);
1432
    sendMessage(msg);
1433 1434 1435 1436
}

void UAS::readParametersFromStorage()
{
1437
    mavlink_message_t msg;
1438
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1);
1439
    sendMessage(msg);
lm's avatar
lm committed
1440 1441
}

1442
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1443 1444
{
    // Buffers to write data to
1445
    mavlink_message_t msg;
1446
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1447 1448
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1449
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1450 1451
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1452 1453
    // TODO: use 0 to turn off and get rid of enable/disable? will require
    //  a different magic flag for turning on defaults, possibly something really high like 1111 ?
lm's avatar
lm committed
1454 1455
    stream.req_message_rate = 0;
    // Start / stop the message
1456
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1457 1458 1459 1460 1461
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1462
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1463 1464
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1465 1466 1467
    sendMessage(msg);
}

1468
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1469 1470 1471
{
    // Buffers to write data to
    mavlink_message_t msg;
1472
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1473
    // Select the message to request from now on
1474
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1475
    // Select the update rate in Hz the message should be send
1476
    stream.req_message_rate = rate;
lm's avatar
lm committed
1477
    // Start / stop the message
1478
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1479 1480 1481 1482 1483
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1484
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1485 1486
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1487 1488 1489
    sendMessage(msg);
}

1490
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1491
{
1492 1493 1494 1495
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1496
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1497
    // Select the update rate in Hz the message should be send
1498
    stream.req_message_rate = rate;
1499
    // Start / stop the message
1500
    stream.start_stop = (rate) ? 1 : 0;
1501 1502 1503 1504 1505 1506
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1507 1508
    // Send message twice to increase chance of reception
    sendMessage(msg);
1509
    sendMessage(msg);
lm's avatar
lm committed
1510
}
1511

1512
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1513
{
1514 1515 1516 1517 1518
#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
    mavlink_message_t msg;
    mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
    sendMessage(msg);
#else
1519 1520 1521
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1522
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1523
    // Select the update rate in Hz the message should be send
1524
    stream.req_message_rate = rate;
1525
    // Start / stop the message
1526
    stream.start_stop = (rate) ? 1 : 0;
1527 1528 1529 1530 1531 1532
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1533 1534
    // Send message twice to increase chance of reception
    sendMessage(msg);
1535
    sendMessage(msg);
1536
#endif
lm's avatar
lm committed
1537 1538
}

1539
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1540
{
1541 1542 1543 1544
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1545
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1546
    // Select the update rate in Hz the message should be send
1547
    stream.req_message_rate = rate;
1548
    // Start / stop the message
1549
    stream.start_stop = (rate) ? 1 : 0;
1550 1551 1552 1553 1554 1555
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1556 1557
    // Send message twice to increase chance of reception
    sendMessage(msg);
1558
    sendMessage(msg);
lm's avatar
lm committed
1559 1560
}

lm's avatar
lm committed
1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581
//void UAS::enableRawSensorFusionTransmission(int rate)
//{
//    // Buffers to write data to
//    mavlink_message_t msg;
//    mavlink_request_data_stream_t stream;
//    // Select the message to request from now on
//    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
//    // Select the update rate in Hz the message should be send
//    stream.req_message_rate = rate;
//    // Start / stop the message
//    stream.start_stop = (rate) ? 1 : 0;
//    // The system which should take this command
//    stream.target_system = uasId;
//    // The component / subsystem which should take this command
//    stream.target_component = 0;
//    // Encode and send the message
//    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
//}
1582

1583
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1584 1585 1586 1587 1588
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1589
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1590
    // Select the update rate in Hz the message should be send
1591
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1592
    // Start / stop the message
1593
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1605
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1606 1607 1608 1609 1610
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1611
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1612
    // Select the update rate in Hz the message should be send
1613
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1614
    // Start / stop the message
1615
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1627
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1628 1629 1630 1631 1632
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1633
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1634
    // Select the update rate in Hz the message should be send
1635
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1636
    // Start / stop the message
1637
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1649
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1650 1651 1652 1653 1654
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1655
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1656
    // Select the update rate in Hz the message should be send
1657
    stream.req_message_rate = rate;
1658
    // Start / stop the message
1659
    stream.start_stop = (rate) ? 1 : 0;
1660 1661 1662 1663 1664 1665
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1666 1667
    // Send message twice to increase chance of reception
    sendMessage(msg);
1668
    sendMessage(msg);
1669 1670
}

lm's avatar
lm committed
1671 1672 1673 1674 1675 1676 1677
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1678
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1679
{
1680 1681
    if (!id.isNull())
    {
1682 1683
        mavlink_message_t msg;
        mavlink_param_set_t p;
1684 1685 1686 1687 1688 1689 1690
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1691
            p.param_type = MAVLINK_TYPE_INT32_T;
1692 1693 1694
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1695
            p.param_type = MAVLINK_TYPE_UINT32_T;
1696 1697 1698
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1699
            p.param_type = MAVLINK_TYPE_FLOAT;
1700 1701 1702 1703 1704 1705 1706
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1707 1708 1709
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

1710 1711
        qDebug() << "SENT PARAM:" << value;

1712
        // Copy string into buffer, ensuring not to exceed the buffer size
1713 1714
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1715
            // String characters
1716 1717
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1718 1719
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1720 1721 1722 1723 1724
            //        // Null termination at end of string or end of buffer
            //        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
            //        {
            //            p.param_id[i] = '\0';
            //        }
1725
            // Zero fill
1726 1727
            else
            {
1728 1729
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1730
        }
1731 1732
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1733
    }
1734 1735
}

1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747
void UAS::requestParameter(int component, int parameter)
{
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
    read.param_index = parameter;
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << parameter;
}

1748 1749 1750 1751
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1752 1753 1754 1755
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1756
        case MAV_TYPE_FIXED_WING:
1757 1758
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1759
        case MAV_TYPE_QUADROTOR:
1760 1761 1762 1763 1764 1765 1766
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1767 1768 1769
void UAS::setUASName(const QString& name)
{
    this->name = name;
1770
    writeSettings();
1771
    emit nameChanged(name);
1772
    emit systemSpecsChanged(uasId);
1773 1774
}

lm's avatar
lm committed
1775 1776 1777
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1778
    mavlink_command_short_t cmd;
1779 1780 1781 1782 1783 1784 1785 1786
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
    cmd.target_system = uasId;
    cmd.target_component = 0;
1787
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1788 1789 1790 1791 1792 1793
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1794
    mavlink_command_short_t cmd;
1795 1796 1797 1798 1799 1800 1801 1802
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.target_system = uasId;
    cmd.target_component = component;
1803 1804 1805 1806 1807 1808 1809 1810
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{
    mavlink_message_t msg;
    mavlink_command_long_t cmd;
1811 1812 1813 1814 1815 1816
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1817 1818 1819
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1820 1821
    cmd.target_system = uasId;
    cmd.target_component = component;
1822
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1823 1824 1825
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1826
/**
lm's avatar
lm committed
1827
 * Launches the system
pixhawk's avatar
pixhawk committed
1828 1829 1830 1831
 *
 **/
void UAS::launch()
{
lm's avatar
lm committed
1832 1833 1834 1835 1836 1837 1838
    // FIXME MAVLINKV10PORTINGNEEDED
//    mavlink_message_t msg;
//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
//    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1839 1840 1841 1842 1843 1844
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1845
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1846
{
1847
    mavlink_message_t msg;
1848
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
1849
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1850 1851 1852 1853 1854 1855
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
1856
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
1857
{
1858
    mavlink_message_t msg;
1859
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
1860
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874
}

void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
{
    // Scale values
    double rollPitchScaling = 0.2f;
    double yawScaling = 0.5f;
    double thrustScaling = 1.0f;

    manualRollAngle = roll * rollPitchScaling;
    manualPitchAngle = pitch * rollPitchScaling;
    manualYawAngle = yaw * yawScaling;
    manualThrust = thrust * thrustScaling;

lm's avatar
lm committed
1875
    if(mode == (int)MAV_MODE_MANUAL_ARMED)
1876
    {
1877 1878 1879 1880
        mavlink_message_t message;
        mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
pixhawk's avatar
pixhawk committed
1881

1882
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
1883 1884 1885
    }
    else
    {
1886 1887
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1888 1889
}

1890 1891 1892 1893 1894
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1895 1896
void UAS::receiveButton(int buttonIndex)
{
1897 1898
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
1899
    case 0:
pixhawk's avatar
pixhawk committed
1900

pixhawk's avatar
pixhawk committed
1901 1902
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1903

pixhawk's avatar
pixhawk committed
1904 1905 1906 1907 1908
        break;
    default:

        break;
    }
1909
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1910 1911 1912

}

1913

pixhawk's avatar
pixhawk committed
1914 1915
void UAS::halt()
{
lm's avatar
lm committed
1916 1917 1918 1919 1920 1921 1922
    // FIXME MAVLINKV10PORTINGNEEDED
//    mavlink_message_t msg;
//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
//    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1923 1924 1925 1926
}

void UAS::go()
{
lm's avatar
lm committed
1927 1928 1929 1930 1931 1932 1933
    // FIXME MAVLINKV10PORTINGNEEDED
//    mavlink_message_t msg;
//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
//    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1934 1935 1936 1937 1938
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
lm's avatar
lm committed
1939 1940 1941 1942 1943 1944 1945
    // FIXME MAVLINKV10PORTINGNEEDED
//    mavlink_message_t msg;
//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
//    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1946 1947 1948 1949 1950 1951 1952 1953
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
lm's avatar
lm committed
1954 1955 1956 1957 1958 1959 1960
//    mavlink_message_t msg;
//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
//    // FIXME MAVLINKV10PORTINGNEEDED
//    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1961 1962 1963
}

/**
lm's avatar
lm committed
1964
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
1965 1966 1967 1968 1969 1970
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
lm's avatar
lm committed
1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996
    // FIXME MAVLINKV10PORTINGNEEDED
//    bool result = false;
//    QMessageBox msgBox;
//    msgBox.setIcon(QMessageBox::Critical);
//    msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
//    msgBox.setInformativeText("Do you want to cut power on all systems?");
//    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;
//        // TODO Replace MG System ID with static function call and allow to change ID in GUI
//        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
//        // Send message twice to increase chance of reception
//        sendMessage(msg);
//        sendMessage(msg);
//        result = true;
//    }
//    return result;
    return false;
pixhawk's avatar
pixhawk committed
1997 1998
}

lm's avatar
lm committed
1999 2000 2001 2002 2003
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2004
        startHil();
lm's avatar
lm committed
2005 2006 2007
    }
    else
    {
2008
        stopHil();
lm's avatar
lm committed
2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039
    }
}

/**
* @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)
*/
void UAS::sendHilState(uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
                    float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
                    int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
    mavlink_message_t msg;
    mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
    sendMessage(msg);
}


2040 2041
void UAS::startHil()
{
lm's avatar
lm committed
2042 2043
    // Connect Flight Gear Link
    simulation->connectSimulation();
2044
    mavlink_message_t msg;
2045
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_HIL_ENABLED);
2046
    sendMessage(msg);
2047 2048
}

2049 2050
void UAS::stopHil()
{
lm's avatar
lm committed
2051
    simulation->disconnectSimulation();
2052
    mavlink_message_t msg;
2053
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_HIL_ENABLED);
2054
    sendMessage(msg);
2055 2056 2057
}


pixhawk's avatar
pixhawk committed
2058 2059
void UAS::shutdown()
{
lm's avatar
lm committed
2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085
    // FIXME MAVLINKV10PORTINGNEEDED
//    bool result = false;
//    QMessageBox msgBox;
//    msgBox.setIcon(QMessageBox::Critical);
//    msgBox.setText("Shutting down the UAS");
//    msgBox.setInformativeText("Do you want to shut down the onboard computer?");

//    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)
//    {
//        // If the active UAS is set, execute command
//        mavlink_message_t msg;
//        // TODO Replace MG System ID with static function call and allow to change ID in GUI
//        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
//        // Send message twice to increase chance of reception
//        sendMessage(msg);
//        sendMessage(msg);

//        result = true;
//    }
pixhawk's avatar
pixhawk committed
2086 2087
}

2088 2089
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2090
    mavlink_message_t msg;
lm's avatar
lm committed
2091
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
2092 2093 2094 2095

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2096 2097
}

pixhawk's avatar
pixhawk committed
2098 2099 2100
/**
 * @return The name of this system as string in human-readable form
 */
2101
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2102 2103
{
    QString result;
2104 2105
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2106
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2107 2108 2109
    }
    else
    {
pixhawk's avatar
pixhawk committed
2110 2111 2112 2113 2114
        result = name;
    }
    return result;
}

2115 2116 2117 2118 2119
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2120 2121 2122 2123 2124 2125 2126 2127
QString UAS::getShortModeTextFor(int id)
{
    QString mode;

    switch (id) {
    case (uint8_t)MAV_MODE_PREFLIGHT:
        mode = "PREFLIGHT";
        break;
lm's avatar
lm committed
2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144
    case (uint8_t)MAV_MODE_MANUAL_ARMED:
        mode = "A|MANUAL";
        break;
    case (uint8_t)MAV_MODE_MANUAL_DISARMED:
        mode = "D|MANUAL";
        break;
    case (uint8_t)MAV_MODE_AUTO_ARMED:
        mode = "A|AUTO";
        break;
    case (uint8_t)MAV_MODE_AUTO_DISARMED:
        mode = "D|AUTO";
        break;
    case (uint8_t)MAV_MODE_GUIDED_ARMED:
        mode = "A|GUIDED";
        break;
    case (uint8_t)MAV_MODE_GUIDED_DISARMED:
        mode = "D|GUIDED";
2145
        break;
lm's avatar
lm committed
2146 2147
    case (uint8_t)MAV_MODE_STABILIZE_ARMED:
        mode = "A|STABILIZED";
2148
        break;
lm's avatar
lm committed
2149 2150
    case (uint8_t)MAV_MODE_STABILIZE_DISARMED:
        mode = "D|STABILIZED";
2151
        break;
lm's avatar
lm committed
2152 2153
    case (uint8_t)MAV_MODE_TEST_ARMED:
        mode = "A|TEST";
2154
        break;
lm's avatar
lm committed
2155 2156
    case (uint8_t)MAV_MODE_TEST_DISARMED:
        mode = "D|TEST";
2157 2158 2159 2160 2161 2162 2163 2164 2165
        break;
    default:
        mode = "UNKNOWN";
        break;
    }

    return mode;
}

2166 2167 2168 2169 2170
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2171 2172
void UAS::addLink(LinkInterface* link)
{
2173 2174
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2175
        links->append(link);
2176
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2177 2178 2179
    }
}

2180 2181 2182
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2183 2184
    if (link)
    {
2185 2186 2187 2188
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2189 2190 2191 2192 2193 2194 2195 2196 2197 2198 2199 2200 2201 2202 2203
/**
 * @brief Get the links associated with this robot
 *
 **/
QList<LinkInterface*>* UAS::getLinks()
{
    return links;
}



void UAS::setBattery(BatteryType type, int cells)
{
    this->batteryType = type;
    this->cells = cells;
2204 2205
    switch (batteryType)
    {
lm's avatar
lm committed
2206
    case NICD:
pixhawk's avatar
pixhawk committed
2207
        break;
lm's avatar
lm committed
2208
    case NIMH:
pixhawk's avatar
pixhawk committed
2209
        break;
lm's avatar
lm committed
2210
    case LIION:
pixhawk's avatar
pixhawk committed
2211
        break;
lm's avatar
lm committed
2212
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2213 2214 2215
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2216
    case LIFE:
pixhawk's avatar
pixhawk committed
2217
        break;
lm's avatar
lm committed
2218
    case AGZN:
pixhawk's avatar
pixhawk committed
2219 2220 2221 2222
        break;
    }
}

2223 2224
void UAS::setBatterySpecs(const QString& specs)
{
2225 2226
    if (specs.length() == 0 || specs.contains("%"))
    {
2227
        batteryRemainingEstimateEnabled = false;
2228
        bool ok;
2229 2230 2231
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2232 2233
        if (ok)
        {
2234
            warnLevelPercent = temp;
2235 2236 2237
        }
        else
        {
2238 2239
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2240 2241 2242
    }
    else
    {
2243 2244 2245 2246 2247
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2248 2249
        if (parts.length() == 3)
        {
2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260
            float temp;
            bool ok;
            // Get the empty voltage
            temp = parts.at(0).toFloat(&ok);
            if (ok) emptyVoltage = temp;
            // Get the warning voltage
            temp = parts.at(1).toFloat(&ok);
            if (ok) warnVoltage = temp;
            // Get the full voltage
            temp = parts.at(2).toFloat(&ok);
            if (ok) fullVoltage = temp;
2261 2262 2263
        }
        else
        {
2264 2265
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2266 2267 2268 2269 2270
    }
}

QString UAS::getBatterySpecs()
{
2271 2272
    if (batteryRemainingEstimateEnabled)
    {
2273
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2274 2275 2276
    }
    else
    {
2277 2278
        return QString("%1%").arg(warnLevelPercent);
    }
2279 2280
}

pixhawk's avatar
pixhawk committed
2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293
int UAS::calculateTimeRemaining()
{
    quint64 dt = MG::TIME::getGroundTimeNow() - startTime;
    double seconds = dt / 1000.0f;
    double voltDifference = startVoltage - currentVoltage;
    if (voltDifference <= 0) voltDifference = 0.00000000001f;
    double dischargePerSecond = voltDifference / seconds;
    int remaining = static_cast<int>((currentVoltage - emptyVoltage) / dischargePerSecond);
    // Can never be below 0
    if (remaining < 0) remaining = 0;
    return remaining;
}

lm's avatar
lm committed
2294 2295 2296
/**
 * @return charge level in percent - 0 - 100
 */
2297
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2298
{
2299 2300 2301 2302
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2303
            chargeLevel = 0.0f;
2304 2305 2306
        }
        else if (lpVoltage > fullVoltage)
        {
2307
            chargeLevel = 100.0f;
2308 2309 2310
        }
        else
        {
2311 2312
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2313 2314
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2315 2316
}

lm's avatar
lm committed
2317 2318
void UAS::startLowBattAlarm()
{
2319 2320
    if (!lowBattAlarm)
    {
2321
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2322
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2323 2324 2325 2326 2327 2328
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2329 2330
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2331 2332 2333 2334
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}