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

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

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

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

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

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

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

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

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

137 138
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
139 140
    if (positionLock)
    {
141
        positionLock = false;
142 143 144 145 146
    }
    else
    {
        if ((mode == (int)MAV_MODE_AUTO || mode == (int)MAV_MODE_GUIDED) && positionLock)
        {
147 148 149 150 151
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

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

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

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

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

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

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

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

237 238 239 240 241 242
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
LM's avatar
LM committed
243 244


245 246 247 248 249 250 251
            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);
252

253
                shortStateText = uasState;
254

255 256
                stateAudio = tr(" changed status to ") + uasState;
            }
lm's avatar
lm committed
257

258
            if (this->mode != static_cast<int>(state.base_mode))
259 260
            {
                modechanged = true;
261
                this->mode = static_cast<int>(state.base_mode);
pixhawk's avatar
pixhawk committed
262

263

264
                shortModeText = getShortModeTextFor(this->mode);
265

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

268 269
                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed
270

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

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

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

300 301 302 303 304 305
            if (state.system_status == MAV_STATE_POWEROFF)
            {
                emit systemRemoved(this);
                emit systemRemoved();
            }
}
306

307 308 309 310 311 312 313 314 315 316
            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);
317

318 319
                emit loadChanged(this,state.load/10.0f);
                emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
320

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

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

LM's avatar
LM committed
343
                // COMMUNICATIONS DROP RATE
344 345
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
346
            }
LM's avatar
LM committed
347
            break;
348

349 350
        case MAVLINK_MSG_ID_RAW_IMU:
            {
LM's avatar
LM committed
351 352
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
353
                quint64 time = getUnixTime(raw.time_usec);
LM's avatar
LM committed
354 355 356 357 358 359 360 361 362 363 364 365

                emit valueChanged(uasId, "accel x", "raw", static_cast<double>(raw.xacc), time);
                emit valueChanged(uasId, "accel y", "raw", static_cast<double>(raw.yacc), time);
                emit valueChanged(uasId, "accel z", "raw", static_cast<double>(raw.zacc), time);
                emit valueChanged(uasId, "gyro roll", "raw", static_cast<double>(raw.xgyro), time);
                emit valueChanged(uasId, "gyro pitch", "raw", static_cast<double>(raw.ygyro), time);
                emit valueChanged(uasId, "gyro yaw", "raw", static_cast<double>(raw.zgyro), time);
                emit valueChanged(uasId, "mag x", "raw", static_cast<double>(raw.xmag), time);
                emit valueChanged(uasId, "mag y", "raw", static_cast<double>(raw.ymag), time);
                emit valueChanged(uasId, "mag z", "raw", static_cast<double>(raw.zmag), time);
            }
            break;
366 367
        case MAVLINK_MSG_ID_SCALED_IMU:
            {
LM's avatar
LM committed
368 369
                mavlink_scaled_imu_t scaled;
                mavlink_msg_scaled_imu_decode(&message, &scaled);
370
                quint64 time = getUnixTime(scaled.time_boot_ms);
LM's avatar
LM committed
371 372 373 374 375 376 377

                emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time);
                emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time);
                emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time);
                emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time);
                emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time);
                emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time);
378 379 380
                emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time);
                emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time);
                emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, time);
LM's avatar
LM committed
381 382
            }
            break;
pixhawk's avatar
pixhawk committed
383 384
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
385
            //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
386 387 388
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
389
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
390
                lastAttitude = time;
LM's avatar
LM committed
391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);
                emit valueChanged(uasId, "roll", "rad", roll, time);
                emit valueChanged(uasId, "pitch", "rad", pitch, time);
                emit valueChanged(uasId, "yaw", "rad", yaw, time);
                emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time);
                emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time);
                emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time);

                // Emit in angles

                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
                while (compass > 360.0f) {
                    compass -= 360.0f;
                }
lm's avatar
lm committed
409

LM's avatar
LM committed
410
                attitudeKnown = true;
lm's avatar
lm committed
411

LM's avatar
LM committed
412 413 414 415 416 417
                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
                emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
418

419
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
420
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
421
            }
LM's avatar
LM committed
422
            break;
lm's avatar
lm committed
423 424 425 426
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
427
                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
428 429
            }
            break;
430 431
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
432 433 434 435 436 437 438 439 440 441 442 443
                mavlink_vfr_hud_t hud;
                mavlink_msg_vfr_hud_decode(&message, &hud);
                quint64 time = getUnixTime();
                // Display updated values
                emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
                emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
                emit valueChanged(uasId, "altitude", "m", hud.alt, time);
                emit valueChanged(uasId, "heading", "deg", hud.heading, time);
                emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
                emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
                emit thrustChanged(this, hud.throttle/100.0);

444 445
                if (!attitudeKnown)
                {
LM's avatar
LM committed
446 447 448
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
449

LM's avatar
LM committed
450 451 452 453 454 455
                emit altitudeChanged(uasId, hud.alt);
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
            }
            break;
456 457
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
458 459 460 461 462 463 464 465 466 467 468 469 470 471
                mavlink_nav_controller_output_t nav;
                mavlink_msg_nav_controller_output_decode(&message, &nav);
                quint64 time = getUnixTime();
                // Update UI
                emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
                emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
                emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
                emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
                emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
                emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
                emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
            }
            break;
472
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
473
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
474
            //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
475 476 477
            {
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
478
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
                emit valueChanged(uasId, "x", "m", pos.x, time);
                emit valueChanged(uasId, "y", "m", pos.y, time);
                emit valueChanged(uasId, "z", "m", pos.z, time);
                emit valueChanged(uasId, "x speed", "m/s", pos.vx, time);
                emit valueChanged(uasId, "y speed", "m/s", pos.vy, time);
                emit valueChanged(uasId, "z speed", "m/s", pos.vz, time);
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);

                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;

                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
501
            }
LM's avatar
LM committed
502
            break;
503
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
504 505
            //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
506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530
            {
                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 valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
                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;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
531
            }
LM's avatar
LM committed
532
            break;
533 534
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
535 536 537 538 539
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

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

543 544 545 546 547 548
                emit valueChanged(uasId, "gps latitude", "deg", pos.lat/(double)1E7, time);
                emit valueChanged(uasId, "gps longitude", "deg", pos.lon/(double)1E7, time);
                emit valueChanged(uasId, "gps speed", "m/s", pos.vel, time);
                emit valueChanged(uasId, "gps eph", "m", pos.eph/(double)1E2, time);
                emit valueChanged(uasId, "gps epv", "m", pos.eph/(double)1E2, time);
                emit valueChanged(uasId, "gps fix", "raw", pos.fix_type, time);
549
                emit valueChanged(uasId, "gps course", "raw", pos.cog, time);
LM's avatar
LM committed
550

LM's avatar
LM committed
551
                if (pos.fix_type > 2) {
LM's avatar
LM committed
552 553 554 555 556 557 558 559 560 561 562 563 564 565
                    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");
                    }
                    emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
                    // Smaller than threshold and not NaN
LM's avatar
LM committed
566 567 568 569 570

                    float vel = pos.vel/100.0f;

                    if (vel < 1000000 && !isnan(vel) && !isinf(vel)) {
                        emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
571 572 573
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
LM's avatar
LM committed
574
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
575
                    }
lm's avatar
lm committed
576 577
                }
            }
LM's avatar
LM committed
578
            break;
579 580
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
581 582
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
583 584
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
585 586
                    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]));
                }
587
            }
LM's avatar
LM committed
588
            break;
589
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
590
            {
591 592
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
593
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
594 595
            }
            break;
596 597
        case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
LM's avatar
LM committed
598 599
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
600
                quint64 time = this->getUnixTime(pressure.time_usec);
LM's avatar
LM committed
601 602 603 604 605 606
                emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time);
                emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time);
            }
            break;
607

608 609
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            {
LM's avatar
LM committed
610 611
                mavlink_scaled_pressure_t pressure;
                mavlink_msg_scaled_pressure_decode(&message, &pressure);
612
                quint64 time = this->getUnixTime(pressure.time_boot_ms);
LM's avatar
LM committed
613 614 615 616 617
                emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
                emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
            }
            break;
618

619 620
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
621 622 623 624 625 626 627 628 629 630 631
                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);
632 633 634 635 636 637 638 639 640
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time);
                emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time);
                emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time);
                emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time);
                emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time);
                emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time);
                emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time);
                emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time);
LM's avatar
LM committed
641 642
            }
            break;
643 644
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
645 646 647 648 649 650 651 652 653 654 655
                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
656
            }
LM's avatar
LM committed
657
            break;
658 659
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
660 661 662 663 664
                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;
665 666 667 668 669 670 671 672 673 674
                mavlink_param_union_t val;
                val.param_float = value.param_value;

                // Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP
//   buffer[bindex]   = (b>>24)&0xff;
//   buffer[bindex+1] = (b>>16)&0xff;
//   buffer[bindex+2] = (b>>8)&0xff;
//   buffer[bindex+3] = (b & 0xff);
//#else
LM's avatar
LM committed
675 676

                // Insert component if necessary
677 678
                if (!parameters.contains(component))
                {
679
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
680
                }
681

LM's avatar
LM committed
682 683
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
684

685 686 687
                // Insert with correct type
                switch (value.param_type)
                {
688
                case MAVLINK_TYPE_FLOAT:
689 690 691 692 693
                    parameters.value(component)->insert(parameterName, val.param_float);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, val.param_float);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float);
                    break;
694
                case MAVLINK_TYPE_UINT32_T:
695 696 697 698 699
                    parameters.value(component)->insert(parameterName, val.param_uint32);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, val.param_uint32);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32);
                    break;
700
                case MAVLINK_TYPE_INT32_T:
701 702 703 704 705 706 707 708
                    parameters.value(component)->insert(parameterName, val.param_int32);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, val.param_int32);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32);
                    break;
                default:
                    qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
                }
LM's avatar
LM committed
709 710
            }
            break;
711 712 713
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
714 715
            if (ack.result == 1)
            {
716
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
717 718 719
            }
            else
            {
720
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
721 722
            }
            break;
pixhawk's avatar
pixhawk committed
723
        case MAVLINK_MSG_ID_DEBUG:
724
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
725
            break;
LM's avatar
LM committed
726
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
727
            {
LM's avatar
LM committed
728 729
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
730
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
LM's avatar
LM committed
731 732 733 734 735
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
                emit valueChanged(uasId, "att control roll", "rad", out.roll, time);
                emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time);
                emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time);
                emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time);
LM's avatar
LM committed
736 737
            }
            break;
738 739
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
LM's avatar
LM committed
740 741
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
742 743
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
744 745
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
746 747 748 749
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
750
            }
LM's avatar
LM committed
751
            break;
pixhawk's avatar
pixhawk committed
752

753 754
        case MAVLINK_MSG_ID_WAYPOINT:
            {
LM's avatar
LM committed
755 756 757
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
758 759
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
760 761
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
762 763 764 765
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
766
            }
LM's avatar
LM committed
767
            break;
pixhawk's avatar
pixhawk committed
768

769 770
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
LM's avatar
LM committed
771 772
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
773 774
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
775 776
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
777
            }
LM's avatar
LM committed
778
            break;
779

780 781
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
LM's avatar
LM committed
782 783
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
784 785
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
786 787
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
788 789 790 791
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
792
            }
LM's avatar
LM committed
793
            break;
pixhawk's avatar
pixhawk committed
794

795 796
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
            {
LM's avatar
LM committed
797 798 799 800 801 802 803 804
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                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
805

806 807
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
            {
LM's avatar
LM committed
808 809 810 811 812
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed
813

814 815
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
816 817 818 819 820
                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;
821 822
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
LM's avatar
LM committed
823 824 825 826 827 828 829 830 831 832 833 834 835
                mavlink_servo_output_raw_t servos;
                mavlink_msg_servo_output_raw_decode(&message, &servos);
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time);
                emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time);
                emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time);
                emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time);
                emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time);
                emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time);
                emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time);
                emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time);
            }
            break;
836 837
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
838 839
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
840
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
841 842 843 844 845 846 847 848
                //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;
849
#ifdef MAVLINK_ENABLED_PIXHAWK
850 851
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
852 853 854 855 856 857 858 859 860 861 862
                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;
863

864 865
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
866 867 868 869 870 871 872 873 874 875 876
                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;
877 878
                }

879 880
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
881 882 883 884 885
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
886

LM's avatar
LM committed
887
                ++imagePacketsArrived;
888

LM's avatar
LM committed
889 890 891 892 893 894 895 896
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
897
            }
LM's avatar
LM committed
898
            break;
899
#endif
900
        case MAVLINK_MSG_ID_DEBUG_VECT:
901 902 903 904
        {
            mavlink_debug_vect_t vect;
            mavlink_msg_debug_vect_decode(&message, &vect);
            QString str((const char*)vect.name);
905
            quint64 time = getUnixTime(vect.time_usec);
906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975
            emit valueChanged(uasId, str+".x", "raw", vect.x, time);
            emit valueChanged(uasId, str+".y", "raw", vect.y, time);
            emit valueChanged(uasId, str+".z", "raw", vect.z, time);
        }
        break;
        // 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++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
//                    break;
//                }
//            }
//        }
//        break;
				//#ifdef MAVLINK_ENABLED_PIXHAWK
				//            case MAVLINK_MSG_ID_POINT_OF_INTEREST:
				//            {
				//                mavlink_point_of_interest_t poi;
				//                mavlink_msg_point_of_interest_decode(&message, &poi);
				//                emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
				//            }
				//            break;
				//            case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
				//            {
				//                mavlink_point_of_interest_connection_t poi;
				//                mavlink_msg_point_of_interest_connection_decode(&message, &poi);
				//                emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
				//            }
				//            break;
				//#endif
lm's avatar
lm committed
976
#ifdef MAVLINK_ENABLED_UALBERTA
977 978
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
979 980 981 982 983 984 985 986 987 988 989
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
            }
            break;
990 991
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
992 993
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
994 995 996 997 998 999
                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
1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018

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

1020
#endif
LM's avatar
LM committed
1021
            // Messages to ignore
1022
        case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
1023
            break;
1024 1025 1026 1027
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
1028 1029 1030 1031 1032 1033 1034
                    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
1035
            }
LM's avatar
LM committed
1036
            break;
pixhawk's avatar
pixhawk committed
1037 1038 1039 1040
        }
    }
}

1041 1042 1043
void UAS::setHomePosition(double lat, double lon, double alt)
{
    // Send new home position to UAS
1044
    mavlink_set_gps_global_origin_t home;
1045 1046 1047 1048
    home.target_system = uasId;
    home.latitude = lat*1E7;
    home.longitude = lon*1E7;
    home.altitude = alt*1000;
1049
    qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
1050
    mavlink_message_t msg;
1051
    mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
1052 1053 1054
    sendMessage(msg);
}

1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069
void UAS::setLocalOriginAtCurrentGPSPosition()
{
    bool result = false;
    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()));


1070 1071
    if (ret == QMessageBox::Yes)
    {
lm's avatar
lm committed
1072 1073 1074 1075 1076 1077 1078 1079 1080
        // FIXME MAVLINKV10PORTINGNEEDED
//        mavlink_message_t msg;
//        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
//        // Send message twice to increase chance that it reaches its goal
//        sendMessage(msg);
//        // Wait 5 ms
//        MG::SLEEP::usleep(5000);
//        // Send again
//        sendMessage(msg);
1081 1082 1083 1084
        result = true;
    }
}

pixhawk's avatar
pixhawk committed
1085 1086
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1087
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1088
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1089 1090
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
1091
#else
lm's avatar
lm committed
1092 1093 1094 1095
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1096
#endif
pixhawk's avatar
pixhawk committed
1097 1098
}

pixhawk's avatar
pixhawk committed
1099 1100
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1101
#ifdef MAVLINK_ENABLED_PIXHAWK
1102 1103 1104
    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
1105
#else
1106 1107 1108 1109
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1110 1111 1112 1113
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1114
{
1115 1116
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1117
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1);
1118
    sendMessage(msg);
lm's avatar
lm committed
1119 1120
}

1121
void UAS::startDataRecording()
lm's avatar
lm committed
1122
{
1123
    mavlink_message_t msg;
1124
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2);
1125
    sendMessage(msg);
lm's avatar
lm committed
1126 1127 1128 1129
}

void UAS::stopDataRecording()
{
1130
    mavlink_message_t msg;
1131
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0);
1132
    sendMessage(msg);
lm's avatar
lm committed
1133 1134
}

pixhawk's avatar
pixhawk committed
1135 1136
void UAS::startMagnetometerCalibration()
{
1137 1138
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1139
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0);
1140
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1141 1142 1143 1144
}

void UAS::startGyroscopeCalibration()
{
1145 1146
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1147
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0);
1148
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1149 1150 1151 1152
}

void UAS::startPressureCalibration()
{
1153 1154
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1155
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0);
1156
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1157 1158
}

LM's avatar
LM committed
1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203
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;
    }
}

1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216
/**
 * @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
1217 1218 1219 1220 1221 1222 1223 1224
/**
 * @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!
 */
1225 1226
quint64 UAS::getUnixTime(quint64 time)
{
LM's avatar
LM committed
1227 1228 1229 1230
    if (attitudeStamped)
    {
        return lastAttitude;
    }
1231 1232
    if (time == 0)
    {
LM's avatar
LM committed
1233
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
LM's avatar
LM committed
1234
        return QGC::groundTimeMilliseconds();
1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251
    }
    // 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
1252
#ifndef _MSC_VER
1253
    else if (time < 1261440000000000LLU)
1254
#else
LM's avatar
LM committed
1255
        else if (time < 1261440000000000)
1256
#endif
LM's avatar
LM committed
1257 1258
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1259 1260
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1261
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1262
        }
1263
        return time/1000 + onboardTimeOffset;
1264 1265 1266
    }
    else
    {
1267 1268
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1269
        return time/1000;
1270 1271 1272
    }
}

1273 1274
QList<QString> UAS::getParameterNames(int component)
{
1275 1276
    if (parameters.contains(component))
    {
1277
        return parameters.value(component)->keys();
1278 1279 1280
    }
    else
    {
1281 1282 1283 1284 1285 1286 1287 1288 1289
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1290
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1291
{
1292
    if (mode >= (int)MAV_MODE_PREFLIGHT && mode < (int)MAV_MODE_ENUM_END)
1293
    {
1294
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1295
        mavlink_message_t msg;
1296
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
pixhawk's avatar
pixhawk committed
1297
        sendMessage(msg);
lm's avatar
lm committed
1298
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1299 1300 1301
    }
    else
    {
1302 1303
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1304 1305 1306 1307 1308
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1309 1310 1311 1312
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1313
            sendMessage(link, message);
1314 1315 1316
        }
        else
        {
1317 1318 1319
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1320 1321 1322
    }
}

1323 1324 1325 1326
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1327

1328 1329 1330 1331
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1332
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1333 1334 1335 1336 1337 1338
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1339
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1340 1341
                        sendMessage(serial, message);
                    }
1342 1343 1344 1345 1346 1347
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1348 1349
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1350
    if(!link) return;
pixhawk's avatar
pixhawk committed
1351 1352 1353
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1354
    int len = mavlink_msg_to_send_buffer(buffer, &message);
lm's avatar
lm committed
1355 1356
    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
1357
    // If link is connected
1358 1359
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1360 1361 1362 1363 1364 1365 1366 1367
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1368
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1369
{
1370
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1371 1372
}

1373 1374
QString UAS::getNavModeText(int mode)
{
1375 1376
    switch (mode)
    {
1377
    case MAV_AUTOPILOT_CUSTOM_MODE_PREFLIGHT:
1378
        return QString("PREFLIGHT");
1379
        break;
1380
    case MAV_AUTOPILOT_CUSTOM_MODE_MANUAL:
1381
        return QString("MANUAL");
1382
        break;
1383
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_TAKEOFF:
1384
        return QString("TAKEOFF");
1385
        break;
1386
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_HOLD:
1387
        return QString("HOLDING");
1388
        break;
1389
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION:
1390
        return QString("MISSION");
1391
        break;
1392
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_VECTOR:
1393
        return QString("VECTOR");
1394
        break;
1395
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_RETURNING:
1396 1397
        return QString("RETURNING");
        break;
1398
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_LANDING:
1399 1400
        return QString("LANDING");
        break;
1401
    case MAV_AUTOPILOT_CUSTOM_MODE_AUTO_LOST:
1402 1403
        return QString("LOST");
        break;
1404
    case MAV_AUTOPILOT_CUSTOM_MODE_STABILIZE_RATES_ACRO:
1405 1406
        return QString("S: RATE/ACRO");
        break;
1407
    case MAV_AUTOPILOT_CUSTOM_MODE_STABILIZE_LEVELING:
1408
        return QString("S: LEVELING");
1409
        break;
1410
    case MAV_AUTOPILOT_CUSTOM_MODE_STABILIZE_ROLL_PITCH_ABSOLUTE:
1411 1412
        return QString("S: R/P ABS");
        break;
1413
    case MAV_AUTOPILOT_CUSTOM_MODE_STABILIZE_ROLL_YAW_ALTITUDE:
1414 1415
        return QString("S: R/Y ALT");
        break;
1416
    case MAV_AUTOPILOT_CUSTOM_MODE_STABILIZE_ROLL_PITCH_YAW_ALTITUDE:
1417
        return QString("S: R/P/Y ALT");
1418
        break;
1419
    case MAV_AUTOPILOT_CUSTOM_MODE_STABILIZE_CURSOR_CONTROL:
1420
        return QString("S: CURSOR");
1421 1422 1423 1424 1425 1426
        break;
    default:
        return QString("UNKNOWN");
    }
}

pixhawk's avatar
pixhawk committed
1427 1428
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1429 1430
    switch (statusCode)
    {
lm's avatar
lm committed
1431
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1432
        uasState = tr("UNINIT");
1433
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1434
        break;
lm's avatar
lm committed
1435
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1436
        uasState = tr("BOOT");
1437
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1438
        break;
lm's avatar
lm committed
1439
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1440
        uasState = tr("CALIBRATING");
1441
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1442
        break;
lm's avatar
lm committed
1443
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1444
        uasState = tr("ACTIVE");
1445
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1446
        break;
lm's avatar
lm committed
1447 1448
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1449
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1450 1451
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1452
        uasState = tr("CRITICAL");
1453
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1454
        break;
lm's avatar
lm committed
1455
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1456
        uasState = tr("EMERGENCY");
1457
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1458
        break;
James Goppert's avatar
James Goppert committed
1459
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1460 1461 1462
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1463

lm's avatar
lm committed
1464
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1465
        uasState = tr("SHUTDOWN");
1466
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1467
        break;
1468

lm's avatar
lm committed
1469
    default:
pixhawk's avatar
pixhawk committed
1470
        uasState = tr("UNKNOWN");
1471
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1472 1473 1474 1475
        break;
    }
}

1476 1477
QImage UAS::getImage()
{
LM's avatar
LM committed
1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524
#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!";
        }
    }
1525 1526
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1527
    //imageRecBuffer.clear();
1528
    return image;
1529 1530
#else
	return QImage();
LM's avatar
LM committed
1531
#endif
1532

1533 1534 1535 1536
}

void UAS::requestImage()
{
1537
#ifdef MAVLINK_ENABLED_PIXHAWK
1538 1539
    qDebug() << "trying to get an image from the uas...";

1540 1541 1542
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1543 1544 1545 1546
        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);
    }
1547
#endif
1548
}
pixhawk's avatar
pixhawk committed
1549 1550 1551 1552 1553 1554 1555 1556 1557


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1558
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1559
{
1560 1561
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1562
        return 0;
1563 1564 1565
    }
    else
    {
pixhawk's avatar
pixhawk committed
1566 1567 1568 1569
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1570
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1571 1572 1573 1574
{
    return commStatus;
}

1575 1576 1577
void UAS::requestParameters()
{
    mavlink_message_t msg;
1578
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1579
    sendMessage(msg);
1580 1581
}

1582
void UAS::writeParametersToStorage()
1583
{
1584
    mavlink_message_t msg;
1585
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1);
1586
    sendMessage(msg);
1587 1588 1589 1590
}

void UAS::readParametersFromStorage()
{
1591
    mavlink_message_t msg;
1592
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1);
1593
    sendMessage(msg);
lm's avatar
lm committed
1594 1595
}

1596
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1597 1598
{
    // Buffers to write data to
1599
    mavlink_message_t msg;
1600
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1601 1602
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1603
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1604 1605
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1606 1607
    // 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
1608 1609
    stream.req_message_rate = 0;
    // Start / stop the message
1610
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1611 1612 1613 1614 1615
    // 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
1616
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1617 1618
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1619 1620 1621
    sendMessage(msg);
}

1622
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1623 1624 1625
{
    // Buffers to write data to
    mavlink_message_t msg;
1626
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1627
    // Select the message to request from now on
1628
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1629
    // Select the update rate in Hz the message should be send
1630
    stream.req_message_rate = rate;
lm's avatar
lm committed
1631
    // Start / stop the message
1632
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1633 1634 1635 1636 1637
    // 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
1638
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1639 1640
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1641 1642 1643
    sendMessage(msg);
}

1644
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1645
{
1646 1647 1648 1649
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1650
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1651
    // Select the update rate in Hz the message should be send
1652
    stream.req_message_rate = rate;
1653
    // Start / stop the message
1654
    stream.start_stop = (rate) ? 1 : 0;
1655 1656 1657 1658 1659 1660
    // 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);
1661 1662
    // Send message twice to increase chance of reception
    sendMessage(msg);
1663
    sendMessage(msg);
lm's avatar
lm committed
1664
}
1665

1666
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1667
{
1668 1669 1670 1671 1672
#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
1673 1674 1675
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1676
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1677
    // Select the update rate in Hz the message should be send
1678
    stream.req_message_rate = rate;
1679
    // Start / stop the message
1680
    stream.start_stop = (rate) ? 1 : 0;
1681 1682 1683 1684 1685 1686
    // 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);
1687 1688
    // Send message twice to increase chance of reception
    sendMessage(msg);
1689
    sendMessage(msg);
1690
#endif
lm's avatar
lm committed
1691 1692
}

1693
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1694
{
1695 1696 1697 1698
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1699
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1700
    // Select the update rate in Hz the message should be send
1701
    stream.req_message_rate = rate;
1702
    // Start / stop the message
1703
    stream.start_stop = (rate) ? 1 : 0;
1704 1705 1706 1707 1708 1709
    // 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);
1710 1711
    // Send message twice to increase chance of reception
    sendMessage(msg);
1712
    sendMessage(msg);
lm's avatar
lm committed
1713 1714
}

lm's avatar
lm committed
1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735
//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);
//}
1736

1737
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1738 1739 1740 1741 1742
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1743
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1744
    // Select the update rate in Hz the message should be send
1745
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1746
    // Start / stop the message
1747
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758
    // 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);
}

1759
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1760 1761 1762 1763 1764
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1765
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1766
    // Select the update rate in Hz the message should be send
1767
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1768
    // Start / stop the message
1769
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780
    // 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);
}

1781
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1782 1783 1784 1785 1786
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1787
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1788
    // Select the update rate in Hz the message should be send
1789
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1790
    // Start / stop the message
1791
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802
    // 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);
}

1803
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1804 1805 1806 1807 1808
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1809
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1810
    // Select the update rate in Hz the message should be send
1811
    stream.req_message_rate = rate;
1812
    // Start / stop the message
1813
    stream.start_stop = (rate) ? 1 : 0;
1814 1815 1816 1817 1818 1819
    // 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);
1820 1821
    // Send message twice to increase chance of reception
    sendMessage(msg);
1822
    sendMessage(msg);
1823 1824
}

lm's avatar
lm committed
1825 1826 1827 1828 1829 1830 1831
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1832
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
lm's avatar
lm committed
1833
{
1834 1835
    if (!id.isNull())
    {
1836 1837
        mavlink_message_t msg;
        mavlink_param_set_t p;
1838 1839 1840 1841 1842 1843 1844
        mavlink_param_union_t union_value;

        // Assign correct value based on QVariant
        switch (value.type())
        {
        case QVariant::Int:
            union_value.param_int32 = value.toInt();
1845
            p.param_type = MAVLINK_TYPE_INT32_T;
1846 1847 1848
            break;
        case QVariant::UInt:
            union_value.param_uint32 = value.toUInt();
1849
            p.param_type = MAVLINK_TYPE_UINT32_T;
1850 1851 1852
            break;
        case QMetaType::Float:
            union_value.param_float = value.toFloat();
1853
            p.param_type = MAVLINK_TYPE_FLOAT;
1854 1855 1856 1857 1858 1859 1860
            break;
        default:
            qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
            return;
        }

        p.param_value = union_value.param_float;
1861 1862 1863 1864
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

        // Copy string into buffer, ensuring not to exceed the buffer size
1865 1866
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1867
            // String characters
1868 1869
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1870 1871
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1872 1873 1874 1875 1876
            //        // 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';
            //        }
1877
            // Zero fill
1878 1879
            else
            {
1880 1881
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1882
        }
1883 1884
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1885
    }
1886 1887
}

1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899
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;
}

1900 1901 1902 1903
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1904 1905 1906 1907
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1908
        case MAV_TYPE_FIXED_WING:
1909 1910
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1911
        case MAV_TYPE_QUADROTOR:
1912 1913 1914 1915 1916 1917 1918
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1919 1920 1921
void UAS::setUASName(const QString& name)
{
    this->name = name;
1922
    writeSettings();
1923
    emit nameChanged(name);
1924
    emit systemSpecsChanged(uasId);
1925 1926
}

lm's avatar
lm committed
1927 1928 1929
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1930
    mavlink_command_short_t cmd;
1931 1932 1933 1934 1935 1936 1937 1938
    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;
1939
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1940 1941 1942 1943 1944 1945
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1946
    mavlink_command_short_t cmd;
1947 1948 1949 1950 1951 1952 1953 1954
    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;
1955 1956 1957 1958 1959 1960 1961 1962
    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;
1963 1964 1965 1966 1967 1968
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1969 1970 1971
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1972 1973
    cmd.target_system = uasId;
    cmd.target_component = component;
1974
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1975 1976 1977
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1978
/**
lm's avatar
lm committed
1979
 * Launches the system
pixhawk's avatar
pixhawk committed
1980 1981 1982 1983
 *
 **/
void UAS::launch()
{
lm's avatar
lm committed
1984 1985 1986 1987 1988 1989 1990
    // 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
1991 1992 1993 1994 1995 1996
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
1997
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
1998
{
1999
    mavlink_message_t msg;
2000
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_SAFETY_ARMED);
2001
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2002 2003 2004 2005 2006 2007
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2008
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2009
{
2010
    mavlink_message_t msg;
2011
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_SAFETY_ARMED);
2012
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026
}

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;

2027 2028
    if(mode == (int)MAV_MODE_MANUAL)
    {
2029 2030 2031 2032
        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
2033

2034
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2035 2036 2037
    }
    else
    {
2038 2039
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2040 2041
}

2042 2043 2044 2045 2046
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2047 2048
void UAS::receiveButton(int buttonIndex)
{
2049 2050
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2051
    case 0:
pixhawk's avatar
pixhawk committed
2052

pixhawk's avatar
pixhawk committed
2053 2054
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2055

pixhawk's avatar
pixhawk committed
2056 2057 2058 2059 2060
        break;
    default:

        break;
    }
2061
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2062 2063 2064

}

2065

pixhawk's avatar
pixhawk committed
2066 2067 2068

void UAS::halt()
{
lm's avatar
lm committed
2069 2070 2071 2072 2073 2074 2075
    // 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
2076 2077 2078 2079
}

void UAS::go()
{
lm's avatar
lm committed
2080 2081 2082 2083 2084 2085 2086
    // 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
2087 2088 2089 2090 2091
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
lm's avatar
lm committed
2092 2093 2094 2095 2096 2097 2098
    // 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
2099 2100 2101 2102 2103 2104 2105 2106
}

/**
 * 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
2107 2108 2109 2110 2111 2112 2113
//    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
2114 2115 2116
}

/**
lm's avatar
lm committed
2117
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2118 2119 2120 2121 2122 2123
 * @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
2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149
    // 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
2150 2151
}

lm's avatar
lm committed
2152 2153 2154 2155 2156
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2157
        startHil();
lm's avatar
lm committed
2158 2159 2160
    }
    else
    {
2161
        stopHil();
lm's avatar
lm committed
2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192
    }
}

/**
* @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);
}


2193 2194
void UAS::startHil()
{
lm's avatar
lm committed
2195 2196
    // Connect Flight Gear Link
    simulation->connectSimulation();
2197
    mavlink_message_t msg;
2198
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode | MAV_MODE_FLAG_HIL_ENABLED);
2199
    sendMessage(msg);
2200 2201
}

2202 2203
void UAS::stopHil()
{
lm's avatar
lm committed
2204
    simulation->disconnectSimulation();
2205
    mavlink_message_t msg;
2206
    mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode, navMode & !MAV_MODE_FLAG_HIL_ENABLED);
2207
    sendMessage(msg);
2208 2209 2210
}


pixhawk's avatar
pixhawk committed
2211 2212
void UAS::shutdown()
{
lm's avatar
lm committed
2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238
    // 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
2239 2240
}

2241 2242
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2243
    mavlink_message_t msg;
2244
    mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
2245 2246 2247 2248

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2249 2250
}

pixhawk's avatar
pixhawk committed
2251 2252 2253
/**
 * @return The name of this system as string in human-readable form
 */
2254
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2255 2256
{
    QString result;
2257 2258
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2259
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2260 2261 2262
    }
    else
    {
pixhawk's avatar
pixhawk committed
2263 2264 2265 2266 2267
        result = name;
    }
    return result;
}

2268 2269 2270 2271 2272
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293
QString UAS::getShortModeTextFor(int id)
{
    QString mode;

    switch (id) {
    case (uint8_t)MAV_MODE_PREFLIGHT:
        mode = "PREFLIGHT";
        break;
    case (uint8_t)MAV_MODE_MANUAL:
        mode = "MANUAL";
        break;
    case (uint8_t)MAV_MODE_AUTO:
        mode = "AUTO";
        break;
    case (uint8_t)MAV_MODE_GUIDED:
        mode = "GUIDED";
        break;
    case (uint8_t)MAV_MODE_STABILIZE:
        mode = "STABILIZED";
        break;
    case (uint8_t)MAV_MODE_TEST:
lm's avatar
lm committed
2294
        mode = "TEST";
2295 2296 2297 2298 2299 2300 2301 2302 2303
        break;
    default:
        mode = "UNKNOWN";
        break;
    }

    return mode;
}

2304 2305 2306 2307 2308
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2309 2310
void UAS::addLink(LinkInterface* link)
{
2311 2312
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2313
        links->append(link);
2314
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2315 2316 2317
    }
}

2318 2319 2320
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2321 2322
    if (link)
    {
2323 2324 2325 2326
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2327 2328 2329 2330 2331 2332 2333 2334 2335 2336 2337 2338 2339 2340 2341
/**
 * @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;
2342 2343
    switch (batteryType)
    {
lm's avatar
lm committed
2344
    case NICD:
pixhawk's avatar
pixhawk committed
2345
        break;
lm's avatar
lm committed
2346
    case NIMH:
pixhawk's avatar
pixhawk committed
2347
        break;
lm's avatar
lm committed
2348
    case LIION:
pixhawk's avatar
pixhawk committed
2349
        break;
lm's avatar
lm committed
2350
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2351 2352 2353
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2354
    case LIFE:
pixhawk's avatar
pixhawk committed
2355
        break;
lm's avatar
lm committed
2356
    case AGZN:
pixhawk's avatar
pixhawk committed
2357 2358 2359 2360
        break;
    }
}

2361 2362
void UAS::setBatterySpecs(const QString& specs)
{
2363 2364
    if (specs.length() == 0 || specs.contains("%"))
    {
2365
        batteryRemainingEstimateEnabled = false;
2366
        bool ok;
2367 2368 2369
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2370 2371
        if (ok)
        {
2372
            warnLevelPercent = temp;
2373 2374 2375
        }
        else
        {
2376 2377
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2378 2379 2380
    }
    else
    {
2381 2382 2383 2384 2385
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2386 2387
        if (parts.length() == 3)
        {
2388 2389 2390 2391 2392 2393 2394 2395 2396 2397 2398
            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;
2399 2400 2401
        }
        else
        {
2402 2403
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2404 2405 2406 2407 2408
    }
}

QString UAS::getBatterySpecs()
{
2409 2410
    if (batteryRemainingEstimateEnabled)
    {
2411
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2412 2413 2414
    }
    else
    {
2415 2416
        return QString("%1%").arg(warnLevelPercent);
    }
2417 2418
}

pixhawk's avatar
pixhawk committed
2419 2420 2421 2422 2423 2424 2425 2426 2427 2428 2429 2430 2431
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
2432 2433 2434
/**
 * @return charge level in percent - 0 - 100
 */
2435
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2436
{
2437 2438 2439 2440
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2441
            chargeLevel = 0.0f;
2442 2443 2444
        }
        else if (lpVoltage > fullVoltage)
        {
2445
            chargeLevel = 100.0f;
2446 2447 2448
        }
        else
        {
2449 2450
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2451 2452
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2453 2454
}

lm's avatar
lm committed
2455 2456
void UAS::startLowBattAlarm()
{
2457 2458
    if (!lowBattAlarm)
    {
2459
        GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
2460
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2461 2462 2463 2464 2465 2466
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2467 2468
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2469 2470 2471 2472
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}