UAS.cc 63.3 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21
======================================================================*/

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

#include <QList>
#include <QMessageBox>
#include <QTimer>
#include <iostream>
#include <QDebug>
#include <cmath>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "MG.h"
22
#include "QGC.h"
pixhawk's avatar
pixhawk committed
23
#include "GAudioOutput.h"
24
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
25
#include "QGCMAVLink.h"
26 27
#include "LinkManager.h"
#include "SerialLink.h"
pixhawk's avatar
pixhawk committed
28

pixhawk's avatar
pixhawk committed
29 30 31 32 33 34 35 36 37 38 39 40 41
#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


42

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

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

97
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
98 99 100 101
{
    return uasId;
}

102 103 104 105 106 107 108 109 110 111
void UAS::updateState()
{
    // 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
112
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
113 114 115 116 117 118
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
119 120 121 122 123 124 125
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
126
    if (!link) return;
pixhawk's avatar
pixhawk committed
127 128 129
    if (!links->contains(link))
    {
        addLink(link);
130
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
131
    }
132 133 134 135
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
136

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

pixhawk's avatar
pixhawk committed
139 140 141 142 143 144 145 146 147 148
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
        QString patternPath;
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
149
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
150
            {
pixhawk's avatar
pixhawk committed
151
                this->type = mavlink_msg_heartbeat_get_type(&message);
152
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
153 154
                emit systemTypeSet(this, type);
            }
155

pixhawk's avatar
pixhawk committed
156 157 158 159 160 161
            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
162 163
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
164 165
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
166

pixhawk's avatar
pixhawk committed
167
                // FIXME
168
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
169

pixhawk's avatar
pixhawk committed
170 171 172 173 174
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
175

pixhawk's avatar
pixhawk committed
176
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
177
                {
pixhawk's avatar
pixhawk committed
178
                    statechanged = true;
lm's avatar
lm committed
179
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
180 181
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
182
                    emit statusChanged(this->status);
183
                    emit loadChanged(this,state.load/10.0f);
184
                    emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
185
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
186 187
                }

lm's avatar
lm committed
188
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
189 190
                {
                    modechanged = true;
lm's avatar
lm committed
191
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
192 193
                    QString mode;

lm's avatar
lm committed
194
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
195
                    {
lm's avatar
lm committed
196
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
197 198
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
199
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
200 201
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
202
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
203 204
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
205
                    case (uint8_t)MAV_MODE_GUIDED:
206 207
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
208
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
209 210
                        mode = "READY";
                        break;
lm's avatar
lm committed
211
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
212 213
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
214
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
215 216
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
217
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
218 219
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
220 221 222
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
223 224 225 226 227 228 229 230
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
231
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
232
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
233 234 235
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
236
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
237
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
238

lm's avatar
lm committed
239 240
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
241
                if (chargeLevel <= 20.0f)
lm's avatar
lm committed
242 243 244 245 246 247 248 249
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
250
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
251
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
252
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
253 254

                // AUDIO
pixhawk's avatar
pixhawk committed
255 256 257 258 259 260 261 262 263 264
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
265
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
266 267 268 269 270 271 272 273
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
274 275 276 277 278 279

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
280 281 282
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
283
            {
pixhawk's avatar
pixhawk committed
284 285
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
286
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
287

288 289 290 291 292 293 294 295 296
                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
297 298 299 300
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
301
            //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
302
            {
pixhawk's avatar
pixhawk committed
303 304
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
305
                quint64 time = getUnixTime(attitude.usec);
lm's avatar
lm committed
306 307 308
                roll = attitude.roll;
                pitch = attitude.pitch;
                yaw = attitude.yaw;
309 310 311
//                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);
312 313 314 315 316 317
                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);
318 319

                // Emit in angles
320 321
                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
322

323 324
                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
325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341

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

344
                emit attitudeChanged(this, attitude.roll, attitude.pitch, attitude.yaw, time);
pixhawk's avatar
pixhawk committed
345 346
            }
            break;
347
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
348
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
349
            //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
350
            {
351 352
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
353
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
354 355 356
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
357 358 359 360 361 362
                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
363
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
364
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
365

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

369
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
370 371 372 373 374 375 376
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
377 378
            }
            break;
379
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
380 381 382
            //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;
            {
383 384
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
385
                quint64 time = QGC::groundTimeUsecs()/1000;
386 387 388 389 390 391
                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;
392 393 394 395 396 397
                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);
398 399
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
pixhawk's avatar
pixhawk committed
400 401 402 403 404 405 406
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
407 408
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
409 410 411 412 413 414 415 416
            }
            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);
417 418 419

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

423 424
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
425

lm's avatar
lm committed
426
                if (pos.fix_type > 0)
427
                {
Laurens Mackay's avatar
Laurens Mackay committed
428
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
429 430 431 432 433 434 435 436

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
437
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
438 439 440
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
441
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
442
                        //qDebug() << "GOT GPS RAW";
443
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
444 445 446 447 448
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
449
                }
450 451
            }
            break;
lm's avatar
lm committed
452 453 454 455
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
456
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
457
                {
lm's avatar
lm committed
458
                    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
459 460 461
                }
            }
            break;
462 463 464 465 466 467 468
        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;
469 470 471 472
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
473 474 475 476
                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);
477 478
            }
            break;
479
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
480
            {
481 482
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
483
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506
                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
507 508
            }
            break;
509 510 511 512
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529

                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);
530 531
            }
            break;
pixhawk's avatar
pixhawk committed
532
        case MAVLINK_MSG_ID_DEBUG:
533
            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
534
            break;
535 536 537 538 539
        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
540
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
541 542 543
                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);
544 545 546 547 548 549
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
550
                quint64 time = MG::TIME::getGroundTimeNow();
551
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
552 553 554
                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);
555 556
            }
            break;
pixhawk's avatar
pixhawk committed
557 558 559 560
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
561 562 563 564
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
565 566 567
            }
            break;

568
        case MAVLINK_MSG_ID_WAYPOINT:
569
            {
570 571
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
572
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
573 574 575 576
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
577
            }
pixhawk's avatar
pixhawk committed
578
            break;
pixhawk's avatar
pixhawk committed
579

580 581 582 583 584 585 586 587 588 589 590
        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
591 592 593 594
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
595 596 597 598
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
599 600 601
            }
            break;

602
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
603
            {
pixhawk's avatar
pixhawk committed
604 605 606
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
607
            }
pixhawk's avatar
pixhawk committed
608
            break;
pixhawk's avatar
pixhawk committed
609

610
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
611
            {
612 613 614
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
615
            }
pixhawk's avatar
pixhawk committed
616
            break;
pixhawk's avatar
pixhawk committed
617

618 619 620 621 622 623 624
        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
625

626
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
627 628 629
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
630
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
631 632
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
633
                int severity = mavlink_msg_statustext_get_severity(&message);
634
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
635
                //emit statusTextReceived(severity, text);
636
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
637 638
            }
            break;
639 640 641 642 643 644
    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);
645 646 647
                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);
648 649
            }
            break;
650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665
            //#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
666
#ifdef MAVLINK_ENABLED_UALBERTA
667 668 669 670 671
        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();
672 673 674 675 676 677
                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);
678 679
            }
            break;
680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703
       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];

704
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
705 706 707 708 709
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

710
#endif
pixhawk's avatar
pixhawk committed
711
        default:
lm's avatar
lm committed
712 713 714 715
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
716 717
                    //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
718 719 720
                    //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
721 722 723 724 725
            break;
        }
    }
}

726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755
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
756 757
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
758
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
759
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
760 761
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
762
#else
lm's avatar
lm committed
763 764 765 766
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
767
#endif
pixhawk's avatar
pixhawk committed
768 769
}

pixhawk's avatar
pixhawk committed
770 771
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
772
#ifdef MAVLINK_ENABLED_PIXHAWK
773 774 775
    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
776
#else
777 778 779 780
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
781 782 783 784 785
#endif
}

void UAS::startRadioControlCalibration()
{
786 787 788
    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
789 790
}

lm's avatar
lm committed
791 792
void UAS::startDataRecording()
{
793 794 795
    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
796 797 798 799
}

void UAS::pauseDataRecording()
{
800 801 802
    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
803 804 805 806
}

void UAS::stopDataRecording()
{
807 808 809
    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
810 811
}

pixhawk's avatar
pixhawk committed
812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832
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);
}

833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854
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
855
#ifndef _MSC_VER
856
    else if (time < 1261440000000000LLU)
857
#else
858
        else if (time < 1261440000000000)
859
#endif
860
        {
861 862
        if (onboardTimeOffset == 0)
        {
863
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
864
        }
865
        return time/1000 + onboardTimeOffset;
866 867 868 869 870
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
871
        return time/1000;
872 873 874
    }
}

875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891
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
892
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
893
{
lm's avatar
lm committed
894
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
895 896
    {
        mavlink_message_t msg;
lm's avatar
lm committed
897
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
898
        sendMessage(msg);
lm's avatar
lm committed
899
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
900
    }
pixhawk's avatar
pixhawk committed
901 902 903 904 905 906 907 908 909 910 911 912
}

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

913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
    foreach(LinkInterface* link, link_list)
    {
        SerialLink* serial = dynamic_cast<SerialLink*>(link);
        if(serial != 0)
        {

            for(int i=0;i<links->size();i++)
            {
                if(serial != links->at(i))
                {
                    qDebug()<<"Forwarding Over link: "<<serial->getName()<<" "<<serial;
                    sendMessage(serial, message);
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
935 936
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
937
    if(!link) return;
pixhawk's avatar
pixhawk committed
938 939 940
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
941
    int len = mavlink_msg_to_send_buffer(buffer, &message);
942
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
943 944 945 946 947 948 949 950 951 952 953
    // 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
 */
954
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
955
{
956
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
957 958 959 960 961 962
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
963
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
964
        uasState = tr("UNINIT");
965
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
966
        break;
lm's avatar
lm committed
967
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
968
        uasState = tr("BOOT");
969
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
970
        break;
lm's avatar
lm committed
971
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
972
        uasState = tr("CALIBRATING");
973
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
974
        break;
lm's avatar
lm committed
975
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
976
        uasState = tr("ACTIVE");
977
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
978
        break;
lm's avatar
lm committed
979 980
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
981
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
982 983
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
984
        uasState = tr("CRITICAL");
985
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
986
        break;
lm's avatar
lm committed
987
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
988 989 990
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
991
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
992
        uasState = tr("SHUTDOWN");
993
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
994
        break;
lm's avatar
lm committed
995
    default:
pixhawk's avatar
pixhawk committed
996
        uasState = tr("UNKNOWN");
997
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1011
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1012 1013 1014 1015 1016 1017 1018 1019
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1020
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1021 1022 1023 1024
{
    return commStatus;
}

1025 1026 1027
void UAS::requestParameters()
{
    mavlink_message_t msg;
1028
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1029 1030
    // Send message twice to increase chance of reception
    sendMessage(msg);
1031 1032
}

1033
void UAS::writeParametersToStorage()
1034
{
1035 1036 1037
    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
1038
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1039 1040 1041 1042 1043 1044 1045 1046 1047
    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
1048 1049
}

1050
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1051 1052
{
    // Buffers to write data to
1053
    mavlink_message_t msg;
1054
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1055 1056
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1057
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1058 1059
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1060 1061
    // 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
1062 1063
    stream.req_message_rate = 0;
    // Start / stop the message
1064
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1065 1066 1067 1068 1069
    // 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
1070
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1071 1072
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1073 1074 1075
    sendMessage(msg);
}

1076
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1077 1078 1079
{
    // Buffers to write data to
    mavlink_message_t msg;
1080
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1081
    // Select the message to request from now on
1082
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1083
    // Select the update rate in Hz the message should be send
1084
    stream.req_message_rate = rate;
lm's avatar
lm committed
1085
    // Start / stop the message
1086
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1087 1088 1089 1090 1091
    // 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
1092
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1093 1094
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1095 1096 1097
    sendMessage(msg);
}

1098
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1099
{
1100 1101 1102 1103
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1104
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1105
    // Select the update rate in Hz the message should be send
1106
    stream.req_message_rate = rate;
1107
    // Start / stop the message
1108
    stream.start_stop = (rate) ? 1 : 0;
1109 1110 1111 1112 1113 1114
    // 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);
1115 1116
    // Send message twice to increase chance of reception
    sendMessage(msg);
1117
    sendMessage(msg);
lm's avatar
lm committed
1118
}
1119

1120
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1121
{
1122 1123 1124 1125 1126
#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
1127 1128 1129
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1130
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1131
    // Select the update rate in Hz the message should be send
1132
    stream.req_message_rate = rate;
1133
    // Start / stop the message
1134
    stream.start_stop = (rate) ? 1 : 0;
1135 1136 1137 1138 1139 1140
    // 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);
1141 1142
    // Send message twice to increase chance of reception
    sendMessage(msg);
1143
    sendMessage(msg);
1144
#endif
lm's avatar
lm committed
1145 1146
}

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

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

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

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

1235
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1236 1237 1238 1239 1240
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1241
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1242
    // Select the update rate in Hz the message should be send
1243
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1244
    // Start / stop the message
1245
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256
    // 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);
}

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

lm's avatar
lm committed
1279 1280 1281 1282 1283 1284 1285
/**
 * 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
1286 1287 1288 1289
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1290 1291 1292
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1293 1294
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1295

1296
    // Copy string into buffer, ensuring not to exceed the buffer size    
1297
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1298
    {
lm's avatar
lm committed
1299
        // String characters
1300
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1301
        {
1302
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1303 1304
        }
        // Null termination at end of string or end of buffer
1305
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1306 1307 1308 1309 1310 1311 1312 1313
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1314
    }    
1315
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1316
    sendMessage(msg);
lm's avatar
lm committed
1317
    }
1318 1319
}

1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332
/**
 * 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
1333
/**
lm's avatar
lm committed
1334
 * Launches the system
pixhawk's avatar
pixhawk committed
1335 1336 1337 1338
 *
 **/
void UAS::launch()
{
1339
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1340
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1341
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1342 1343 1344
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1345 1346 1347 1348 1349 1350 1351 1352
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1353
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1354
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1355
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1356 1357 1358
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1359 1360 1361 1362 1363 1364 1365 1366
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1367
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1368
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1369
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1370 1371 1372
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386
}

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;

1387 1388 1389 1390 1391 1392
    //    if(mode == (int)MAV_MODE_MANUAL)
    //    {
    mavlink_message_t message;
    mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &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
1393

1394 1395
    emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    //    }
pixhawk's avatar
pixhawk committed
1396 1397
}

1398 1399 1400 1401 1402
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1403 1404 1405 1406 1407
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1408

pixhawk's avatar
pixhawk committed
1409 1410
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1411

pixhawk's avatar
pixhawk committed
1412 1413 1414 1415 1416
        break;
    default:

        break;
    }
1417
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1418 1419 1420

}

1421

1422
/*void UAS::requestWaypoints()
1423 1424 1425 1426 1427
{
//    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
1428 1429
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1430 1431
}

pixhawk's avatar
pixhawk committed
1432 1433
void UAS::setWaypoint(Waypoint* wp)
{
1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451
//    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
1452 1453 1454 1455
}

void UAS::setWaypointActive(int id)
{
1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478
//    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!";
1479
}*/
pixhawk's avatar
pixhawk committed
1480 1481 1482 1483


void UAS::halt()
{
1484
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1485
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1486
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1487 1488 1489
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1490 1491 1492 1493
}

void UAS::go()
{
1494
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1495
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1496
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1497 1498 1499
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1500 1501 1502 1503 1504
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1505
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1506
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1507
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1508 1509 1510
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1511 1512 1513 1514 1515 1516 1517 1518
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1519
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1520
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1521
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1522 1523 1524
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549
}

/**
 * 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)
    {
1550
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1551
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1552
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1553 1554 1555
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578
        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
1579
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1580
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1581
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1582 1583 1584
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1585 1586 1587 1588
        result = true;
    }
}

1589 1590
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1591 1592 1593 1594 1595 1596
    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);
1597 1598
}

pixhawk's avatar
pixhawk committed
1599 1600 1601
/**
 * @return The name of this system as string in human-readable form
 */
1602
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622
{
    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);
    }
    //links->append(link);
1623
    //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
1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642
}

/**
 * @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
1643
    case NICD:
pixhawk's avatar
pixhawk committed
1644
        break;
lm's avatar
lm committed
1645
    case NIMH:
pixhawk's avatar
pixhawk committed
1646
        break;
lm's avatar
lm committed
1647
    case LIION:
pixhawk's avatar
pixhawk committed
1648
        break;
lm's avatar
lm committed
1649
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1650 1651 1652
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1653
    case LIFE:
pixhawk's avatar
pixhawk committed
1654
        break;
lm's avatar
lm committed
1655
    case AGZN:
pixhawk's avatar
pixhawk committed
1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672
        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
1673 1674 1675
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1676 1677
double UAS::getChargeLevel()
{
1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691
    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
1692 1693
}

lm's avatar
lm committed
1694 1695 1696 1697
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1698 1699
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711
        lowBattAlarm = true;
    }
}

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