UAS.cc 69.9 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(),
31 32 33 34 35 36 37 38 39 40 41 42
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
pixhawk's avatar
pixhawk committed
43
warnVoltage(9.5f),
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
currentVoltage(12.0f),
lpVoltage(12.0f),
mode(MAV_MODE_UNINIT),
status(MAV_STATE_UNINIT),
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)),
71 72
paramsOnceRequested(false),
airframe(0)
pixhawk's avatar
pixhawk committed
73
{
74
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
75
    setBattery(LIPOLY, 3);
76
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
77
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
78
    statusTimeout->start(500);
79
    readSettings();
pixhawk's avatar
pixhawk committed
80 81 82 83
}

UAS::~UAS()
{
84
    writeSettings();
pixhawk's avatar
pixhawk committed
85
    delete links;
86
    links=NULL;
pixhawk's avatar
pixhawk committed
87 88
}

89 90 91 92 93
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
94 95
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
96
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
97 98 99 100 101 102 103 104 105
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
106 107
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
108 109 110 111
    if (settings.contains("BATTERY_SPECS"))
    {
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
112 113 114
    settings.endGroup();
}

115
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
116 117 118 119
{
    return uasId;
}

120 121
void UAS::updateState()
{
122 123 124 125 126 127 128 129
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

130 131 132 133 134 135 136 137
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
    if (positionLock)
    {
        positionLock = false;
    }
    else
    {
pixhawk's avatar
pixhawk committed
138
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
139 140 141 142 143 144
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
145 146
void UAS::setSelected()
{
147 148 149 150 151 152 153 154 155 156
    if (UASManager::instance()->getActiveUAS() != this)
    {
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

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

159 160 161 162
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
163 164
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
Andrew Tridgell's avatar
Andrew Tridgell committed
165
        emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime(0));
166 167 168
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
169 170
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
Andrew Tridgell's avatar
Andrew Tridgell committed
171
        emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), (float)val.value, getUnixTime(0));
172 173 174
    }
}

pixhawk's avatar
pixhawk committed
175 176
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
177
    if (!link) return;
pixhawk's avatar
pixhawk committed
178 179 180
    if (!links->contains(link))
    {
        addLink(link);
181
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
182
    }
183 184 185 186
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
187

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

pixhawk's avatar
pixhawk committed
190 191 192 193 194
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
        QString patternPath;
pixhawk's avatar
pixhawk committed
195 196 197 198

        // Receive named value message
        receiveMessageNamedValue(message);

pixhawk's avatar
pixhawk committed
199 200 201
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
202
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
203 204
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
205
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
206
            {
pixhawk's avatar
pixhawk committed
207
                this->type = mavlink_msg_heartbeat_get_type(&message);
208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
                if (airframe == 0)
                {
                    switch (type)
                    {
                    case MAV_FIXED_WING:
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
                    case MAV_QUADROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
                    default:
                        // Do nothing
                        break;
                    }
                }
223
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
224 225
                emit systemTypeSet(this, type);
            }
226

pixhawk's avatar
pixhawk committed
227 228 229 230 231 232
            break;
        case MAVLINK_MSG_ID_BOOT:
            getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
            emit statusChanged(this, uasState, stateDescription);
            onboardTimeOffset = 0; // Reset offset measurement
            break;
pixhawk's avatar
pixhawk committed
233 234
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
235 236
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
237

pixhawk's avatar
pixhawk committed
238
                // FIXME
239
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
240

pixhawk's avatar
pixhawk committed
241 242 243 244 245
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
246

pixhawk's avatar
pixhawk committed
247
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
248
                {
pixhawk's avatar
pixhawk committed
249
                    statechanged = true;
lm's avatar
lm committed
250
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
251 252
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
253
                    emit statusChanged(this->status);
254
                    emit loadChanged(this,state.load/10.0f);
255
                    emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
256
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
257 258
                }

lm's avatar
lm committed
259
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
260 261
                {
                    modechanged = true;
lm's avatar
lm committed
262
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
263 264
                    QString mode;

lm's avatar
lm committed
265
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
266
                    {
lm's avatar
lm committed
267
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
268 269
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
270
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
271 272
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
273
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
274 275
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
276
                    case (uint8_t)MAV_MODE_GUIDED:
277 278
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
279
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
280 281
                        mode = "READY";
                        break;
lm's avatar
lm committed
282
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
283 284
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
285
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
286 287
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
288
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
289 290
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
291 292 293
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
294 295 296 297 298 299 300 301
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
302
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
303
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
304 305 306
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
307
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
308
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
309

lm's avatar
lm committed
310
                // LOW BATTERY ALARM
311
                if (lpVoltage < warnVoltage)
lm's avatar
lm committed
312 313 314 315 316 317 318 319
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
320
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
321
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
322
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
323 324

                // AUDIO
pixhawk's avatar
pixhawk committed
325 326 327 328 329 330 331 332 333 334
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
335
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
336 337 338 339 340 341 342 343
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
344 345 346 347 348 349

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
350 351
            }
            break;
352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
                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;
pixhawk's avatar
pixhawk committed
368
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
369
            {
pixhawk's avatar
pixhawk committed
370 371
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
372
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
373

pixhawk's avatar
pixhawk committed
374 375 376
                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);
377 378 379
                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);
pixhawk's avatar
pixhawk committed
380 381 382
                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);
pixhawk's avatar
pixhawk committed
383 384 385 386
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
387
            //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;
pixhawk's avatar
pixhawk committed
388
            {
pixhawk's avatar
pixhawk committed
389 390
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
391
                quint64 time = getUnixTime(attitude.usec);
392 393 394 395 396 397 398 399

                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);
400 401 402
                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);
403 404

                // Emit in angles
405 406 407 408 409 410 411 412 413 414 415

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

                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
pixhawk's avatar
pixhawk committed
416
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
417 418 419
                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);
420

421 422
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
423 424
            }
            break;
425
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
426
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
427
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
lm's avatar
lm committed
428
            {
429 430
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
431
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
432 433 434
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
435 436 437 438 439 440
                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);
lm's avatar
lm committed
441
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
442
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
443

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

447
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
448 449 450 451 452 453 454
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
455 456
            }
            break;
457
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
458 459 460
            //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;
            {
461 462
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
463
                quint64 time = QGC::groundTimeUsecs()/1000;
464 465 466 467 468 469
                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;
470 471 472 473 474 475
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                emit valueChanged(uasId, "gps x speed", "m/s", speedX, time);
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
476
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503
                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);
            }
            break;
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = QGC::groundTimeUsecs()/1000;
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
                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);
                emit valueChanged(uasId, "gps x speed", "m/s", speedX, time);
504 505
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
506 507
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
508
                emit valueChanged(uasId, "gpsspeed", "m/s", sqrt(speedX*speedX+speedY*speedY+speedZ*speedZ), time);
pixhawk's avatar
pixhawk committed
509 510 511 512 513 514 515
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
516 517
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
518 519 520 521 522 523 524 525
            }
            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);
526 527 528

                // SANITY CHECK
                // only accept values in a realistic range
529
                // quint64 time = getUnixTime(pos.usec);
pixhawk's avatar
pixhawk committed
530
                quint64 time = MG::TIME::getGroundTimeNow();
lm's avatar
lm committed
531

532 533
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
534

lm's avatar
lm committed
535
                if (pos.fix_type > 0)
536
                {
Laurens Mackay's avatar
Laurens Mackay committed
537
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
538
                    emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time);
lm's avatar
lm committed
539 540 541 542 543 544 545 546

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
547
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
548 549 550
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
551
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
552
                        //qDebug() << "GOT GPS RAW";
553
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
554 555 556 557 558
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
559
                }
560 561
            }
            break;
lm's avatar
lm committed
562 563 564 565
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
566
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
567
                {
lm's avatar
lm committed
568
                    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]));
lm's avatar
lm committed
569 570 571
                }
            }
            break;
572 573 574 575 576 577 578
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
                // FIXME Emit to other components
            }
            break;
579 580 581 582
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
583
                quint64 time = this->getUnixTime(0);
584 585 586
                emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time);
587 588
            }
            break;
589
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
590
            {
591 592
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
593
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616
                emit remoteControlChannelRawChanged(0, channels.chan1_raw);
                emit remoteControlChannelRawChanged(1, channels.chan2_raw);
                emit remoteControlChannelRawChanged(2, channels.chan3_raw);
                emit remoteControlChannelRawChanged(3, channels.chan4_raw);
                emit remoteControlChannelRawChanged(4, channels.chan5_raw);
                emit remoteControlChannelRawChanged(5, channels.chan6_raw);
                emit remoteControlChannelRawChanged(6, channels.chan7_raw);
                emit remoteControlChannelRawChanged(7, channels.chan8_raw);
            }
            break;
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
                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
617 618
            }
            break;
619 620 621 622
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639

                QString parameterName = QString((char*)value.param_id);
                int component = message.compid;
                float val = value.param_value;

                // Insert component if necessary
                if (!parameters.contains(component))
                {
                    parameters.insert(component, new QMap<QString, float>());
                }

                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);

                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
640 641
            }
            break;
pixhawk's avatar
pixhawk committed
642
        case MAVLINK_MSG_ID_DEBUG:
643
            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
644
            break;
645 646 647 648 649
        case MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT:
            {
                mavlink_attitude_controller_output_t out;
                mavlink_msg_attitude_controller_output_decode(&message, &out);
                quint64 time = MG::TIME::getGroundTimeNowUsecs();
lm's avatar
lm committed
650
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
651 652 653
                emit valueChanged(uasId, "att control roll", "raw", out.roll, time/1000.0f);
                emit valueChanged(uasId, "att control pitch", "raw", out.pitch, time/1000.0f);
                emit valueChanged(uasId, "att control yaw", "raw", out.yaw, time/1000.0f);
654 655 656 657 658 659
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
660
                quint64 time = MG::TIME::getGroundTimeNow();
661
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
662 663 664
                emit valueChanged(uasId, "pos control x", "raw", out.x, time);
                emit valueChanged(uasId, "pos control y", "raw", out.y, time);
                emit valueChanged(uasId, "pos control z", "raw", out.z, time);
665 666
            }
            break;
pixhawk's avatar
pixhawk committed
667 668 669 670
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
671 672 673 674
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
675 676 677
            }
            break;

678
        case MAVLINK_MSG_ID_WAYPOINT:
679
            {
680 681
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
682
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
683 684 685 686
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
687
            }
pixhawk's avatar
pixhawk committed
688
            break;
pixhawk's avatar
pixhawk committed
689

690 691 692 693 694 695 696 697 698 699 700
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
            }
            break;

pixhawk's avatar
pixhawk committed
701 702 703 704
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
705 706 707 708
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
709 710 711
            }
            break;

712
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
713
            {
pixhawk's avatar
pixhawk committed
714 715 716
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
717
            }
pixhawk's avatar
pixhawk committed
718
            break;
pixhawk's avatar
pixhawk committed
719

720
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
721
            {
722 723 724
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
725
            }
pixhawk's avatar
pixhawk committed
726
            break;
pixhawk's avatar
pixhawk committed
727

728 729 730 731 732 733 734
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
                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;
pixhawk's avatar
pixhawk committed
735

736
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
737 738 739
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
740
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
741 742
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
743
                int severity = mavlink_msg_statustext_get_severity(&message);
744
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
745
                //emit statusTextReceived(severity, text);
746
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
747 748
            }
            break;
749 750 751 752 753 754
    case MAVLINK_MSG_ID_DEBUG_VECT:
            {
                mavlink_debug_vect_t vect;
                mavlink_msg_debug_vect_decode(&message, &vect);
                QString str((const char*)vect.name);
                quint64 time = getUnixTime(vect.usec);
755 756 757
                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);
758 759
            }
            break;
760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775
            //#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
776
#ifdef MAVLINK_ENABLED_UALBERTA
777 778 779 780 781
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = MG::TIME::getGroundTimeNow();
782 783 784 785 786 787
                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);
788 789
            }
            break;
790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813
       case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
                QVector<float> aileron;
                QVector<float> elevator;
                QVector<float> rudder;
                QVector<float> gyro;
                QVector<float> pitch;
                QVector<float> throttle;

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

814
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
815 816 817 818 819
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

820
#endif
pixhawk's avatar
pixhawk committed
821
        default:
lm's avatar
lm committed
822 823 824 825
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
826 827
                    //GAudioOutput::instance()->say("UNABLE TO DECODE MESSAGE WITH ID " + QString::number(message.msgid) + " FROM SYSTEM " + QString::number(message.sysid));
                    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;
lm's avatar
lm committed
828 829 830
                    //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;
                }
            }
pixhawk's avatar
pixhawk committed
831 832 833 834 835
            break;
        }
    }
}

836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865
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()));


    if (ret == QMessageBox::Yes)
    {
        mavlink_message_t msg;
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getSystemId(), &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);
        result = true;
    }
}

pixhawk's avatar
pixhawk committed
866 867
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
868
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
869
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
870 871
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
872
#else
lm's avatar
lm committed
873 874 875 876
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
877
#endif
pixhawk's avatar
pixhawk committed
878 879
}

pixhawk's avatar
pixhawk committed
880 881
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
882
#ifdef MAVLINK_ENABLED_PIXHAWK
883 884 885
    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
886
#else
887 888 889 890
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
891 892 893 894 895
#endif
}

void UAS::startRadioControlCalibration()
{
896 897 898
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_RC);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
899 900
}

lm's avatar
lm committed
901 902
void UAS::startDataRecording()
{
903 904 905
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
    sendMessage(msg);
lm's avatar
lm committed
906 907 908 909
}

void UAS::pauseDataRecording()
{
910 911 912
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
    sendMessage(msg);
lm's avatar
lm committed
913 914 915 916
}

void UAS::stopDataRecording()
{
917 918 919
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
    sendMessage(msg);
lm's avatar
lm committed
920 921
}

pixhawk's avatar
pixhawk committed
922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942
void UAS::startMagnetometerCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_MAG);
    sendMessage(msg);
}

void UAS::startGyroscopeCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_GYRO);
    sendMessage(msg);
}

void UAS::startPressureCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_PRESSURE);
    sendMessage(msg);
}

943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964
quint64 UAS::getUnixTime(quint64 time)
{
    if (time == 0)
    {
        return MG::TIME::getGroundTimeNow();
    }
    // 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
965
#ifndef _MSC_VER
966
    else if (time < 1261440000000000LLU)
967
#else
968
        else if (time < 1261440000000000)
969
#endif
970
        {
971 972
        if (onboardTimeOffset == 0)
        {
973
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
974
        }
975
        return time/1000 + onboardTimeOffset;
976 977 978 979 980
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
981
        return time/1000;
982 983 984
    }
}

985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001
QList<QString> UAS::getParameterNames(int component)
{
    if (parameters.contains(component))
    {
        return parameters.value(component)->keys();
    }
    else
    {
        return QList<QString>();
    }
}

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

pixhawk's avatar
pixhawk committed
1002
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1003
{
lm's avatar
lm committed
1004
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1005
    {
1006
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1007
        mavlink_message_t msg;
lm's avatar
lm committed
1008
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1009
        sendMessage(msg);
lm's avatar
lm committed
1010
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1011
    }
pixhawk's avatar
pixhawk committed
1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>::iterator i;
    for (i = links->begin(); i != links->end(); ++i)
    {
        sendMessage(*i, message);
    }
}

1024 1025 1026 1027
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1028

1029 1030
    foreach(LinkInterface* link, link_list)
    {
1031
        if (link)
1032
        {
1033 1034
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1035
            {
1036 1037

                for(int i=0;i<links->size();i++)
1038
                {
1039 1040
                    if(serial != links->at(i))
                    {
1041
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1042 1043
                        sendMessage(serial, message);
                    }
1044 1045 1046 1047 1048 1049
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1050 1051
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1052
    if(!link) return;
pixhawk's avatar
pixhawk committed
1053 1054 1055
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1056
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1057
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068
    // If link is connected
    if (link->isConnected())
    {
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * @param value battery voltage
 */
1069
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1070
{
1071
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1072 1073 1074 1075 1076 1077
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1078
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1079
        uasState = tr("UNINIT");
1080
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
1081
        break;
lm's avatar
lm committed
1082
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1083
        uasState = tr("BOOT");
1084
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
1085
        break;
lm's avatar
lm committed
1086
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1087
        uasState = tr("CALIBRATING");
1088
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
1089
        break;
lm's avatar
lm committed
1090
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1091
        uasState = tr("ACTIVE");
1092
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
1093
        break;
lm's avatar
lm committed
1094 1095
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1096
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
1097 1098
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1099
        uasState = tr("CRITICAL");
1100
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
1101
        break;
lm's avatar
lm committed
1102
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1103
        uasState = tr("EMERGENCY");
1104
        stateDescription = tr("EMERGENCY: Land!");
pixhawk's avatar
pixhawk committed
1105
        break;
lm's avatar
lm committed
1106
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1107
        uasState = tr("SHUTDOWN");
1108
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
1109
        break;
lm's avatar
lm committed
1110
    default:
pixhawk's avatar
pixhawk committed
1111
        uasState = tr("UNKNOWN");
1112
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1126
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1127 1128 1129 1130 1131 1132 1133 1134
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1135
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1136 1137 1138 1139
{
    return commStatus;
}

1140 1141 1142
void UAS::requestParameters()
{
    mavlink_message_t msg;
1143
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1144 1145
    // Send message twice to increase chance of reception
    sendMessage(msg);
1146 1147
}

1148
void UAS::writeParametersToStorage()
1149
{
1150 1151 1152
    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, (uint8_t)MAV_ACTION_STORAGE_WRITE);
unknown's avatar
unknown committed
1153
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1154 1155 1156 1157 1158 1159 1160 1161 1162
    sendMessage(msg);
}

void UAS::readParametersFromStorage()
{
    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,(uint8_t)MAV_ACTION_STORAGE_READ);
    sendMessage(msg);
lm's avatar
lm committed
1163 1164
}

1165
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1166 1167
{
    // Buffers to write data to
1168
    mavlink_message_t msg;
1169
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1170 1171
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1172
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1173 1174
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1175 1176
    // 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
1177 1178
    stream.req_message_rate = 0;
    // Start / stop the message
1179
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1180 1181 1182 1183 1184
    // 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
1185
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1186 1187
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1188 1189 1190
    sendMessage(msg);
}

1191
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1192 1193 1194
{
    // Buffers to write data to
    mavlink_message_t msg;
1195
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1196
    // Select the message to request from now on
1197
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1198
    // Select the update rate in Hz the message should be send
1199
    stream.req_message_rate = rate;
lm's avatar
lm committed
1200
    // Start / stop the message
1201
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1202 1203 1204 1205 1206
    // 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
1207
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1208 1209
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1210 1211 1212
    sendMessage(msg);
}

1213
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1214
{
1215 1216 1217 1218
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1219
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1220
    // Select the update rate in Hz the message should be send
1221
    stream.req_message_rate = rate;
1222
    // Start / stop the message
1223
    stream.start_stop = (rate) ? 1 : 0;
1224 1225 1226 1227 1228 1229
    // 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);
1230 1231
    // Send message twice to increase chance of reception
    sendMessage(msg);
1232
    sendMessage(msg);
lm's avatar
lm committed
1233
}
1234

1235
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1236
{
1237 1238 1239 1240 1241
#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
1242 1243 1244
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1245
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1246
    // Select the update rate in Hz the message should be send
1247
    stream.req_message_rate = rate;
1248
    // Start / stop the message
1249
    stream.start_stop = (rate) ? 1 : 0;
1250 1251 1252 1253 1254 1255
    // 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);
1256 1257
    // Send message twice to increase chance of reception
    sendMessage(msg);
1258
    sendMessage(msg);
1259
#endif
lm's avatar
lm committed
1260 1261
}

1262
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1263
{
1264 1265 1266 1267
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1268
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1269
    // Select the update rate in Hz the message should be send
1270
    stream.req_message_rate = rate;
1271
    // Start / stop the message
1272
    stream.start_stop = (rate) ? 1 : 0;
1273 1274 1275 1276 1277 1278
    // 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);
1279 1280
    // Send message twice to increase chance of reception
    sendMessage(msg);
1281
    sendMessage(msg);
lm's avatar
lm committed
1282 1283
}

1284
void UAS::enableRawSensorFusionTransmission(int rate)
lm's avatar
lm committed
1285
{
1286 1287 1288 1289
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1290
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
1291
    // Select the update rate in Hz the message should be send
1292
    stream.req_message_rate = rate;
1293
    // Start / stop the message
1294
    stream.start_stop = (rate) ? 1 : 0;
1295 1296 1297 1298 1299 1300
    // 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);
1301 1302
    // Send message twice to increase chance of reception
    sendMessage(msg);
1303
    sendMessage(msg);
1304 1305
}

1306
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1307 1308 1309 1310 1311
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1312
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1313
    // Select the update rate in Hz the message should be send
1314
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1315
    // Start / stop the message
1316
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327
    // 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);
}

1328
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1329 1330 1331 1332 1333
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1334
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1335
    // Select the update rate in Hz the message should be send
1336
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1337
    // Start / stop the message
1338
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349
    // 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);
}

1350
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1351 1352 1353 1354 1355
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1356
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1357
    // Select the update rate in Hz the message should be send
1358
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1359
    // Start / stop the message
1360
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371
    // 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);
}

1372
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1373 1374 1375 1376 1377
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1378
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1379
    // Select the update rate in Hz the message should be send
1380
    stream.req_message_rate = rate;
1381
    // Start / stop the message
1382
    stream.start_stop = (rate) ? 1 : 0;
1383 1384 1385 1386 1387 1388
    // 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);
1389 1390
    // Send message twice to increase chance of reception
    sendMessage(msg);
1391
    sendMessage(msg);
1392 1393
}

lm's avatar
lm committed
1394 1395 1396 1397 1398 1399 1400
/**
 * 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
1401 1402 1403 1404
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1405 1406 1407
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1408 1409
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1410

1411
    // Copy string into buffer, ensuring not to exceed the buffer size    
1412
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1413
    {
lm's avatar
lm committed
1414
        // String characters
1415
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1416
        {
1417
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1418 1419
        }
        // Null termination at end of string or end of buffer
1420
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1421 1422 1423 1424 1425 1426 1427 1428
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1429
    }    
1430
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1431
    sendMessage(msg);
lm's avatar
lm committed
1432
    }
1433 1434
}

1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
    if (airframe == 0)
    {
        switch (systemType)
        {
        case MAV_FIXED_WING:
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
        case MAV_QUADROTOR:
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1454 1455 1456
void UAS::setUASName(const QString& name)
{
    this->name = name;
1457
    writeSettings();
1458
    emit nameChanged(name);
1459
    emit systemSpecsChanged(uasId);
1460 1461
}

1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474
/**
 * Sets an action
 *
 **/
void UAS::setAction(MAV_ACTION action)
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, action);
    // Send message twice to increase chance that it reaches its goal
    sendMessage(msg);
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1475
/**
lm's avatar
lm committed
1476
 * Launches the system
pixhawk's avatar
pixhawk committed
1477 1478 1479 1480
 *
 **/
void UAS::launch()
{
1481
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1482
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1483
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1484 1485 1486
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1487 1488 1489 1490 1491 1492 1493 1494
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1495
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1496
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1497
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1498 1499 1500
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1501 1502 1503 1504 1505 1506 1507 1508
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1509
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1510
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1511
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1512 1513 1514
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528
}

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;

1529 1530 1531 1532 1533 1534
    if(mode == (int)MAV_MODE_MANUAL)
    {
        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
1535

1536 1537 1538 1539 1540 1541
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    }
    else
    {
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1542 1543
}

1544 1545 1546 1547 1548
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1549 1550 1551 1552 1553
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1554

pixhawk's avatar
pixhawk committed
1555 1556
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1557

pixhawk's avatar
pixhawk committed
1558 1559 1560 1561 1562
        break;
    default:

        break;
    }
1563
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1564 1565 1566

}

1567

1568
/*void UAS::requestWaypoints()
1569 1570 1571 1572 1573
{
//    mavlink_message_t msg;
//    mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1574 1575
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1576 1577
}

pixhawk's avatar
pixhawk committed
1578 1579
void UAS::setWaypoint(Waypoint* wp)
{
1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597
//    mavlink_message_t msg;
//    mavlink_waypoint_set_t set;
//    set.id = wp->id;
//    //QString name = wp->name;
//    // FIXME Check if this works properly
//    //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN);
//    //strcpy((char*)set.name, name.toStdString().c_str());
//    set.autocontinue = wp->autocontinue;
//    set.target_component = 25; // FIXME
//    set.target_system = uasId;
//    set.active = wp->current;
//    set.x = wp->x;
//    set.y = wp->y;
//    set.z = wp->z;
//    set.yaw = wp->yaw;
//    mavlink_msg_waypoint_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &set);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1598 1599 1600 1601
}

void UAS::setWaypointActive(int id)
{
1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624
//    mavlink_message_t msg;
//    mavlink_waypoint_set_active_t active;
//    active.id = id;
//    active.target_system = uasId;
//    active.target_component = 25; // FIXME
//    mavlink_msg_waypoint_set_active_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &active);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
//    // TODO This should be not directly emitted, but rather being fed back from the UAS
//    emit waypointSelected(getUASID(), id);
}

void UAS::clearWaypointList()
{
//    mavlink_message_t msg;
//    // FIXME
//    mavlink_waypoint_clear_list_t clist;
//    clist.target_system = uasId;
//    clist.target_component = 25;  // FIXME
//    mavlink_msg_waypoint_clear_list_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &clist);
//    sendMessage(msg);
//    qDebug() << "UAS clears Waypoints!";
1625
}*/
pixhawk's avatar
pixhawk committed
1626 1627 1628 1629


void UAS::halt()
{
1630
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1631
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1632
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1633 1634 1635
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1636 1637 1638 1639
}

void UAS::go()
{
1640
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1641
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1642
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1643 1644 1645
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1646 1647 1648 1649 1650
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1651
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1652
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1653
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1654 1655 1656
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1657 1658 1659 1660 1661 1662 1663 1664
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1665
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1666
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1667
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1668 1669 1670
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695
}

/**
 * All systems are immediately shut down (e.g. the main power line is cut).
 * @warning This might lead to a crash
 *
 * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
 */
bool UAS::emergencyKILL()
{
    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)
    {
1696
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1697
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1698
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1699 1700 1701
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724
        result = true;
    }
    return result;
}

void UAS::shutdown()
{
    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
1725
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1726
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1727
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1728 1729 1730
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1731 1732 1733 1734
        result = true;
    }
}

1735 1736
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1737 1738 1739 1740 1741 1742
    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);
1743 1744
}

pixhawk's avatar
pixhawk committed
1745 1746 1747
/**
 * @return The name of this system as string in human-readable form
 */
1748
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766
{
    QString result;
    if (name == "")
    {
        result = tr("MAV ") + result.sprintf("%03d", getUASID());
    }
    else
    {
        result = name;
    }
    return result;
}

void UAS::addLink(LinkInterface* link)
{
    if (!links->contains(link))
    {
        links->append(link);
1767
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1768 1769
    }
    //links->append(link);
1770
    //qDebug() << link<<" ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
pixhawk's avatar
pixhawk committed
1771 1772
}

1773 1774 1775 1776 1777 1778 1779 1780 1781
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798
/**
 * @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;
    switch (batteryType)
    {
lm's avatar
lm committed
1799
    case NICD:
pixhawk's avatar
pixhawk committed
1800
        break;
lm's avatar
lm committed
1801
    case NIMH:
pixhawk's avatar
pixhawk committed
1802
        break;
lm's avatar
lm committed
1803
    case LIION:
pixhawk's avatar
pixhawk committed
1804
        break;
lm's avatar
lm committed
1805
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1806 1807 1808
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1809
    case LIFE:
pixhawk's avatar
pixhawk committed
1810
        break;
lm's avatar
lm committed
1811
    case AGZN:
pixhawk's avatar
pixhawk committed
1812 1813 1814 1815
        break;
    }
}

1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842
void UAS::setBatterySpecs(const QString& specs)
{
    QString stringList = specs;
    stringList = stringList.remove("V");
    stringList = stringList.remove("v");
    QStringList parts = stringList.split(",");
    if (parts.length() == 3)
    {
        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;
    }
}

QString UAS::getBatterySpecs()
{
    return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
}

pixhawk's avatar
pixhawk committed
1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855
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
1856 1857 1858
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1859 1860
double UAS::getChargeLevel()
{
1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874
    float chargeLevel;
    if (lpVoltage < emptyVoltage)
    {
        chargeLevel = 0.0f;
    }
    else if (lpVoltage > fullVoltage)
    {
        chargeLevel = 100.0f;
    }
    else
    {
        chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
1875 1876
}

lm's avatar
lm committed
1877 1878 1879 1880
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1881 1882
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894
        lowBattAlarm = true;
    }
}

void UAS::stopLowBattAlarm()
{
    if (lowBattAlarm)
    {
        GAudioOutput::instance()->stopEmergency();
        lowBattAlarm = false;
    }
}