UAS.cc 63.2 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);
                }
pixhawk's avatar
pixhawk committed
274 275 276
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
277
            {
pixhawk's avatar
pixhawk committed
278 279
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
280
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
281

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

                // Emit in angles
314 315
                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
316

317 318
                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
319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335

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

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

360 361
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
362

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

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

417 418
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
419

lm's avatar
lm committed
420
                if (pos.fix_type > 0)
421
                {
Laurens Mackay's avatar
Laurens Mackay committed
422
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
423 424 425 426 427 428 429 430

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

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

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

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

596
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
597
            {
pixhawk's avatar
pixhawk committed
598 599 600
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
601
            }
pixhawk's avatar
pixhawk committed
602
            break;
pixhawk's avatar
pixhawk committed
603

604
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
605
            {
606 607 608
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
609
            }
pixhawk's avatar
pixhawk committed
610
            break;
pixhawk's avatar
pixhawk committed
611

612 613 614 615 616 617 618
        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
619

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

698
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
699 700 701 702 703
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

704
#endif
pixhawk's avatar
pixhawk committed
705
        default:
lm's avatar
lm committed
706 707 708 709
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
710 711
                    //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
712 713 714
                    //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
715 716 717 718 719
            break;
        }
    }
}

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

pixhawk's avatar
pixhawk committed
764 765
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
766
#ifdef MAVLINK_ENABLED_PIXHAWK
767 768 769
    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
770
#else
771 772 773 774
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
775 776 777 778 779
#endif
}

void UAS::startRadioControlCalibration()
{
780 781 782
    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
783 784
}

lm's avatar
lm committed
785 786
void UAS::startDataRecording()
{
787 788 789
    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
790 791 792 793
}

void UAS::pauseDataRecording()
{
794 795 796
    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
797 798 799 800
}

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

pixhawk's avatar
pixhawk committed
806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826
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);
}

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

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

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

907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928
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
929 930
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
931
    if(!link) return;
pixhawk's avatar
pixhawk committed
932 933 934
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
935
    int len = mavlink_msg_to_send_buffer(buffer, &message);
936
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
937 938 939 940 941 942 943 944 945 946 947
    // 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
 */
948
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
949
{
950
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
951 952 953 954 955 956
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
957
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
958 959 960
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
961
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
962 963 964
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
965
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
966 967 968
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
969
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
970 971 972
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
973 974 975 976 977
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
978 979 980
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
981
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
982 983 984
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
985
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
986 987 988
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
989
    default:
pixhawk's avatar
pixhawk committed
990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1005
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1006 1007 1008 1009 1010 1011 1012 1013
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1014
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1015 1016 1017 1018
{
    return commStatus;
}

1019 1020 1021
void UAS::requestParameters()
{
    mavlink_message_t msg;
1022
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1023 1024
    // Send message twice to increase chance of reception
    sendMessage(msg);
1025 1026
}

1027
void UAS::writeParametersToStorage()
1028
{
1029 1030 1031
    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
1032
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1033 1034 1035 1036 1037 1038 1039 1040 1041
    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
1042 1043
}

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

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

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

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

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

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

1185
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1186 1187 1188 1189 1190
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1191
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1192
    // Select the update rate in Hz the message should be send
1193
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1194
    // Start / stop the message
1195
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1196 1197 1198 1199 1200 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);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

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

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

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

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

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

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

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

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

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;

1381 1382 1383 1384 1385 1386
    //    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
1387

1388 1389
    emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    //    }
pixhawk's avatar
pixhawk committed
1390 1391
}

1392 1393 1394 1395 1396
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1397 1398 1399 1400 1401
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1402

pixhawk's avatar
pixhawk committed
1403 1404
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1405

pixhawk's avatar
pixhawk committed
1406 1407 1408 1409 1410
        break;
    default:

        break;
    }
1411
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1412 1413 1414

}

1415

1416
/*void UAS::requestWaypoints()
1417 1418 1419 1420 1421
{
//    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
1422 1423
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1424 1425
}

pixhawk's avatar
pixhawk committed
1426 1427
void UAS::setWaypoint(Waypoint* wp)
{
1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445
//    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
1446 1447 1448 1449
}

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


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

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

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

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

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

1583 1584
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1585 1586 1587 1588 1589 1590
    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);
1591 1592
}

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

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

lm's avatar
lm committed
1688 1689 1690 1691
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1692 1693
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705
        lowBattAlarm = true;
    }
}

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