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

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

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

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
LM's avatar
LM committed
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 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 259 260 261
            if (this->mode != static_cast<int>(state.system_mode))
            {
                modechanged = true;
                this->mode = static_cast<int>(state.system_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 272 273 274 275 276
            if (navMode != state.flight_mode)
            {
                emit navModeChanged(uasId, state.flight_mode, getNavModeText(state.flight_mode));
                navMode = state.flight_mode;
                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 297 298
            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();
                GAudioOutput::instance()->say(audiostring);
            }
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 326
                if (!batteryRemainingEstimateEnabled)
                {
327
                    chargeLevel = state.battery_percent/2.55f;
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.battery_percent/2.55f);
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
                emit dropRateChanged(this->getUASID(), state.errors_uart/1000.0f);
345
            }
LM's avatar
LM committed
346
            break;
347 348

#ifdef MAVLINK_ENABLED_PIXHAWK
349 350
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
LM's avatar
LM committed
351 352 353 354 355 356 357 358 359 360 361 362 363 364
                mavlink_control_status_t status;
                mavlink_msg_control_status_decode(&message, &status);
                // Emit control status vector
                emit attitudeControlEnabled(static_cast<bool>(status.control_att));
                emit positionXYControlEnabled(static_cast<bool>(status.control_pos_xy));
                emit positionZControlEnabled(static_cast<bool>(status.control_pos_z));
                emit positionYawControlEnabled(static_cast<bool>(status.control_pos_yaw));

                // Emit localization status vector
                emit localizationChanged(this, status.position_fix);
                emit visionLocalizationChanged(this, status.vision_fix);
                emit gpsLocalizationChanged(this, status.gps_fix);
            }
            break;
lm's avatar
lm committed
365
#endif // PIXHAWK
366 367
        case MAVLINK_MSG_ID_RAW_IMU:
            {
LM's avatar
LM committed
368 369 370 371 372 373 374 375 376 377 378 379 380 381 382
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
                quint64 time = getUnixTime(raw.usec);

                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;
383 384
        case MAVLINK_MSG_ID_SCALED_IMU:
            {
LM's avatar
LM committed
385 386 387 388 389 390 391 392 393 394
                mavlink_scaled_imu_t scaled;
                mavlink_msg_scaled_imu_decode(&message, &scaled);
                quint64 time = getUnixTime(scaled.usec);

                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);
395 396 397
                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
398 399
            }
            break;
pixhawk's avatar
pixhawk committed
400 401
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
402
            //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
403 404 405
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
LM's avatar
LM committed
406 407
                quint64 time = getUnixReferenceTime(attitude.usec);
                lastAttitude = time;
LM's avatar
LM committed
408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425
                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
426

LM's avatar
LM committed
427
                attitudeKnown = true;
lm's avatar
lm committed
428

LM's avatar
LM committed
429 430 431 432 433 434
                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);
435

436
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
437
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
438
            }
LM's avatar
LM committed
439
            break;
lm's avatar
lm committed
440 441 442 443 444 445 446
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
                emit hilControlsChanged(hil.time_us, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
            }
            break;
447 448
        case MAVLINK_MSG_ID_VFR_HUD:
            {
LM's avatar
LM committed
449 450 451 452 453 454 455 456 457 458 459 460
                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);

461 462
                if (!attitudeKnown)
                {
LM's avatar
LM committed
463 464 465
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
lm's avatar
lm committed
466

LM's avatar
LM committed
467 468 469 470 471 472
                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;
473 474
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
475 476 477 478 479 480 481 482 483 484 485 486 487 488
                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;
489
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
490
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
491
            //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
492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517
            {
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
                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
518
            }
LM's avatar
LM committed
519
            break;
520
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
521 522
            //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
523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547
            {
                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);
548
            }
LM's avatar
LM committed
549
            break;
550 551
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
LM's avatar
LM committed
552 553 554
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime();
555 556 557
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
LM's avatar
LM committed
558 559 560 561 562 563 564 565 566 567 568 569 570 571
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
                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();
572
                }
LM's avatar
LM committed
573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614
                positionLock = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
            }
            break;
        case MAVLINK_MSG_ID_GPS_RAW:
            //std::cerr << std::endl;
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
            {
                mavlink_gps_raw_t pos;
                mavlink_msg_gps_raw_decode(&message, &pos);

                // SANITY CHECK
                // only accept values in a realistic range
                // quint64 time = getUnixTime(pos.usec);
                quint64 time = getUnixTime();

                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);

                if (pos.fix_type > 0) {
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
                    latitude = pos.lat;
                    longitude = pos.lon;
                    altitude = pos.alt;
                    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, time);
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v) {
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
615 616
                }
            }
LM's avatar
LM committed
617
            break;
618 619
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
LM's avatar
LM committed
620 621 622 623 624 625 626 627 628 629 630 631 632
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

                // SANITY CHECK
                // only accept values in a realistic range
                // quint64 time = getUnixTime(pos.usec);
                quint64 time = getUnixTime();

                emit valueChanged(uasId, "latitude", "deg", pos.lat/(double)1E7, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon/(double)1E7, time);

                if (pos.fix_type > 0) {
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
LM's avatar
LM committed
633
                    emit valueChanged(uasId, "gps speed", "m/s", pos.vel, time);
LM's avatar
LM committed
634 635 636 637 638 639 640 641 642 643 644 645 646
                    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
647 648 649 650 651

                    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
652 653 654
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
LM's avatar
LM committed
655
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
LM's avatar
LM committed
656
                    }
lm's avatar
lm committed
657 658
                }
            }
LM's avatar
LM committed
659
            break;
660 661
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
LM's avatar
LM committed
662 663
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
664 665
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
LM's avatar
LM committed
666 667
                    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]));
                }
668
            }
LM's avatar
LM committed
669
            break;
670 671
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
LM's avatar
LM committed
672 673
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
LM's avatar
LM committed
674
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
675 676
            }
            break;
677 678
        case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
LM's avatar
LM committed
679 680 681 682 683 684 685 686 687
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
                quint64 time = this->getUnixTime(pressure.usec);
                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;
688

689 690
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            {
LM's avatar
LM committed
691 692 693 694 695 696 697 698
                mavlink_scaled_pressure_t pressure;
                mavlink_msg_scaled_pressure_decode(&message, &pressure);
                quint64 time = this->getUnixTime(pressure.usec);
                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;
699

700 701
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
LM's avatar
LM committed
702 703 704 705 706 707 708 709 710 711 712
                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);
713 714 715 716 717 718 719 720 721
                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
722 723
            }
            break;
724 725
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
LM's avatar
LM committed
726 727 728 729 730 731 732 733 734 735 736
                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
737
            }
LM's avatar
LM committed
738
            break;
739 740
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
LM's avatar
LM committed
741 742 743 744 745 746 747 748
                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;
                float val = value.param_value;

                // Insert component if necessary
749 750
                if (!parameters.contains(component))
                {
LM's avatar
LM committed
751 752
                    parameters.insert(component, new QMap<QString, float>());
                }
753

LM's avatar
LM committed
754 755 756
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);
757

LM's avatar
LM committed
758 759 760 761 762
                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
            }
            break;
763 764 765
        case MAVLINK_MSG_ID_COMMAND_ACK:
            mavlink_command_ack_t ack;
            mavlink_msg_command_ack_decode(&message, &ack);
766 767
            if (ack.result == 1)
            {
768
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
769 770 771
            }
            else
            {
772
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
773 774
            }
            break;
pixhawk's avatar
pixhawk committed
775
        case MAVLINK_MSG_ID_DEBUG:
776
            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
777
            break;
LM's avatar
LM committed
778
        case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
779
            {
LM's avatar
LM committed
780 781 782 783 784 785 786 787
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
                quint64 time = getUnixTime(out.time_ms*1000);
                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
788 789
            }
            break;
790 791
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
LM's avatar
LM committed
792 793
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
794 795
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
796 797
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
798 799 800 801
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
802
            }
LM's avatar
LM committed
803
            break;
pixhawk's avatar
pixhawk committed
804

805 806
        case MAVLINK_MSG_ID_WAYPOINT:
            {
LM's avatar
LM committed
807 808 809
                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;
810 811
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
812 813
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
814 815 816 817
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
818
            }
LM's avatar
LM committed
819
            break;
pixhawk's avatar
pixhawk committed
820

821 822
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
LM's avatar
LM committed
823 824
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
825 826
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
827 828
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
829
            }
LM's avatar
LM committed
830
            break;
831

832 833
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
LM's avatar
LM committed
834 835
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
836 837
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
838 839
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
840 841 842 843
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
844
            }
LM's avatar
LM committed
845
            break;
pixhawk's avatar
pixhawk committed
846

847 848
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
            {
LM's avatar
LM committed
849 850 851 852 853 854 855 856
                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
857

858 859
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
            {
LM's avatar
LM committed
860 861 862 863 864
                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
865

866 867
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
868 869 870 871 872
                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;
873 874
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
LM's avatar
LM committed
875 876 877 878 879 880 881 882 883 884 885 886 887
                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;
888 889
        case MAVLINK_MSG_ID_STATUSTEXT:
            {
LM's avatar
LM committed
890 891
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
892
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
893 894 895 896 897 898 899 900
                //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;
901
#ifdef MAVLINK_ENABLED_PIXHAWK
902 903
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
904 905 906 907 908 909 910 911 912 913 914
                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;
915

916 917
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
918 919 920 921 922 923 924 925 926 927 928
                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;
929 930
                }

931 932
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
933 934 935 936 937
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
938

LM's avatar
LM committed
939
                ++imagePacketsArrived;
940

LM's avatar
LM committed
941 942 943 944 945 946 947 948
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
949
            }
LM's avatar
LM committed
950
            break;
951
#endif
952
        case MAVLINK_MSG_ID_DEBUG_VECT:
953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027
        {
            mavlink_debug_vect_t vect;
            mavlink_msg_debug_vect_decode(&message, &vect);
            QString str((const char*)vect.name);
            quint64 time = getUnixTime(vect.usec);
            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
1028
#ifdef MAVLINK_ENABLED_UALBERTA
1029 1030
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041
                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;
1042 1043
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
1044 1045
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
1046 1047 1048 1049 1050 1051
                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
1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070

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

1072
#endif
LM's avatar
LM committed
1073
            // Messages to ignore
1074
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
1075
            break;
1076 1077 1078 1079
        default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
LM's avatar
LM committed
1080 1081 1082 1083 1084 1085 1086
                    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
1087
            }
LM's avatar
LM committed
1088
            break;
pixhawk's avatar
pixhawk committed
1089 1090 1091 1092
        }
    }
}

1093 1094 1095 1096 1097 1098 1099 1100 1101
void UAS::setHomePosition(double lat, double lon, double alt)
{
    // Send new home position to UAS
    mavlink_gps_set_global_origin_t home;
    home.target_system = uasId;
    home.target_component = 0; // ALL components
    home.latitude = lat*1E7;
    home.longitude = lon*1E7;
    home.altitude = alt*1000;
1102
    qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
1103 1104 1105 1106 1107
    mavlink_message_t msg;
    mavlink_msg_gps_set_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
    sendMessage(msg);
}

1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122
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()));


1123 1124
    if (ret == QMessageBox::Yes)
    {
lm's avatar
lm committed
1125 1126 1127 1128 1129 1130 1131 1132 1133
        // 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);
1134 1135 1136 1137
        result = true;
    }
}

pixhawk's avatar
pixhawk committed
1138 1139
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1140
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1141
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1142 1143
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
1144
#else
lm's avatar
lm committed
1145 1146 1147 1148
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1149
#endif
pixhawk's avatar
pixhawk committed
1150 1151
}

pixhawk's avatar
pixhawk committed
1152 1153
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1154
#ifdef MAVLINK_ENABLED_PIXHAWK
1155 1156 1157
    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
1158
#else
1159 1160 1161 1162
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1163 1164 1165 1166
#endif
}

void UAS::startRadioControlCalibration()
lm's avatar
lm committed
1167
{
1168 1169
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1170
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1);
1171
    sendMessage(msg);
lm's avatar
lm committed
1172 1173
}

1174
void UAS::startDataRecording()
lm's avatar
lm committed
1175
{
1176
    mavlink_message_t msg;
1177
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2);
1178
    sendMessage(msg);
lm's avatar
lm committed
1179 1180 1181 1182
}

void UAS::stopDataRecording()
{
1183
    mavlink_message_t msg;
1184
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0);
1185
    sendMessage(msg);
lm's avatar
lm committed
1186 1187
}

pixhawk's avatar
pixhawk committed
1188 1189
void UAS::startMagnetometerCalibration()
{
1190 1191
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1192
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0);
1193
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1194 1195 1196 1197
}

void UAS::startGyroscopeCalibration()
{
1198 1199
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1200
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0);
1201
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1202 1203 1204 1205
}

void UAS::startPressureCalibration()
{
1206 1207
    mavlink_message_t msg;
    // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
1208
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0);
1209
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1210 1211
}

LM's avatar
LM committed
1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264
quint64 UAS::getUnixReferenceTime(quint64 time)
{
    // Same as getUnixTime, but does not react to attitudeStamped mode
    if (time == 0)
    {
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
        return QGC::groundTimeMilliseconds();
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000000LLU)
#else
        else if (time < 1261440000000000)
#endif
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
        if (onboardTimeOffset == 0)
        {
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
        }
        return time/1000 + onboardTimeOffset;
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        return time/1000;
    }
}

/**
 * @warning If attitudeStamped is enabled, this function will not actually return 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!
 */
1265 1266
quint64 UAS::getUnixTime(quint64 time)
{
LM's avatar
LM committed
1267 1268 1269 1270
    if (attitudeStamped)
    {
        return lastAttitude;
    }
1271 1272
    if (time == 0)
    {
LM's avatar
LM committed
1273
        //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
LM's avatar
LM committed
1274
        return QGC::groundTimeMilliseconds();
1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291
    }
    // 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
1292
#ifndef _MSC_VER
1293
    else if (time < 1261440000000000LLU)
1294
#else
LM's avatar
LM committed
1295
        else if (time < 1261440000000000)
1296
#endif
LM's avatar
LM committed
1297 1298
        {
        //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
1299 1300
        if (onboardTimeOffset == 0)
        {
LM's avatar
LM committed
1301
            onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
1302
        }
1303
        return time/1000 + onboardTimeOffset;
1304 1305 1306
    }
    else
    {
1307 1308
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1309
        return time/1000;
1310 1311 1312
    }
}

1313 1314
QList<QString> UAS::getParameterNames(int component)
{
1315 1316
    if (parameters.contains(component))
    {
1317
        return parameters.value(component)->keys();
1318 1319 1320
    }
    else
    {
1321 1322 1323 1324 1325 1326 1327 1328 1329
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1330
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1331
{
1332
    if (mode >= (int)MAV_MODE_PREFLIGHT && mode < (int)MAV_MODE_ENUM_END)
1333
    {
1334
        //this->mode = mode; //no call assignament, update receive message from UAS
pixhawk's avatar
pixhawk committed
1335
        mavlink_message_t msg;
lm's avatar
lm committed
1336
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1337
        sendMessage(msg);
lm's avatar
lm committed
1338
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
1339 1340 1341
    }
    else
    {
1342 1343
        qDebug() << "uas Mode not assign: " << mode;
    }
pixhawk's avatar
pixhawk committed
1344 1345 1346 1347 1348
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1349 1350 1351 1352
    foreach (LinkInterface* link, *links)
    {
        if (link)
        {
1353
            sendMessage(link, message);
1354 1355 1356
        }
        else
        {
1357 1358 1359
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1360 1361 1362
    }
}

1363 1364 1365 1366
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1367

1368 1369 1370 1371
    foreach(LinkInterface* link, link_list)
    {
        if (link)
        {
1372
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
1373 1374 1375 1376 1377 1378
            if(serial != 0)
            {
                for(int i=0; i<links->size(); i++)
                {
                    if(serial != links->at(i))
                    {
1379
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1380 1381
                        sendMessage(serial, message);
                    }
1382 1383 1384 1385 1386 1387
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1388 1389
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1390
    if(!link) return;
pixhawk's avatar
pixhawk committed
1391 1392 1393
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1394
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1395
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1396
    // If link is connected
1397 1398
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
1399 1400 1401 1402 1403 1404 1405 1406
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1407
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1408
{
1409
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1410 1411
}

1412 1413
QString UAS::getNavModeText(int mode)
{
1414 1415
    switch (mode)
    {
1416 1417
    case MAV_FLIGHT_MODE_PREFLIGHT:
        return QString("PREFLIGHT");
1418
        break;
1419 1420
    case MAV_FLIGHT_MODE_MANUAL:
        return QString("MANUAL");
1421
        break;
1422 1423
    case MAV_FLIGHT_MODE_AUTO_TAKEOFF:
        return QString("TAKEOFF");
1424
        break;
1425 1426
    case MAV_FLIGHT_MODE_AUTO_HOLD:
        return QString("HOLDING");
1427
        break;
1428 1429
    case MAV_FLIGHT_MODE_AUTO_MISSION:
        return QString("MISSION");
1430
        break;
1431 1432
    case MAV_FLIGHT_MODE_AUTO_VECTOR:
        return QString("VECTOR");
1433
        break;
1434
    case MAV_FLIGHT_MODE_AUTO_RETURNING:
1435 1436
        return QString("RETURNING");
        break;
1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456
    case MAV_FLIGHT_MODE_AUTO_LANDING:
        return QString("LANDING");
        break;
    case MAV_FLIGHT_MODE_AUTO_LOST:
        return QString("LOST");
        break;
    case MAV_FLIGHT_MODE_STABILIZE_RATES_ACRO:
        return QString("S: RATE/ACRO");
        break;
    case MAV_FLIGHT_MODE_STABILIZE_LEVELING:
        return QString("S: LEVELING");
        break;
    case MAV_FLIGHT_MODE_STABILIZE_ROLL_PITCH_ABSOLUTE:
        return QString("S: R/P ABS");
        break;
    case MAV_FLIGHT_MODE_STABILIZE_ROLL_YAW_ALTITUDE:
        return QString("S: R/Y ALT");
        break;
    case MAV_FLIGHT_MODE_STABILIZE_ROLL_PITCH_YAW_ALTITUDE:
        return QString("S: R/P/Y ALT");
1457
        break;
1458 1459
    case MAV_FLIGHT_MODE_STABILIZE_CURSOR_CONTROL:
        return QString("S: CURSOR");
1460 1461 1462 1463 1464 1465
        break;
    default:
        return QString("UNKNOWN");
    }
}

pixhawk's avatar
pixhawk committed
1466 1467
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
1468 1469
    switch (statusCode)
    {
lm's avatar
lm committed
1470
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1471
        uasState = tr("UNINIT");
1472
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1473
        break;
lm's avatar
lm committed
1474
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1475
        uasState = tr("BOOT");
1476
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1477
        break;
lm's avatar
lm committed
1478
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1479
        uasState = tr("CALIBRATING");
1480
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1481
        break;
lm's avatar
lm committed
1482
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1483
        uasState = tr("ACTIVE");
1484
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1485
        break;
lm's avatar
lm committed
1486 1487
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1488
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1489 1490
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1491
        uasState = tr("CRITICAL");
1492
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1493
        break;
lm's avatar
lm committed
1494
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1495
        uasState = tr("EMERGENCY");
1496
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1497
        break;
James Goppert's avatar
James Goppert committed
1498
        //case MAV_STATE_HILSIM:
James Goppert's avatar
James Goppert committed
1499 1500 1501
        //uasState = tr("HIL SIM");
        //stateDescription = tr("HIL Simulation, Sensors read from SIM");
        //break;
1502

lm's avatar
lm committed
1503
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1504
        uasState = tr("SHUTDOWN");
1505
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1506
        break;
1507

lm's avatar
lm committed
1508
    default:
pixhawk's avatar
pixhawk committed
1509
        uasState = tr("UNKNOWN");
1510
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1511 1512 1513 1514
        break;
    }
}

1515 1516
QImage UAS::getImage()
{
LM's avatar
LM committed
1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563
#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!";
        }
    }
1564 1565
    // Restart statemachine
    imagePacketsArrived = 0;
LM's avatar
LM committed
1566
    //imageRecBuffer.clear();
1567
    return image;
1568 1569
#else
	return QImage();
LM's avatar
LM committed
1570
#endif
1571

1572 1573 1574 1575
}

void UAS::requestImage()
{
1576
#ifdef MAVLINK_ENABLED_PIXHAWK
1577 1578
    qDebug() << "trying to get an image from the uas...";

1579 1580 1581
    // check if there is already an image transmission going on
    if (imagePacketsArrived == 0)
    {
1582 1583 1584 1585
        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);
    }
1586
#endif
1587
}
pixhawk's avatar
pixhawk committed
1588 1589 1590 1591 1592 1593 1594 1595 1596


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1597
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1598
{
1599 1600
    if(startTime == 0)
    {
pixhawk's avatar
pixhawk committed
1601
        return 0;
1602 1603 1604
    }
    else
    {
pixhawk's avatar
pixhawk committed
1605 1606 1607 1608
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1609
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1610 1611 1612 1613
{
    return commStatus;
}

1614 1615 1616
void UAS::requestParameters()
{
    mavlink_message_t msg;
1617
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1618
    sendMessage(msg);
1619 1620
}

1621
void UAS::writeParametersToStorage()
1622
{
1623
    mavlink_message_t msg;
1624
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1);
1625
    sendMessage(msg);
1626 1627 1628 1629
}

void UAS::readParametersFromStorage()
{
1630
    mavlink_message_t msg;
1631
    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1);
1632
    sendMessage(msg);
lm's avatar
lm committed
1633 1634
}

1635
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1636 1637
{
    // Buffers to write data to
1638
    mavlink_message_t msg;
1639
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1640 1641
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1642
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1643 1644
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1645 1646
    // 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
1647 1648
    stream.req_message_rate = 0;
    // Start / stop the message
1649
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1650 1651 1652 1653 1654
    // 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
1655
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1656 1657
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1658 1659 1660
    sendMessage(msg);
}

1661
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1662 1663 1664
{
    // Buffers to write data to
    mavlink_message_t msg;
1665
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1666
    // Select the message to request from now on
1667
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1668
    // Select the update rate in Hz the message should be send
1669
    stream.req_message_rate = rate;
lm's avatar
lm committed
1670
    // Start / stop the message
1671
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1672 1673 1674 1675 1676
    // 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
1677
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1678 1679
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1680 1681 1682
    sendMessage(msg);
}

1683
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1684
{
1685 1686 1687 1688
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1689
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1690
    // Select the update rate in Hz the message should be send
1691
    stream.req_message_rate = rate;
1692
    // Start / stop the message
1693
    stream.start_stop = (rate) ? 1 : 0;
1694 1695 1696 1697 1698 1699
    // 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);
1700 1701
    // Send message twice to increase chance of reception
    sendMessage(msg);
1702
    sendMessage(msg);
lm's avatar
lm committed
1703
}
1704

1705
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1706
{
1707 1708 1709 1710 1711
#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
1712 1713 1714
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1715
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1716
    // Select the update rate in Hz the message should be send
1717
    stream.req_message_rate = rate;
1718
    // Start / stop the message
1719
    stream.start_stop = (rate) ? 1 : 0;
1720 1721 1722 1723 1724 1725
    // 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);
1726 1727
    // Send message twice to increase chance of reception
    sendMessage(msg);
1728
    sendMessage(msg);
1729
#endif
lm's avatar
lm committed
1730 1731
}

1732
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1733
{
1734 1735 1736 1737
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1738
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1739
    // Select the update rate in Hz the message should be send
1740
    stream.req_message_rate = rate;
1741
    // Start / stop the message
1742
    stream.start_stop = (rate) ? 1 : 0;
1743 1744 1745 1746 1747 1748
    // 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);
1749 1750
    // Send message twice to increase chance of reception
    sendMessage(msg);
1751
    sendMessage(msg);
lm's avatar
lm committed
1752 1753
}

lm's avatar
lm committed
1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774
//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);
//}
1775

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

1798
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1799 1800 1801 1802 1803
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1804
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1805
    // Select the update rate in Hz the message should be send
1806
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1807
    // Start / stop the message
1808
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1809 1810 1811 1812 1813 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);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

1820
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1821 1822 1823 1824 1825
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1826
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1827
    // Select the update rate in Hz the message should be send
1828
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1829
    // Start / stop the message
1830
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841
    // 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);
}

1842
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1843 1844 1845 1846 1847
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1848
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1849
    // Select the update rate in Hz the message should be send
1850
    stream.req_message_rate = rate;
1851
    // Start / stop the message
1852
    stream.start_stop = (rate) ? 1 : 0;
1853 1854 1855 1856 1857 1858
    // 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);
1859 1860
    // Send message twice to increase chance of reception
    sendMessage(msg);
1861
    sendMessage(msg);
1862 1863
}

lm's avatar
lm committed
1864 1865 1866 1867 1868 1869 1870
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
lm's avatar
lm committed
1871 1872
void UAS::setParameter(const int component, const QString& id, const float value)
{
1873 1874
    if (!id.isNull())
    {
1875 1876 1877 1878 1879 1880 1881
        mavlink_message_t msg;
        mavlink_param_set_t p;
        p.param_value = value;
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;

        // Copy string into buffer, ensuring not to exceed the buffer size
1882 1883
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
        {
1884
            // String characters
1885 1886
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
            {
1887 1888
                p.param_id[i] = id.toAscii()[i];
            }
LM's avatar
LM committed
1889 1890 1891 1892 1893
            //        // 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';
            //        }
1894
            // Zero fill
1895 1896
            else
            {
1897 1898
                p.param_id[i] = 0;
            }
lm's avatar
lm committed
1899
        }
1900 1901
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
        sendMessage(msg);
lm's avatar
lm committed
1902
    }
1903 1904
}

1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916
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;
}

1917 1918 1919 1920
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
1921 1922 1923 1924
    if (airframe == 0)
    {
        switch (systemType)
        {
lm's avatar
lm committed
1925
        case MAV_TYPE_FIXED_WING:
1926 1927
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
lm's avatar
lm committed
1928
        case MAV_TYPE_QUADROTOR:
1929 1930 1931 1932 1933 1934 1935
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1936 1937 1938
void UAS::setUASName(const QString& name)
{
    this->name = name;
1939
    writeSettings();
1940
    emit nameChanged(name);
1941
    emit systemSpecsChanged(uasId);
1942 1943
}

lm's avatar
lm committed
1944 1945 1946
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
1947
    mavlink_command_short_t cmd;
1948 1949 1950 1951 1952 1953 1954 1955
    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;
1956
    mavlink_msg_command_short_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
1957 1958 1959 1960 1961 1962
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979
    mavlink_command_short_t cmd;
    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;
    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;
1980 1981 1982 1983 1984 1985
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
1986 1987 1988
    cmd.param5 = param5;
    cmd.param6 = param6;
    cmd.param7 = param7;
1989 1990
    cmd.target_system = uasId;
    cmd.target_component = component;
1991
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1992 1993 1994
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1995
/**
lm's avatar
lm committed
1996
 * Launches the system
pixhawk's avatar
pixhawk committed
1997 1998 1999 2000
 *
 **/
void UAS::launch()
{
lm's avatar
lm committed
2001 2002 2003 2004 2005 2006 2007
    // 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
2008 2009 2010 2011 2012 2013
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
2014
void UAS::armSystem()
pixhawk's avatar
pixhawk committed
2015
{
2016 2017 2018
    mavlink_message_t msg;
    mavlink_msg_set_safety_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_SAFETY_ARMED);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2019 2020 2021 2022 2023 2024
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
2025
void UAS::disarmSystem()
pixhawk's avatar
pixhawk committed
2026
{
2027 2028 2029
    mavlink_message_t msg;
    mavlink_msg_set_safety_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_SAFETY_DISARMED);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043
}

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;

2044 2045
    if(mode == (int)MAV_MODE_MANUAL)
    {
2046 2047 2048 2049
        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
2050

2051
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
2052 2053 2054
    }
    else
    {
2055 2056
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
2057 2058
}

2059 2060 2061 2062 2063
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
2064 2065
void UAS::receiveButton(int buttonIndex)
{
2066 2067
    switch (buttonIndex)
    {
pixhawk's avatar
pixhawk committed
2068
    case 0:
pixhawk's avatar
pixhawk committed
2069

pixhawk's avatar
pixhawk committed
2070 2071
        break;
    case 1:
pixhawk's avatar
pixhawk committed
2072

pixhawk's avatar
pixhawk committed
2073 2074 2075 2076 2077
        break;
    default:

        break;
    }
2078
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
2079 2080 2081

}

2082

pixhawk's avatar
pixhawk committed
2083 2084 2085

void UAS::halt()
{
lm's avatar
lm committed
2086 2087 2088 2089 2090 2091 2092
    // 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
2093 2094 2095 2096
}

void UAS::go()
{
lm's avatar
lm committed
2097 2098 2099 2100 2101 2102 2103
    // 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
2104 2105 2106 2107 2108
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
lm's avatar
lm committed
2109 2110 2111 2112 2113 2114 2115
    // 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
2116 2117 2118 2119 2120 2121 2122 2123
}

/**
 * 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
2124 2125 2126 2127 2128 2129 2130
//    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
2131 2132 2133
}

/**
lm's avatar
lm committed
2134
 * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
pixhawk's avatar
pixhawk committed
2135 2136 2137 2138 2139 2140
 * @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
2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166
    // 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
2167 2168
}

lm's avatar
lm committed
2169 2170 2171 2172 2173
void UAS::enableHil(bool enable)
{
    // Connect Flight Gear Link
    if (enable)
    {
2174
        startHil();
lm's avatar
lm committed
2175 2176 2177
    }
    else
    {
2178
        stopHil();
lm's avatar
lm committed
2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208 2209
    }
}

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


2210 2211
void UAS::startHil()
{
lm's avatar
lm committed
2212 2213
    // Connect Flight Gear Link
    simulation->connectSimulation();
2214 2215 2216
    mavlink_message_t msg;
    mavlink_msg_set_safety_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_SAFETY_HIL);
    sendMessage(msg);
2217 2218
}

2219 2220
void UAS::stopHil()
{
lm's avatar
lm committed
2221
    simulation->disconnectSimulation();
2222 2223 2224
    mavlink_message_t msg;
    mavlink_msg_set_safety_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_SAFETY_DISARMED);
    sendMessage(msg);
2225 2226 2227
}


pixhawk's avatar
pixhawk committed
2228 2229
void UAS::shutdown()
{
lm's avatar
lm committed
2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255
    // 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
2256 2257
}

2258 2259
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2260 2261 2262 2263 2264 2265
    mavlink_message_t msg;
    mavlink_msg_position_target_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, x, y, z, yaw);

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
2266 2267
}

pixhawk's avatar
pixhawk committed
2268 2269 2270
/**
 * @return The name of this system as string in human-readable form
 */
2271
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2272 2273
{
    QString result;
2274 2275
    if (name == "")
    {
pixhawk's avatar
pixhawk committed
2276
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
2277 2278 2279
    }
    else
    {
pixhawk's avatar
pixhawk committed
2280 2281 2282 2283 2284
        result = name;
    }
    return result;
}

2285 2286 2287 2288 2289
const QString& UAS::getShortState() const
{
    return shortStateText;
}

2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310
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
2311
        mode = "TEST";
2312 2313 2314 2315 2316 2317 2318 2319 2320
        break;
    default:
        mode = "UNKNOWN";
        break;
    }

    return mode;
}

2321 2322 2323 2324 2325
const QString& UAS::getShortMode() const
{
    return shortModeText;
}

pixhawk's avatar
pixhawk committed
2326 2327
void UAS::addLink(LinkInterface* link)
{
2328 2329
    if (!links->contains(link))
    {
pixhawk's avatar
pixhawk committed
2330
        links->append(link);
2331
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2332 2333 2334
    }
}

2335 2336 2337
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
2338 2339
    if (link)
    {
2340 2341 2342 2343
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2344 2345 2346 2347 2348 2349 2350 2351 2352 2353 2354 2355 2356 2357 2358
/**
 * @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;
2359 2360
    switch (batteryType)
    {
lm's avatar
lm committed
2361
    case NICD:
pixhawk's avatar
pixhawk committed
2362
        break;
lm's avatar
lm committed
2363
    case NIMH:
pixhawk's avatar
pixhawk committed
2364
        break;
lm's avatar
lm committed
2365
    case LIION:
pixhawk's avatar
pixhawk committed
2366
        break;
lm's avatar
lm committed
2367
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2368 2369 2370
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2371
    case LIFE:
pixhawk's avatar
pixhawk committed
2372
        break;
lm's avatar
lm committed
2373
    case AGZN:
pixhawk's avatar
pixhawk committed
2374 2375 2376 2377
        break;
    }
}

2378 2379
void UAS::setBatterySpecs(const QString& specs)
{
2380 2381
    if (specs.length() == 0 || specs.contains("%"))
    {
2382
        batteryRemainingEstimateEnabled = false;
2383
        bool ok;
2384 2385 2386
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2387 2388
        if (ok)
        {
2389
            warnLevelPercent = temp;
2390 2391 2392
        }
        else
        {
2393 2394
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2395 2396 2397
    }
    else
    {
2398 2399 2400 2401 2402
        batteryRemainingEstimateEnabled = true;
        QString stringList = specs;
        stringList = stringList.remove("V");
        stringList = stringList.remove("v");
        QStringList parts = stringList.split(",");
2403 2404
        if (parts.length() == 3)
        {
2405 2406 2407 2408 2409 2410 2411 2412 2413 2414 2415
            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;
2416 2417 2418
        }
        else
        {
2419 2420
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2421 2422 2423 2424 2425
    }
}

QString UAS::getBatterySpecs()
{
2426 2427
    if (batteryRemainingEstimateEnabled)
    {
2428
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
2429 2430 2431
    }
    else
    {
2432 2433
        return QString("%1%").arg(warnLevelPercent);
    }
2434 2435
}

pixhawk's avatar
pixhawk committed
2436 2437 2438 2439 2440 2441 2442 2443 2444 2445 2446 2447 2448
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
2449 2450 2451
/**
 * @return charge level in percent - 0 - 100
 */
2452
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2453
{
2454 2455 2456 2457
    if (batteryRemainingEstimateEnabled)
    {
        if (lpVoltage < emptyVoltage)
        {
2458
            chargeLevel = 0.0f;
2459 2460 2461
        }
        else if (lpVoltage > fullVoltage)
        {
2462
            chargeLevel = 100.0f;
2463 2464 2465
        }
        else
        {
2466 2467
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2468 2469
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2470 2471
}

lm's avatar
lm committed
2472 2473
void UAS::startLowBattAlarm()
{
2474 2475
    if (!lowBattAlarm)
    {
2476
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2477
        QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2478 2479 2480 2481 2482 2483
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
2484 2485
    if (lowBattAlarm)
    {
lm's avatar
lm committed
2486 2487 2488 2489
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}