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

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

#include <QList>
#include <QMessageBox>
#include <QTimer>
15
#include <QSettings>
pixhawk's avatar
pixhawk committed
16 17 18 19 20 21
#include <iostream>
#include <QDebug>
#include <cmath>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
22
//#include "MG.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

pixhawk's avatar
pixhawk committed
30 31 32 33 34 35 36 37 38 39 40 41 42
#ifndef M_PI
#define M_PI        3.14159265358979323846  /* pi */
#endif

#ifndef M_PI_2
#define M_PI_2      1.57079632679489661923  /* pi/2 */
#endif

#ifndef M_PI_4
#define M_PI_4      0.78539816339744830962  /* pi/4 */
#endif


43

44
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84
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),
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)),
paramsOnceRequested(false)
pixhawk's avatar
pixhawk committed
85
{
86
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
87
    setBattery(LIPOLY, 3);
88
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
89
    statusTimeout->start(500);
90
    readSettings();
pixhawk's avatar
pixhawk committed
91 92 93 94
}

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

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

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
    settings.endGroup();
}

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

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

132 133 134 135 136 137 138 139
    // 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
140
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
141 142 143 144 145 146
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
147 148 149 150 151
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

152 153 154 155 156 157 158 159 160 161 162 163
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {

    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {

    }
}

pixhawk's avatar
pixhawk committed
164 165
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
166
    if (!link) return;
pixhawk's avatar
pixhawk committed
167 168 169
    if (!links->contains(link))
    {
        addLink(link);
170
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
171
    }
172 173 174 175
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
176

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

pixhawk's avatar
pixhawk committed
179 180 181 182 183 184 185 186
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
        QString patternPath;
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
187
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
188 189
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
190
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
191
            {
pixhawk's avatar
pixhawk committed
192
                this->type = mavlink_msg_heartbeat_get_type(&message);
193
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
194 195
                emit systemTypeSet(this, type);
            }
196

pixhawk's avatar
pixhawk committed
197 198 199 200 201 202
            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
203 204
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
205 206
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
207

pixhawk's avatar
pixhawk committed
208
                // FIXME
209
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
210

pixhawk's avatar
pixhawk committed
211 212 213 214 215
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
216

pixhawk's avatar
pixhawk committed
217
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
218
                {
pixhawk's avatar
pixhawk committed
219
                    statechanged = true;
lm's avatar
lm committed
220
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
221 222
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
223
                    emit statusChanged(this->status);
224
                    emit loadChanged(this,state.load/10.0f);
225
                    emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
226
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
227 228
                }

lm's avatar
lm committed
229
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
230 231
                {
                    modechanged = true;
lm's avatar
lm committed
232
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
233 234
                    QString mode;

lm's avatar
lm committed
235
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
236
                    {
lm's avatar
lm committed
237
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
238 239
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
240
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
241 242
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
243
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
244 245
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
246
                    case (uint8_t)MAV_MODE_GUIDED:
247 248
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
249
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
250 251
                        mode = "READY";
                        break;
lm's avatar
lm committed
252
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
253 254
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
255
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
256 257
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
258
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
259 260
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
261 262 263
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
264 265 266 267 268 269 270 271
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
272
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
273
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
274 275 276
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
277
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
278
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
279

lm's avatar
lm committed
280 281
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
282
                if (chargeLevel <= 20.0f)
lm's avatar
lm committed
283 284 285 286 287 288 289 290
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
291
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
292
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
293
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
294 295

                // AUDIO
pixhawk's avatar
pixhawk committed
296 297 298 299 300 301 302 303 304 305
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
306
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
307 308 309 310 311 312 313 314
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
315 316 317 318 319 320

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
321 322 323
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
324
            {
pixhawk's avatar
pixhawk committed
325 326
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
327
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
328

329 330 331 332 333 334 335 336 337
                emit valueChanged(uasId, "accel x", "raw", raw.xacc, time);
                emit valueChanged(uasId, "accel y", "raw", raw.yacc, time);
                emit valueChanged(uasId, "accel z", "raw", 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", raw.xmag, time);
                emit valueChanged(uasId, "mag y", "raw", raw.ymag, time);
                emit valueChanged(uasId, "mag z", "raw", raw.zmag, time);
pixhawk's avatar
pixhawk committed
338 339 340 341
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
342
            //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
343
            {
pixhawk's avatar
pixhawk committed
344 345
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
346
                quint64 time = getUnixTime(attitude.usec);
lm's avatar
lm committed
347 348 349
                roll = attitude.roll;
                pitch = attitude.pitch;
                yaw = attitude.yaw;
350 351 352
//                emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
//                emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
//                emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
353 354 355 356 357 358
                emit valueChanged(uasId, "roll", "rad", mavlink_msg_attitude_get_roll(&message), time);
                emit valueChanged(uasId, "pitch", "rad", mavlink_msg_attitude_get_pitch(&message), time);
                emit valueChanged(uasId, "yaw", "rad", mavlink_msg_attitude_get_yaw(&message), 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);
359 360

                // Emit in angles
361 362
                emit valueChanged(uasId, "roll", "deg", (attitude.roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch", "deg", (attitude.pitch/M_PI)*180.0, time);
lm's avatar
lm committed
363

364 365
                emit valueChanged(uasId, "rollspeed", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitchspeed", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
lm's avatar
lm committed
366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382

                // Force yaw to 180 deg range
                double yaw = ((attitude.yaw/M_PI)*180.0);
                double sign = 1.0;
                if (yaw < 0)
                {
                    sign = -1.0;
                    yaw = -yaw;
                }
                while (yaw > 180.0)
                {
                    yaw -= 180.0;
                }

                yaw *= sign;

                emit valueChanged(uasId, "yaw", "deg", yaw, time);
383
                emit valueChanged(uasId, "yawspeed", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
384

385
                emit attitudeChanged(this, attitude.roll, attitude.pitch, attitude.yaw, time);
pixhawk's avatar
pixhawk committed
386 387
            }
            break;
388
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
389
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
390
            //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
391
            {
392 393
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
394
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
395 396 397
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
398 399 400 401 402 403
                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
404
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
405
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
406

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

410
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
411 412 413 414 415 416 417
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
418 419
            }
            break;
420
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
421 422 423
            //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;
            {
424 425
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
426
                quint64 time = QGC::groundTimeUsecs()/1000;
427 428 429 430 431 432
                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;
433 434 435 436 437 438
                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);
439 440
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
pixhawk's avatar
pixhawk committed
441 442 443 444 445 446 447
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
448 449
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
450 451 452 453 454 455 456 457
            }
            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);
458 459 460

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

464 465
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
466

467 468 469 470 471 472
                // FIXME REMOVE
                longitude = pos.lon;
                latitude = pos.lat;
                altitude = pos.alt;
                emit globalPositionChanged(this, longitude, latitude, altitude, time);

lm's avatar
lm committed
473
                if (pos.fix_type > 0)
474
                {
Laurens Mackay's avatar
Laurens Mackay committed
475
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
476 477 478 479 480 481 482 483

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
484
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
485 486 487
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
488
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
489
                        //qDebug() << "GOT GPS RAW";
490
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
491 492 493 494 495
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
496
                }
497 498
            }
            break;
lm's avatar
lm committed
499 500 501 502
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
503
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
504
                {
lm's avatar
lm committed
505
                    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
506 507 508
                }
            }
            break;
509 510 511 512 513 514 515
        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;
516 517 518 519
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
520 521 522 523
                quint64 time = this->getUnixTime(0);
                emit valueChanged(uasId, "abs pressure", "hP", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "hP", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "hP", pressure.press_diff2, time);
524 525
            }
            break;
526
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
527
            {
528 529
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
530
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553
                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
554 555
            }
            break;
556 557 558 559
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576

                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);
577 578
            }
            break;
pixhawk's avatar
pixhawk committed
579
        case MAVLINK_MSG_ID_DEBUG:
580
            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
581
            break;
582 583 584 585 586
        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
587
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
588 589 590
                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);
591 592 593 594 595 596
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
597
                quint64 time = MG::TIME::getGroundTimeNow();
598
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
599 600 601
                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);
602 603
            }
            break;
pixhawk's avatar
pixhawk committed
604 605 606 607
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
608 609 610 611
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
612 613 614
            }
            break;

615
        case MAVLINK_MSG_ID_WAYPOINT:
616
            {
617 618
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
619
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
620 621 622 623
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
624
            }
pixhawk's avatar
pixhawk committed
625
            break;
pixhawk's avatar
pixhawk committed
626

627 628 629 630 631 632 633 634 635 636 637
        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
638 639 640 641
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
642 643 644 645
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
646 647 648
            }
            break;

649
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
650
            {
pixhawk's avatar
pixhawk committed
651 652 653
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
654
            }
pixhawk's avatar
pixhawk committed
655
            break;
pixhawk's avatar
pixhawk committed
656

657
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
658
            {
659 660 661
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
662
            }
pixhawk's avatar
pixhawk committed
663
            break;
pixhawk's avatar
pixhawk committed
664

665 666 667 668 669 670 671
        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
672

673
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
674 675 676
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
677
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
678 679
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
680
                int severity = mavlink_msg_statustext_get_severity(&message);
681
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
682
                //emit statusTextReceived(severity, text);
683
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
684 685
            }
            break;
686 687 688 689 690 691
    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);
692 693 694
                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);
695 696
            }
            break;
697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712
            //#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
713
#ifdef MAVLINK_ENABLED_UALBERTA
714 715 716 717 718
        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();
719 720 721 722 723 724
                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);
725 726
            }
            break;
727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750
       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];

751
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
752 753 754 755 756
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

757
#endif
pixhawk's avatar
pixhawk committed
758
        default:
lm's avatar
lm committed
759 760 761 762
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
763 764
                    //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
765 766 767
                    //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
768 769 770 771 772
            break;
        }
    }
}

773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802
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
803 804
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
805
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
806
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
807 808
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
809
#else
lm's avatar
lm committed
810 811 812 813
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
814
#endif
pixhawk's avatar
pixhawk committed
815 816
}

pixhawk's avatar
pixhawk committed
817 818
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
819
#ifdef MAVLINK_ENABLED_PIXHAWK
820 821 822
    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
823
#else
824 825 826 827
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
828 829 830 831 832
#endif
}

void UAS::startRadioControlCalibration()
{
833 834 835
    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
836 837
}

lm's avatar
lm committed
838 839
void UAS::startDataRecording()
{
840 841 842
    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
843 844 845 846
}

void UAS::pauseDataRecording()
{
847 848 849
    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
850 851 852 853
}

void UAS::stopDataRecording()
{
854 855 856
    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
857 858
}

pixhawk's avatar
pixhawk committed
859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879
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);
}

880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901
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
902
#ifndef _MSC_VER
903
    else if (time < 1261440000000000LLU)
904
#else
905
        else if (time < 1261440000000000)
906
#endif
907
        {
908 909
        if (onboardTimeOffset == 0)
        {
910
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
911
        }
912
        return time/1000 + onboardTimeOffset;
913 914 915 916 917
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
918
        return time/1000;
919 920 921
    }
}

922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938
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
939
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
940
{
lm's avatar
lm committed
941
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
942
    {
943
        this->mode = mode;
pixhawk's avatar
pixhawk committed
944
        mavlink_message_t msg;
lm's avatar
lm committed
945
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
946
        sendMessage(msg);
lm's avatar
lm committed
947
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
948
    }
pixhawk's avatar
pixhawk committed
949 950 951 952 953 954 955 956 957 958 959 960
}

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

961 962 963 964
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
965

966 967
    foreach(LinkInterface* link, link_list)
    {
968
        if (link)
969
        {
970 971
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
972
            {
973 974

                for(int i=0;i<links->size();i++)
975
                {
976 977 978 979 980
                    if(serial != links->at(i))
                    {
                        qDebug()<<"Forwarding Over link: "<<serial->getName()<<" "<<serial;
                        sendMessage(serial, message);
                    }
981 982 983 984 985 986
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
987 988
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
989
    if(!link) return;
pixhawk's avatar
pixhawk committed
990 991 992
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
993
    int len = mavlink_msg_to_send_buffer(buffer, &message);
994
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
995 996 997 998 999 1000 1001 1002 1003 1004 1005
    // 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
 */
1006
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1007
{
1008
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1009 1010 1011 1012 1013 1014
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1015
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1016
        uasState = tr("UNINIT");
1017
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
1018
        break;
lm's avatar
lm committed
1019
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1020
        uasState = tr("BOOT");
1021
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
1022
        break;
lm's avatar
lm committed
1023
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1024
        uasState = tr("CALIBRATING");
1025
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
1026
        break;
lm's avatar
lm committed
1027
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1028
        uasState = tr("ACTIVE");
1029
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
1030
        break;
lm's avatar
lm committed
1031 1032
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1033
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
1034 1035
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1036
        uasState = tr("CRITICAL");
1037
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
1038
        break;
lm's avatar
lm committed
1039
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1040 1041 1042
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
1043
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1044
        uasState = tr("SHUTDOWN");
1045
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
1046
        break;
lm's avatar
lm committed
1047
    default:
pixhawk's avatar
pixhawk committed
1048
        uasState = tr("UNKNOWN");
1049
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1063
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1064 1065 1066 1067 1068 1069 1070 1071
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1072
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1073 1074 1075 1076
{
    return commStatus;
}

1077 1078 1079
void UAS::requestParameters()
{
    mavlink_message_t msg;
1080
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1081 1082
    // Send message twice to increase chance of reception
    sendMessage(msg);
1083 1084
}

1085
void UAS::writeParametersToStorage()
1086
{
1087 1088 1089
    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
1090
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1091 1092 1093 1094 1095 1096 1097 1098 1099
    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
1100 1101
}

1102
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1103 1104
{
    // Buffers to write data to
1105
    mavlink_message_t msg;
1106
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1107 1108
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1109
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1110 1111
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1112 1113
    // 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
1114 1115
    stream.req_message_rate = 0;
    // Start / stop the message
1116
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1117 1118 1119 1120 1121
    // 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
1122
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1123 1124
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1125 1126 1127
    sendMessage(msg);
}

1128
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1129 1130 1131
{
    // Buffers to write data to
    mavlink_message_t msg;
1132
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1133
    // Select the message to request from now on
1134
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1135
    // Select the update rate in Hz the message should be send
1136
    stream.req_message_rate = rate;
lm's avatar
lm committed
1137
    // Start / stop the message
1138
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1139 1140 1141 1142 1143
    // 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
1144
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1145 1146
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1147 1148 1149
    sendMessage(msg);
}

1150
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1151
{
1152 1153 1154 1155
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1156
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1157
    // Select the update rate in Hz the message should be send
1158
    stream.req_message_rate = rate;
1159
    // Start / stop the message
1160
    stream.start_stop = (rate) ? 1 : 0;
1161 1162 1163 1164 1165 1166
    // 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);
1167 1168
    // Send message twice to increase chance of reception
    sendMessage(msg);
1169
    sendMessage(msg);
lm's avatar
lm committed
1170
}
1171

1172
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1173
{
1174 1175 1176 1177 1178
#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
1179 1180 1181
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1182
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1183
    // Select the update rate in Hz the message should be send
1184
    stream.req_message_rate = rate;
1185
    // Start / stop the message
1186
    stream.start_stop = (rate) ? 1 : 0;
1187 1188 1189 1190 1191 1192
    // 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);
1193 1194
    // Send message twice to increase chance of reception
    sendMessage(msg);
1195
    sendMessage(msg);
1196
#endif
lm's avatar
lm committed
1197 1198
}

1199
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1200
{
1201 1202 1203 1204
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1205
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1206
    // Select the update rate in Hz the message should be send
1207
    stream.req_message_rate = rate;
1208
    // Start / stop the message
1209
    stream.start_stop = (rate) ? 1 : 0;
1210 1211 1212 1213 1214 1215
    // 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);
1216 1217
    // Send message twice to increase chance of reception
    sendMessage(msg);
1218
    sendMessage(msg);
lm's avatar
lm committed
1219 1220
}

1221
void UAS::enableRawSensorFusionTransmission(int rate)
lm's avatar
lm committed
1222
{
1223 1224 1225 1226
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1227
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
1228
    // Select the update rate in Hz the message should be send
1229
    stream.req_message_rate = rate;
1230
    // Start / stop the message
1231
    stream.start_stop = (rate) ? 1 : 0;
1232 1233 1234 1235 1236 1237
    // 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);
1238 1239
    // Send message twice to increase chance of reception
    sendMessage(msg);
1240
    sendMessage(msg);
1241 1242
}

1243
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1244 1245 1246 1247 1248
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1249
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1250
    // Select the update rate in Hz the message should be send
1251
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1252
    // Start / stop the message
1253
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264
    // 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);
}

1265
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1266 1267 1268 1269 1270
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1271
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1272
    // Select the update rate in Hz the message should be send
1273
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1274
    // Start / stop the message
1275
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286
    // 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);
}

1287
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1288 1289 1290 1291 1292
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1293
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1294
    // Select the update rate in Hz the message should be send
1295
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1296
    // Start / stop the message
1297
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308
    // 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);
}

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

lm's avatar
lm committed
1331 1332 1333 1334 1335 1336 1337
/**
 * 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
1338 1339 1340 1341
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1342 1343 1344
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1345 1346
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1347

1348
    // Copy string into buffer, ensuring not to exceed the buffer size    
1349
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1350
    {
lm's avatar
lm committed
1351
        // String characters
1352
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1353
        {
1354
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1355 1356
        }
        // Null termination at end of string or end of buffer
1357
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1358 1359 1360 1361 1362 1363 1364 1365
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1366
    }    
1367
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1368
    sendMessage(msg);
lm's avatar
lm committed
1369
    }
1370 1371
}

1372 1373 1374
void UAS::setUASName(const QString& name)
{
    this->name = name;
1375
    writeSettings();
1376 1377 1378
    emit nameChanged(name);
}

1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391
/**
 * 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
1392
/**
lm's avatar
lm committed
1393
 * Launches the system
pixhawk's avatar
pixhawk committed
1394 1395 1396 1397
 *
 **/
void UAS::launch()
{
1398
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1399
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1400
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1401 1402 1403
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1404 1405 1406 1407 1408 1409 1410 1411
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1412
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1413
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1414
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1415 1416 1417
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1418 1419 1420 1421 1422 1423 1424 1425
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1426
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1427
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1428
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1429 1430 1431
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445
}

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;

1446 1447 1448 1449 1450 1451
    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
1452

1453 1454 1455 1456 1457 1458
        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
1459 1460
}

1461 1462 1463 1464 1465
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1466 1467 1468 1469 1470
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1471

pixhawk's avatar
pixhawk committed
1472 1473
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1474

pixhawk's avatar
pixhawk committed
1475 1476 1477 1478 1479
        break;
    default:

        break;
    }
1480
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1481 1482 1483

}

1484

1485
/*void UAS::requestWaypoints()
1486 1487 1488 1489 1490
{
//    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
1491 1492
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1493 1494
}

pixhawk's avatar
pixhawk committed
1495 1496
void UAS::setWaypoint(Waypoint* wp)
{
1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514
//    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
1515 1516 1517 1518
}

void UAS::setWaypointActive(int id)
{
1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541
//    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!";
1542
}*/
pixhawk's avatar
pixhawk committed
1543 1544 1545 1546


void UAS::halt()
{
1547
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1548
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1549
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1550 1551 1552
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1553 1554 1555 1556
}

void UAS::go()
{
1557
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1558
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1559
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1560 1561 1562
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1563 1564 1565 1566 1567
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1568
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1569
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1570
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1571 1572 1573
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1574 1575 1576 1577 1578 1579 1580 1581
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1582
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1583
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1584
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1585 1586 1587
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612
}

/**
 * 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)
    {
1613
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1614
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1615
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1616 1617 1618
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641
        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
1642
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1643
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1644
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1645 1646 1647
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1648 1649 1650 1651
        result = true;
    }
}

1652 1653
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1654 1655 1656 1657 1658 1659
    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);
1660 1661
}

pixhawk's avatar
pixhawk committed
1662 1663 1664
/**
 * @return The name of this system as string in human-readable form
 */
1665
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683
{
    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);
1684
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1685 1686
    }
    //links->append(link);
1687
    //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
1688 1689
}

1690 1691 1692 1693 1694 1695 1696 1697 1698
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715
/**
 * @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
1716
    case NICD:
pixhawk's avatar
pixhawk committed
1717
        break;
lm's avatar
lm committed
1718
    case NIMH:
pixhawk's avatar
pixhawk committed
1719
        break;
lm's avatar
lm committed
1720
    case LIION:
pixhawk's avatar
pixhawk committed
1721
        break;
lm's avatar
lm committed
1722
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1723 1724 1725
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1726
    case LIFE:
pixhawk's avatar
pixhawk committed
1727
        break;
lm's avatar
lm committed
1728
    case AGZN:
pixhawk's avatar
pixhawk committed
1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745
        break;
    }
}

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
1746 1747 1748
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1749 1750
double UAS::getChargeLevel()
{
1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764
    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
1765 1766
}

lm's avatar
lm committed
1767 1768 1769 1770
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1771 1772
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784
        lowBattAlarm = true;
    }
}

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