UAS.cc 67 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
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)),
84 85
paramsOnceRequested(false),
airframe(0)
pixhawk's avatar
pixhawk committed
86
{
87
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
88
    setBattery(LIPOLY, 3);
89
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
90
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
91
    statusTimeout->start(500);
92
    readSettings();
pixhawk's avatar
pixhawk committed
93 94 95 96
}

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

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

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

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

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

138 139 140 141 142 143 144 145
    // 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
146
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
147 148 149 150 151 152
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
153 154
void UAS::setSelected()
{
155 156 157 158 159 160 161 162 163 164
    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
165 166
}

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

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

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

pixhawk's avatar
pixhawk committed
198 199 200 201 202
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
        QString patternPath;
pixhawk's avatar
pixhawk committed
203 204 205 206

        // Receive named value message
        receiveMessageNamedValue(message);

pixhawk's avatar
pixhawk committed
207 208 209
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
210
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
211 212
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
213
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
214
            {
pixhawk's avatar
pixhawk committed
215
                this->type = mavlink_msg_heartbeat_get_type(&message);
216 217 218 219 220 221 222 223 224 225 226 227 228 229 230
                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;
                    }
                }
231
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
232 233
                emit systemTypeSet(this, type);
            }
234

pixhawk's avatar
pixhawk committed
235 236 237 238 239 240
            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
241 242
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
243 244
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
245

pixhawk's avatar
pixhawk committed
246
                // FIXME
247
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
248

pixhawk's avatar
pixhawk committed
249 250 251 252 253
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
254

pixhawk's avatar
pixhawk committed
255
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
256
                {
pixhawk's avatar
pixhawk committed
257
                    statechanged = true;
lm's avatar
lm committed
258
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
259 260
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
261
                    emit statusChanged(this->status);
262
                    emit loadChanged(this,state.load/10.0f);
263
                    emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
264
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
265 266
                }

267 268
                qDebug() << "Remote Mode: " << state.mode;
                qDebug() << "Loclal Mode: " << this->mode;
lm's avatar
lm committed
269
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
270 271
                {
                    modechanged = true;
lm's avatar
lm committed
272
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
273 274
                    QString mode;

lm's avatar
lm committed
275
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
276
                    {
lm's avatar
lm committed
277
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
278 279
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
280
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
281 282
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
283
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
284 285
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
286
                    case (uint8_t)MAV_MODE_GUIDED:
287 288
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
289
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
290 291
                        mode = "READY";
                        break;
lm's avatar
lm committed
292
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
293 294
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
295
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
296 297
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
298
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
299 300
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
301 302 303
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
304 305 306 307 308 309 310 311
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
312
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
313
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
314 315 316
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
317
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
318
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
319

lm's avatar
lm committed
320 321
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
322
                if (chargeLevel <= 20.0f)
lm's avatar
lm committed
323 324 325 326 327 328 329 330
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
331
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
332
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
333
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
334 335

                // AUDIO
pixhawk's avatar
pixhawk committed
336 337 338 339 340 341 342 343 344 345
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
346
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
347 348 349 350 351 352 353 354
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
355 356 357 358 359 360

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
361 362 363
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
364
            {
pixhawk's avatar
pixhawk committed
365 366
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
367
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
368

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

                // Emit in angles
401 402
                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
403

404 405
                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
406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422

                // 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);
423
                emit valueChanged(uasId, "yawspeed", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
424

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

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

450
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
451 452 453 454 455 456 457
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
458 459
            }
            break;
460
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
461 462 463
            //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;
            {
464 465
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
466
                quint64 time = QGC::groundTimeUsecs()/1000;
467 468 469 470 471 472
                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;
473 474 475 476 477 478
                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);
479 480
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
pixhawk's avatar
pixhawk committed
481 482 483 484 485 486 487
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
488 489
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
490 491 492 493 494 495 496 497
            }
            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);
498 499 500

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

504 505
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
506

507 508 509 510 511 512
                // FIXME REMOVE
                longitude = pos.lon;
                latitude = pos.lat;
                altitude = pos.alt;
                emit globalPositionChanged(this, longitude, latitude, altitude, time);

lm's avatar
lm committed
513
                if (pos.fix_type > 0)
514
                {
Laurens Mackay's avatar
Laurens Mackay committed
515
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
516 517 518 519 520 521 522 523

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
524
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
525 526 527
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
528
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
529
                        //qDebug() << "GOT GPS RAW";
530
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
531 532 533 534 535
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
536
                }
537 538
            }
            break;
lm's avatar
lm committed
539 540 541 542
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
543
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
544
                {
lm's avatar
lm committed
545
                    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
546 547 548
                }
            }
            break;
549 550 551 552 553 554 555
        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;
556 557 558 559
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
560 561 562 563
                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);
564 565
            }
            break;
566
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
567
            {
568 569
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
570
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593
                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
594 595
            }
            break;
596 597 598 599
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616

                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);
617 618
            }
            break;
pixhawk's avatar
pixhawk committed
619
        case MAVLINK_MSG_ID_DEBUG:
620
            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
621
            break;
622 623 624 625 626
        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
627
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
628 629 630
                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);
631 632 633 634 635 636
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
637
                quint64 time = MG::TIME::getGroundTimeNow();
638
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
639 640 641
                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);
642 643
            }
            break;
pixhawk's avatar
pixhawk committed
644 645 646 647
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
648 649 650 651
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
652 653 654
            }
            break;

655
        case MAVLINK_MSG_ID_WAYPOINT:
656
            {
657 658
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
659
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
660 661 662 663
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
664
            }
pixhawk's avatar
pixhawk committed
665
            break;
pixhawk's avatar
pixhawk committed
666

667 668 669 670 671 672 673 674 675 676 677
        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
678 679 680 681
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
682 683 684 685
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
686 687 688
            }
            break;

689
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
690
            {
pixhawk's avatar
pixhawk committed
691 692 693
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
694
            }
pixhawk's avatar
pixhawk committed
695
            break;
pixhawk's avatar
pixhawk committed
696

697
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
698
            {
699 700 701
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
702
            }
pixhawk's avatar
pixhawk committed
703
            break;
pixhawk's avatar
pixhawk committed
704

705 706 707 708 709 710 711
        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
712

713
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
714 715 716
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
717
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
718 719
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
720
                int severity = mavlink_msg_statustext_get_severity(&message);
721
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
722
                //emit statusTextReceived(severity, text);
723
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
724 725
            }
            break;
726 727 728 729 730 731
    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);
732 733 734
                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);
735 736
            }
            break;
737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752
            //#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
753
#ifdef MAVLINK_ENABLED_UALBERTA
754 755 756 757 758
        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();
759 760 761 762 763 764
                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);
765 766
            }
            break;
767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790
       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];

791
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
792 793 794 795 796
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

797
#endif
pixhawk's avatar
pixhawk committed
798
        default:
lm's avatar
lm committed
799 800 801 802
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
803 804
                    //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
805 806 807
                    //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
808 809 810 811 812
            break;
        }
    }
}

813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842
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
843 844
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
845
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
846
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
847 848
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
849
#else
lm's avatar
lm committed
850 851 852 853
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
854
#endif
pixhawk's avatar
pixhawk committed
855 856
}

pixhawk's avatar
pixhawk committed
857 858
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
859
#ifdef MAVLINK_ENABLED_PIXHAWK
860 861 862
    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
863
#else
864 865 866 867
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
868 869 870 871 872
#endif
}

void UAS::startRadioControlCalibration()
{
873 874 875
    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
876 877
}

lm's avatar
lm committed
878 879
void UAS::startDataRecording()
{
880 881 882
    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
883 884 885 886
}

void UAS::pauseDataRecording()
{
887 888 889
    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
890 891 892 893
}

void UAS::stopDataRecording()
{
894 895 896
    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
897 898
}

pixhawk's avatar
pixhawk committed
899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919
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);
}

920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941
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
942
#ifndef _MSC_VER
943
    else if (time < 1261440000000000LLU)
944
#else
945
        else if (time < 1261440000000000)
946
#endif
947
        {
948 949
        if (onboardTimeOffset == 0)
        {
950
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
951
        }
952
        return time/1000 + onboardTimeOffset;
953 954 955 956 957
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
958
        return time/1000;
959 960 961
    }
}

962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978
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
979
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
980
{
lm's avatar
lm committed
981
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
982
    {
983
        this->mode = mode;
pixhawk's avatar
pixhawk committed
984
        mavlink_message_t msg;
lm's avatar
lm committed
985
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
986
        sendMessage(msg);
lm's avatar
lm committed
987
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
988
    }
pixhawk's avatar
pixhawk committed
989 990 991 992 993 994 995 996 997 998 999 1000
}

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

1001 1002 1003 1004
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1005

1006 1007
    foreach(LinkInterface* link, link_list)
    {
1008
        if (link)
1009
        {
1010 1011
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1012
            {
1013 1014

                for(int i=0;i<links->size();i++)
1015
                {
1016 1017 1018 1019 1020
                    if(serial != links->at(i))
                    {
                        qDebug()<<"Forwarding Over link: "<<serial->getName()<<" "<<serial;
                        sendMessage(serial, message);
                    }
1021 1022 1023 1024 1025 1026
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1027 1028
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1029
    if(!link) return;
pixhawk's avatar
pixhawk committed
1030 1031 1032
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1033
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1034
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
    // 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
 */
1046
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1047
{
1048
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1049 1050 1051 1052 1053 1054
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1055
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1056
        uasState = tr("UNINIT");
1057
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
1058
        break;
lm's avatar
lm committed
1059
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1060
        uasState = tr("BOOT");
1061
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
1062
        break;
lm's avatar
lm committed
1063
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1064
        uasState = tr("CALIBRATING");
1065
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
1066
        break;
lm's avatar
lm committed
1067
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1068
        uasState = tr("ACTIVE");
1069
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
1070
        break;
lm's avatar
lm committed
1071 1072
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1073
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
1074 1075
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1076
        uasState = tr("CRITICAL");
1077
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
1078
        break;
lm's avatar
lm committed
1079
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1080
        uasState = tr("EMERGENCY");
1081
        stateDescription = tr("EMERGENCY: Land!");
pixhawk's avatar
pixhawk committed
1082
        break;
lm's avatar
lm committed
1083
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1084
        uasState = tr("SHUTDOWN");
1085
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
1086
        break;
lm's avatar
lm committed
1087
    default:
pixhawk's avatar
pixhawk committed
1088
        uasState = tr("UNKNOWN");
1089
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1103
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1104 1105 1106 1107 1108 1109 1110 1111
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1112
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1113 1114 1115 1116
{
    return commStatus;
}

1117 1118 1119
void UAS::requestParameters()
{
    mavlink_message_t msg;
1120
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1121 1122
    // Send message twice to increase chance of reception
    sendMessage(msg);
1123 1124
}

1125
void UAS::writeParametersToStorage()
1126
{
1127 1128 1129
    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
1130
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1131 1132 1133 1134 1135 1136 1137 1138 1139
    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
1140 1141
}

1142
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1143 1144
{
    // Buffers to write data to
1145
    mavlink_message_t msg;
1146
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1147 1148
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1149
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1150 1151
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1152 1153
    // 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
1154 1155
    stream.req_message_rate = 0;
    // Start / stop the message
1156
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1157 1158 1159 1160 1161
    // 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
1162
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1163 1164
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1165 1166 1167
    sendMessage(msg);
}

1168
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1169 1170 1171
{
    // Buffers to write data to
    mavlink_message_t msg;
1172
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1173
    // Select the message to request from now on
1174
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1175
    // Select the update rate in Hz the message should be send
1176
    stream.req_message_rate = rate;
lm's avatar
lm committed
1177
    // Start / stop the message
1178
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1179 1180 1181 1182 1183
    // 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
1184
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1185 1186
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1187 1188 1189
    sendMessage(msg);
}

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

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

1239
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1240
{
1241 1242 1243 1244
    // Buffers to write data to
    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_RAW_CONTROLLER;
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);
lm's avatar
lm committed
1259 1260
}

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

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

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

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

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

lm's avatar
lm committed
1371 1372 1373 1374 1375 1376 1377
/**
 * 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
1378 1379 1380 1381
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1382 1383 1384
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1385 1386
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1387

1388
    // Copy string into buffer, ensuring not to exceed the buffer size    
1389
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1390
    {
lm's avatar
lm committed
1391
        // String characters
1392
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1393
        {
1394
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1395 1396
        }
        // Null termination at end of string or end of buffer
1397
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1398 1399 1400 1401 1402 1403 1404 1405
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1406
    }    
1407
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1408
    sendMessage(msg);
lm's avatar
lm committed
1409
    }
1410 1411
}

1412 1413 1414
void UAS::setUASName(const QString& name)
{
    this->name = name;
1415
    writeSettings();
1416
    emit nameChanged(name);
1417
    emit systemSpecsChanged(uasId);
1418 1419
}

1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432
/**
 * 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
1433
/**
lm's avatar
lm committed
1434
 * Launches the system
pixhawk's avatar
pixhawk committed
1435 1436 1437 1438
 *
 **/
void UAS::launch()
{
1439
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1440
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1441
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1442 1443 1444
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1445 1446 1447 1448 1449 1450 1451 1452
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1453
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1454
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1455
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1456 1457 1458
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1459 1460 1461 1462 1463 1464 1465 1466
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1467
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1468
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1469
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1470 1471 1472
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486
}

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;

1487 1488 1489 1490 1491 1492
    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
1493

1494 1495 1496 1497 1498 1499
        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
1500 1501
}

1502 1503 1504 1505 1506
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1507 1508 1509 1510 1511
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1512

pixhawk's avatar
pixhawk committed
1513 1514
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1515

pixhawk's avatar
pixhawk committed
1516 1517 1518 1519 1520
        break;
    default:

        break;
    }
1521
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1522 1523 1524

}

1525

1526
/*void UAS::requestWaypoints()
1527 1528 1529 1530 1531
{
//    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
1532 1533
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1534 1535
}

pixhawk's avatar
pixhawk committed
1536 1537
void UAS::setWaypoint(Waypoint* wp)
{
1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555
//    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
1556 1557 1558 1559
}

void UAS::setWaypointActive(int id)
{
1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582
//    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!";
1583
}*/
pixhawk's avatar
pixhawk committed
1584 1585 1586 1587


void UAS::halt()
{
1588
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1589
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1590
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1591 1592 1593
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1594 1595 1596 1597
}

void UAS::go()
{
1598
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1599
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1600
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1601 1602 1603
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1604 1605 1606 1607 1608
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1609
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1610
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1611
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1612 1613 1614
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1615 1616 1617 1618 1619 1620 1621 1622
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1623
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1624
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1625
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1626 1627 1628
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653
}

/**
 * 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)
    {
1654
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1655
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1656
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1657 1658 1659
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682
        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
1683
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1684
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1685
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1686 1687 1688
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1689 1690 1691 1692
        result = true;
    }
}

1693 1694
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1695 1696 1697 1698 1699 1700
    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);
1701 1702
}

pixhawk's avatar
pixhawk committed
1703 1704 1705
/**
 * @return The name of this system as string in human-readable form
 */
1706
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724
{
    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);
1725
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1726 1727
    }
    //links->append(link);
1728
    //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
1729 1730
}

1731 1732 1733 1734 1735 1736 1737 1738 1739
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756
/**
 * @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
1757
    case NICD:
pixhawk's avatar
pixhawk committed
1758
        break;
lm's avatar
lm committed
1759
    case NIMH:
pixhawk's avatar
pixhawk committed
1760
        break;
lm's avatar
lm committed
1761
    case LIION:
pixhawk's avatar
pixhawk committed
1762
        break;
lm's avatar
lm committed
1763
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1764 1765 1766
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1767
    case LIFE:
pixhawk's avatar
pixhawk committed
1768
        break;
lm's avatar
lm committed
1769
    case AGZN:
pixhawk's avatar
pixhawk committed
1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786
        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
1787 1788 1789
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1790 1791
double UAS::getChargeLevel()
{
1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805
    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
1806 1807
}

lm's avatar
lm committed
1808 1809 1810 1811
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1812 1813
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825
        lowBattAlarm = true;
    }
}

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