UAS.cc 59.7 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

lm's avatar
lm committed
3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

lm's avatar
lm committed
5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

lm's avatar
lm committed
7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

lm's avatar
lm committed
9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

lm's avatar
lm committed
14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
lm's avatar
lm committed
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41

======================================================================*/

/**
 * @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"
42
#include "QGC.h"
pixhawk's avatar
pixhawk committed
43
#include "GAudioOutput.h"
44
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
45
#include "QGCMAVLink.h"
pixhawk's avatar
pixhawk committed
46

47
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
48
        uasId(id),
pixhawk's avatar
pixhawk committed
49 50 51
        startTime(MG::TIME::getGroundTimeNow()),
        commStatus(COMM_DISCONNECTED),
        name(""),
52
        autopilot(0),
pixhawk's avatar
pixhawk committed
53
        links(new QList<LinkInterface*>()),
54
        unknownPackets(),
55
        mavlink(protocol),
56
        waypointManager(*this),
pixhawk's avatar
pixhawk committed
57
        thrustSum(0),
pixhawk's avatar
pixhawk committed
58
        thrustMax(10),
pixhawk's avatar
pixhawk committed
59
        startVoltage(0),
60 61
        currentVoltage(12.0f),
        lpVoltage(12.0f),
pixhawk's avatar
pixhawk committed
62 63 64
        mode(MAV_MODE_UNINIT),
        status(MAV_STATE_UNINIT),
        onboardTimeOffset(0),
pixhawk's avatar
pixhawk committed
65 66 67 68
        controlRollManual(true),
        controlPitchManual(true),
        controlYawManual(true),
        controlThrustManual(true),
pixhawk's avatar
pixhawk committed
69 70 71
        manualRollAngle(0),
        manualPitchAngle(0),
        manualYawAngle(0),
lm's avatar
lm committed
72 73
        manualThrust(0),
        receiveDropRate(0),
lm's avatar
lm committed
74
        sendDropRate(0),
75 76
        lowBattAlarm(false),
        positionLock(false),
77 78 79 80 81 82 83 84 85
        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),
86
        statusTimeout(new QTimer(this))
pixhawk's avatar
pixhawk committed
87
{
88
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
89
    setBattery(LIPOLY, 3);
90 91
    statusTimeout->setInterval(500);
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
pixhawk's avatar
pixhawk committed
92 93 94 95 96 97 98
}

UAS::~UAS()
{
    delete links;
}

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

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

pixhawk's avatar
pixhawk committed
121 122 123 124 125 126 127 128 129 130
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

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

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

pixhawk's avatar
pixhawk committed
140 141 142 143 144 145 146 147 148 149
    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
150
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
151
            {
pixhawk's avatar
pixhawk committed
152
                this->type = mavlink_msg_heartbeat_get_type(&message);
153
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
154 155 156 157 158 159 160 161
                emit systemTypeSet(this, type);
            }
            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 184
                    emit loadChanged(this,state.load/10.0f);
                    emit UAS::valueChanged(this, "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

pixhawk's avatar
pixhawk committed
282 283 284 285 286 287 288 289 290
                emit valueChanged(uasId, "Accel. X", raw.xacc, time);
                emit valueChanged(uasId, "Accel. Y", raw.yacc, time);
                emit valueChanged(uasId, "Accel. Z", raw.zacc, time);
                emit valueChanged(uasId, "Gyro Phi", raw.xgyro, time);
                emit valueChanged(uasId, "Gyro Theta", raw.ygyro, time);
                emit valueChanged(uasId, "Gyro Psi", raw.zgyro, time);
                emit valueChanged(uasId, "Mag. X", raw.xmag, time);
                emit valueChanged(uasId, "Mag. Y", raw.ymag, time);
                emit valueChanged(uasId, "Mag. Z", 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;
pixhawk's avatar
pixhawk committed
303 304 305 306 307 308
                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);
                emit valueChanged(this, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
                emit valueChanged(this, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
                emit valueChanged(this, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
lm's avatar
lm committed
309 310 311
                emit valueChanged(uasId, "rollspeed IMU", attitude.rollspeed, time);
                emit valueChanged(uasId, "pitchspeed IMU", attitude.pitchspeed, time);
                emit valueChanged(uasId, "yawspeed IMU", attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
312
                emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time);
pixhawk's avatar
pixhawk committed
313 314
            }
            break;
315
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
316
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
317
            //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
318
            {
319 320
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
321
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
322 323 324
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
lm's avatar
lm committed
325 326 327
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
328 329 330
                emit valueChanged(uasId, "Vx", pos.vx, time);
                emit valueChanged(uasId, "Vy", pos.vy, time);
                emit valueChanged(uasId, "Vz", pos.vz, time);
lm's avatar
lm committed
331
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
332 333
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
334 335 336 337 338 339 340
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
341 342
            }
            break;
343 344 345 346 347 348 349
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            //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_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
350 351 352
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
353 354 355 356 357 358 359
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
                emit valueChanged(uasId, "alt", pos.alt, time);
                emit valueChanged(uasId, "g-vx", pos.vx, time);
                emit valueChanged(uasId, "g-vy", pos.vy, time);
                emit valueChanged(uasId, "g-vz", pos.vz, time);
                emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
pixhawk's avatar
pixhawk committed
360 361 362 363 364 365 366 367
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
368 369 370 371 372

                // Send to patch antenna
                mavlink_message_t msg;
                mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
                sendMessage(msg);
373 374 375 376 377 378 379 380
            }
            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);
381 382 383

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

387 388
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
lm's avatar
lm committed
389

lm's avatar
lm committed
390
                if (pos.fix_type > 0)
391
                {
Laurens Mackay's avatar
Laurens Mackay committed
392
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "alt", pos.alt, time);
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
                        emit valueChanged(uasId, "speed", pos.v, time);
                        //qDebug() << "GOT GPS RAW";
                        emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
413
                }
414 415
            }
            break;
lm's avatar
lm committed
416 417 418 419
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
420
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
421
                {
lm's avatar
lm committed
422
                    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
423 424 425
                }
            }
            break;
426 427 428 429 430 431 432
        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;
433
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
434
            {
435 436
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
437
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460
                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
461 462
            }
            break;
463 464 465 466 467 468 469
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
                emit parameterChanged(uasId, message.compid, QString((char*)value.param_id), value.param_value);
            }
            break;
pixhawk's avatar
pixhawk committed
470
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
471
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
472
            break;
473 474 475 476 477
        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
478
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
479 480 481 482 483 484 485 486 487
                emit valueChanged(uasId, "att control roll", out.roll, time/1000.0f);
                emit valueChanged(uasId, "att control pitch", out.pitch, time/1000.0f);
                emit valueChanged(uasId, "att control yaw", out.yaw, time/1000.0f);
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
488
                quint64 time = MG::TIME::getGroundTimeNow();
489
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
490 491 492
                emit valueChanged(uasId, "pos control x", out.x, time);
                emit valueChanged(uasId, "pos control y", out.y, time);
                emit valueChanged(uasId, "pos control z", out.z, time);
493 494
            }
            break;
pixhawk's avatar
pixhawk committed
495 496 497 498
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
499 500 501 502
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
503 504 505
            }
            break;

506
        case MAVLINK_MSG_ID_WAYPOINT:
507
            {
508 509
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
510
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
511 512 513 514
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
515
            }
pixhawk's avatar
pixhawk committed
516
            break;
pixhawk's avatar
pixhawk committed
517

518 519 520 521 522 523 524 525 526 527 528
        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
529 530 531 532
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
533 534 535 536
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
537 538 539
            }
            break;

540
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
541
            {
pixhawk's avatar
pixhawk committed
542 543 544
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
545
            }
pixhawk's avatar
pixhawk committed
546
            break;
pixhawk's avatar
pixhawk committed
547

548
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
549
            {
550 551 552
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
553
            }
pixhawk's avatar
pixhawk committed
554
            break;
pixhawk's avatar
pixhawk committed
555

556 557 558 559 560 561 562
        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
563

564
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
565 566 567
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
568
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
569 570
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
571
                int severity = mavlink_msg_statustext_get_severity(&message);
572
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
573
                //emit statusTextReceived(severity, text);
574
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
575 576
            }
            break;
577 578 579 580 581 582 583 584 585 586 587
    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);
                emit valueChanged(uasId, str+".x", vect.x, time);
                emit valueChanged(uasId, str+".y", vect.y, time);
                emit valueChanged(uasId, str+".z", vect.z, time);
            }
            break;
588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
//#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
604
#ifdef MAVLINK_ENABLED_UALBERTA
605 606 607 608 609 610 611 612 613 614 615 616 617
        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();
                emit valueChanged(uasId, "b_f[0]", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", bias.gyro_2, time);
            }
            break;
618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641
       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];

642
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
643 644 645 646 647
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

648
#endif
pixhawk's avatar
pixhawk committed
649
        default:
lm's avatar
lm committed
650 651 652 653
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
654 655
                    //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
656 657 658
                    //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
659 660 661 662 663
            break;
        }
    }
}

664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693
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
694 695
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
696
    #ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
697
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
698 699
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
lm's avatar
lm committed
700 701 702 703 704 705
    #else
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
    #endif
pixhawk's avatar
pixhawk committed
706 707
}

pixhawk's avatar
pixhawk committed
708 709
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
710
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
711 712 713
  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
714 715 716 717 718
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
719 720 721 722 723 724 725 726 727 728
#endif
}

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

lm's avatar
lm committed
729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749
void UAS::startDataRecording()
{
  mavlink_message_t msg;
  mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
  sendMessage(msg);
}

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

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

pixhawk's avatar
pixhawk committed
750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770
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);
}

771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792
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
793
#ifndef _MSVC_VER
794
    else if (time < 1261440000000000LLU)
795
#else
796
    else if (time < 1261440000000000)
797
#endif
798 799 800
    {
        if (onboardTimeOffset == 0)
        {
801
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
802
        }
803
        return time/1000 + onboardTimeOffset;
804 805 806 807 808
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
809
        return time/1000;
810 811 812
    }
}

pixhawk's avatar
pixhawk committed
813
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
814
{
lm's avatar
lm committed
815
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
816 817
    {
        mavlink_message_t msg;
lm's avatar
lm committed
818
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
819
        sendMessage(msg);
lm's avatar
lm committed
820
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
821
    }
pixhawk's avatar
pixhawk committed
822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838
}

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

void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
839
    int len = mavlink_msg_to_send_buffer(buffer, &message);
840
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
841 842 843 844 845 846 847 848 849 850 851
    // 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
 */
852
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
853
{
854
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
855 856 857 858 859 860
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
861
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
862 863 864
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
865
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
866 867 868
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
869
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
870 871 872
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
873
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
874 875 876
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
877 878 879 880 881
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
882 883 884
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
885
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
886 887 888
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
889
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
890 891 892
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
893
    default:
pixhawk's avatar
pixhawk committed
894 895 896 897 898 899 900 901 902 903 904 905 906 907 908
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
909
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
910 911 912 913 914 915 916 917
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

918
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
919 920 921 922
{
    return commStatus;
}

923 924 925
void UAS::requestParameters()
{
    mavlink_message_t msg;
926
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
927 928
    // Send message twice to increase chance of reception
    sendMessage(msg);
929 930
}

931
void UAS::writeParametersToStorage()
932
{
933 934 935
    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
936
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
937 938 939 940 941 942 943 944 945
    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
946 947
}

948
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
949 950
{
    // Buffers to write data to
951
    mavlink_message_t msg;
952
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
953 954
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
955
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
956 957
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
958 959
    // 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
960 961
    stream.req_message_rate = 0;
    // Start / stop the message
962
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
963 964 965 966 967
    // 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
968
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
969 970
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
971 972 973
    sendMessage(msg);
}

974
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
975 976 977
{
    // Buffers to write data to
    mavlink_message_t msg;
978
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
979
    // Select the message to request from now on
980
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
981
    // Select the update rate in Hz the message should be send
982
    stream.req_message_rate = rate;
lm's avatar
lm committed
983
    // Start / stop the message
984
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
985 986 987 988 989
    // 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
990
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
991 992
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
993 994 995
    sendMessage(msg);
}

996
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
997
{
998 999 1000 1001
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1002
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1003
    // Select the update rate in Hz the message should be send
1004
    stream.req_message_rate = rate;
1005
    // Start / stop the message
1006
    stream.start_stop = (rate) ? 1 : 0;
1007 1008 1009 1010 1011 1012
    // 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);
1013 1014
    // Send message twice to increase chance of reception
    sendMessage(msg);
1015
    sendMessage(msg);
lm's avatar
lm committed
1016
}
1017

1018
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1019
{
1020 1021 1022 1023 1024
#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
1025 1026 1027
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1028
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1029
    // Select the update rate in Hz the message should be send
1030
    stream.req_message_rate = rate;
1031
    // Start / stop the message
1032
    stream.start_stop = (rate) ? 1 : 0;
1033 1034 1035 1036 1037 1038
    // 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);
1039 1040
    // Send message twice to increase chance of reception
    sendMessage(msg);
1041
    sendMessage(msg);
1042
#endif
lm's avatar
lm committed
1043 1044
}

1045
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1046
{
1047 1048 1049 1050
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1051
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1052
    // Select the update rate in Hz the message should be send
1053
    stream.req_message_rate = rate;
1054
    // Start / stop the message
1055
    stream.start_stop = (rate) ? 1 : 0;
1056 1057 1058 1059 1060 1061
    // 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);
1062 1063
    // Send message twice to increase chance of reception
    sendMessage(msg);
1064
    sendMessage(msg);
lm's avatar
lm committed
1065 1066
}

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

1089
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1090 1091 1092 1093 1094
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1095
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1096
    // Select the update rate in Hz the message should be send
1097
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1098
    // Start / stop the message
1099
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110
    // 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);
}

1111
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1112 1113 1114 1115 1116
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1117
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1118
    // Select the update rate in Hz the message should be send
1119
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1120
    // Start / stop the message
1121
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132
    // 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);
}

1133
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1134 1135 1136 1137 1138
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1139
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1140
    // Select the update rate in Hz the message should be send
1141
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1142
    // Start / stop the message
1143
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154
    // 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);
}

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

lm's avatar
lm committed
1177 1178 1179 1180 1181 1182 1183
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1184
void UAS::setParameter(int component, QString id, float value)
1185
{    
1186 1187 1188
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1189 1190
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1191

1192
    // Copy string into buffer, ensuring not to exceed the buffer size    
1193
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1194
    {
lm's avatar
lm committed
1195
        // String characters
1196
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1197
        {
1198
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1199 1200
        }
        // Null termination at end of string or end of buffer
1201
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1202 1203 1204 1205 1206 1207 1208 1209
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1210
    }    
1211
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1212
    sendMessage(msg);
1213 1214
}

pixhawk's avatar
pixhawk committed
1215
/**
lm's avatar
lm committed
1216
 * Launches the system
pixhawk's avatar
pixhawk committed
1217 1218 1219 1220
 *
 **/
void UAS::launch()
{
1221
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1222
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1223
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1224 1225 1226
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1227 1228 1229 1230 1231 1232 1233 1234
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1235
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1236
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1237
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1238 1239 1240
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1241 1242 1243 1244 1245 1246 1247 1248
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1249
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1250
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1251
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1252 1253 1254
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268
}

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;

lm's avatar
lm committed
1269 1270
//    if(mode == (int)MAV_MODE_MANUAL)
//    {
pixhawk's avatar
pixhawk committed
1271
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
1272
        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);
pixhawk's avatar
pixhawk committed
1273 1274 1275 1276
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;

        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
lm's avatar
lm committed
1277
//    }
pixhawk's avatar
pixhawk committed
1278 1279
}

1280 1281 1282 1283 1284
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1285 1286 1287 1288 1289
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1290

pixhawk's avatar
pixhawk committed
1291 1292
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1293

pixhawk's avatar
pixhawk committed
1294 1295 1296 1297 1298
        break;
    default:

        break;
    }
1299
//    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1300 1301 1302

}

1303

1304
/*void UAS::requestWaypoints()
1305 1306 1307 1308 1309
{
//    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
1310 1311
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1312 1313
}

pixhawk's avatar
pixhawk committed
1314 1315
void UAS::setWaypoint(Waypoint* wp)
{
1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333
//    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
1334 1335 1336 1337
}

void UAS::setWaypointActive(int id)
{
1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360
//    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!";
1361
}*/
pixhawk's avatar
pixhawk committed
1362 1363 1364 1365


void UAS::halt()
{
1366
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1367
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1368
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1369 1370 1371
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1372 1373 1374 1375
}

void UAS::go()
{
1376
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1377
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1378
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1379 1380 1381
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1382 1383 1384 1385 1386
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1387
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1388
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1389
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1390 1391 1392
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1393 1394 1395 1396 1397 1398 1399 1400
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1401
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1402
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1403
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1404 1405 1406
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431
}

/**
 * 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)
    {
1432
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1433
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1434
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1435 1436 1437
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460
        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
1461
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1462
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1463
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1464 1465 1466
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1467 1468 1469 1470
        result = true;
    }
}

1471 1472
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1473 1474 1475 1476 1477 1478
    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);
1479 1480
}

pixhawk's avatar
pixhawk committed
1481 1482 1483
/**
 * @return The name of this system as string in human-readable form
 */
1484
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524
{
    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);
    //qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
}

/**
 * @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
1525
    case NICD:
pixhawk's avatar
pixhawk committed
1526
        break;
lm's avatar
lm committed
1527
    case NIMH:
pixhawk's avatar
pixhawk committed
1528
        break;
lm's avatar
lm committed
1529
    case LIION:
pixhawk's avatar
pixhawk committed
1530
        break;
lm's avatar
lm committed
1531
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1532 1533 1534
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1535
    case LIFE:
pixhawk's avatar
pixhawk committed
1536
        break;
lm's avatar
lm committed
1537
    case AGZN:
pixhawk's avatar
pixhawk committed
1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554
        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
1555 1556 1557
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1558 1559
double UAS::getChargeLevel()
{
1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573
    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
1574 1575
}

lm's avatar
lm committed
1576 1577 1578 1579
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1580 1581
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593
        lowBattAlarm = true;
    }
}

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