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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
136 137 138 139 140 141 142 143 144 145
    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
146
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
147
            {
pixhawk's avatar
pixhawk committed
148
                this->type = mavlink_msg_heartbeat_get_type(&message);
pixhawk's avatar
pixhawk committed
149 150 151 152 153 154 155 156
                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
157 158
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
159 160
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
161

pixhawk's avatar
pixhawk committed
162
                // FIXME
163
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
164

pixhawk's avatar
pixhawk committed
165 166 167 168 169
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
170

pixhawk's avatar
pixhawk committed
171
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
172
                {
pixhawk's avatar
pixhawk committed
173
                    statechanged = true;
lm's avatar
lm committed
174
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
175 176
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
177
                    emit statusChanged(this->status);
178
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
179 180
                }

lm's avatar
lm committed
181
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
182 183
                {
                    modechanged = true;
lm's avatar
lm committed
184
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
185 186
                    QString mode;

lm's avatar
lm committed
187
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
188
                    {
lm's avatar
lm committed
189
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
190 191
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
192
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
193 194
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
195
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
196 197
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
198
                    case (uint8_t)MAV_MODE_GUIDED:
199 200
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
201
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
202 203
                        mode = "READY";
                        break;
lm's avatar
lm committed
204
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
205 206
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
207
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
208 209
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
210
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
211 212 213 214 215 216 217 218 219 220
                        mode = "TEST3 MODE";
                        break;
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
221
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
222
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
223 224 225
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
226
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
227
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
228

lm's avatar
lm committed
229 230
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
231
                if (chargeLevel <= 20.0f)
lm's avatar
lm committed
232 233 234 235 236 237 238 239
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
240
                // COMMUNICATIONS DROP RATE
241
                emit dropRateChanged(this->getUASID(), state.packet_drop);
242
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
243 244

                // AUDIO
pixhawk's avatar
pixhawk committed
245 246 247 248 249 250 251 252 253 254
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
255
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
256 257 258 259 260 261 262 263
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
pixhawk's avatar
pixhawk committed
264 265 266
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
267
            {
pixhawk's avatar
pixhawk committed
268 269
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
270
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
271

pixhawk's avatar
pixhawk committed
272 273 274 275 276 277 278 279 280
                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
281 282 283 284
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
285
            //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
286
            {
pixhawk's avatar
pixhawk committed
287 288
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
289
                quint64 time = getUnixTime(attitude.usec);
lm's avatar
lm committed
290 291 292
                roll = attitude.roll;
                pitch = attitude.pitch;
                yaw = attitude.yaw;
pixhawk's avatar
pixhawk committed
293 294 295 296 297 298
                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
299 300 301
                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
302
                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
303 304
            }
            break;
305
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
306
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
307
            //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
308
            {
309 310
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
311
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
312 313 314
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
lm's avatar
lm committed
315 316 317
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
318 319 320
                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
321
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
322 323
                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
324 325 326 327 328 329 330
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
331 332
            }
            break;
333 334 335 336 337 338 339 340 341 342 343 344 345 346
        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);
                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
347 348 349 350 351 352 353 354
                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;
355 356 357 358 359 360 361 362
            }
            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);
363 364 365

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

369 370
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
lm's avatar
lm committed
371

lm's avatar
lm committed
372
                if (pos.fix_type > 0)
373
                {
Laurens Mackay's avatar
Laurens Mackay committed
374
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394

                    // 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));
                    }
395
                }
396 397
            }
            break;
lm's avatar
lm committed
398 399 400 401
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
402
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
403
                {
lm's avatar
lm committed
404
                    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
405 406 407
                }
            }
            break;
lm's avatar
lm committed
408 409 410 411
        case MAVLINK_MSG_ID_RC_CHANNELS:
            {
                mavlink_rc_channels_t channels;
                mavlink_msg_rc_channels_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
412
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
lm's avatar
lm committed
413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444
                for (int i = 0; i < 8; i++)
                {
                    switch (i)
                    {
                    case 0:
                        emit remoteControlChannelChanged(i, channels.chan1_raw, channels.chan1_255/255.0f);
                        break;
                    case 1:
                        emit remoteControlChannelChanged(i, channels.chan2_raw, channels.chan2_255/255.0f);
                        break;
                    case 2:
                        emit remoteControlChannelChanged(i, channels.chan3_raw, channels.chan3_255/255.0f);
                        break;
                    case 3:
                        emit remoteControlChannelChanged(i, channels.chan4_raw, channels.chan4_255/255.0f);
                        break;
                    case 4:
                        emit remoteControlChannelChanged(i, channels.chan5_raw, channels.chan5_255/255.0f);
                        break;
                    case 5:
                        emit remoteControlChannelChanged(i, channels.chan6_raw, channels.chan6_255/255.0f);
                        break;
                    case 6:
                        emit remoteControlChannelChanged(i, channels.chan7_raw, channels.chan7_255/255.0f);
                        break;
                    case 7:
                        emit remoteControlChannelChanged(i, channels.chan8_raw, channels.chan8_255/255.0f);
                        break;
                    }
                }
            }
            break;
445 446 447 448 449 450 451
        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
452
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
453
            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
454
            break;
455 456 457 458 459
        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
460
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
461 462 463 464 465 466 467 468 469
                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);
470
                quint64 time = MG::TIME::getGroundTimeNow();
471
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
472 473 474
                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);
475 476
            }
            break;
pixhawk's avatar
pixhawk committed
477 478 479 480
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
481 482 483 484
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
485 486 487
            }
            break;

488
        case MAVLINK_MSG_ID_WAYPOINT:
489
            {
490 491
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
492
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
493 494 495 496
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
497
            }
pixhawk's avatar
pixhawk committed
498
            break;
pixhawk's avatar
pixhawk committed
499

500 501 502 503 504 505 506 507 508 509 510
        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
511 512 513 514
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
515 516 517 518
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
519 520 521
            }
            break;

522
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
523
            {
pixhawk's avatar
pixhawk committed
524 525 526
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
527
            }
pixhawk's avatar
pixhawk committed
528
            break;
pixhawk's avatar
pixhawk committed
529

530
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
531
            {
532 533 534
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
535
            }
pixhawk's avatar
pixhawk committed
536
            break;
pixhawk's avatar
pixhawk committed
537

538 539 540 541 542 543 544
        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
545

546
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
547 548 549
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
550
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
551 552
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
553
                int severity = mavlink_msg_statustext_get_severity(&message);
554
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
555
                //emit statusTextReceived(severity, text);
556
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
557 558
            }
            break;
559
#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES
560 561 562 563 564 565 566 567 568 569 570 571 572 573
        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;
#endif
pixhawk's avatar
pixhawk committed
574
        default:
lm's avatar
lm committed
575 576 577 578
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
579 580
                    //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
581 582 583
                    //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
584 585 586 587 588
            break;
        }
    }
}

pixhawk's avatar
pixhawk committed
589 590
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
591
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
592
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
593 594
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
595
  #endif
pixhawk's avatar
pixhawk committed
596 597
}

pixhawk's avatar
pixhawk committed
598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
  mavlink_message_t msg;
  mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
  sendMessage(msg);
#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);
}

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

635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656
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
657
    else if (time < 1261440000000000LLU)
658 659 660
    {
        if (onboardTimeOffset == 0)
        {
661
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
662
        }
663
        return time/1000 + onboardTimeOffset;
664 665 666 667 668
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
669
        return time/1000;
670 671 672
    }
}

pixhawk's avatar
pixhawk committed
673
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
674
{
lm's avatar
lm committed
675
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_TEST3)
pixhawk's avatar
pixhawk committed
676 677
    {
        mavlink_message_t msg;
lm's avatar
lm committed
678
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
679
        sendMessage(msg);
lm's avatar
lm committed
680
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
681
    }
pixhawk's avatar
pixhawk committed
682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698
}

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
699
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
700 701 702 703 704 705 706 707 708 709 710
    // 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
 */
711
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
712
{
713
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
714 715 716 717 718 719
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
720
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
721 722 723
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
724
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
725 726 727
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
728
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
729 730 731
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
732
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
733 734 735
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
736 737 738 739 740
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
741 742 743
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
744
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
745 746 747
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
748
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
749 750 751
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
752
    default:
pixhawk's avatar
pixhawk committed
753 754 755 756 757 758 759 760 761 762 763 764 765 766 767
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
768
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
769 770 771 772 773 774 775 776
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

777
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
778 779 780 781
{
    return commStatus;
}

782 783 784
void UAS::requestParameters()
{
    mavlink_message_t msg;
785
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
786 787
    // Send message twice to increase chance of reception
    sendMessage(msg);
788 789
}

790
void UAS::writeParametersToStorage()
791
{
792 793 794
    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
795
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
796 797 798 799 800 801 802 803 804
    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
805 806 807 808
}

void UAS::enableAllDataTransmission(bool enabled)
{
809
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
lm's avatar
lm committed
810
    // Buffers to write data to
811
    mavlink_message_t msg;
812
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
813 814
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
815
    stream.req_stream_id = 0;
lm's avatar
lm committed
816 817 818 819 820 821 822 823 824 825
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
    stream.req_message_rate = 0;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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
826
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
827 828
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
829
    sendMessage(msg);
830
#endif
lm's avatar
lm committed
831 832 833 834
}

void UAS::enableRawSensorDataTransmission(bool enabled)
{
835
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
lm's avatar
lm committed
836 837
    // Buffers to write data to
    mavlink_message_t msg;
838
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
839
    // Select the message to request from now on
840
    stream.req_stream_id = 1;
lm's avatar
lm committed
841 842 843 844 845 846 847 848 849
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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
850
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
851 852
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
853
    sendMessage(msg);
854
#endif
lm's avatar
lm committed
855 856 857 858
}

void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
859
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
860 861 862 863 864 865 866 867 868 869 870 871 872 873 874
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 2;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 10;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
875 876
    // Send message twice to increase chance of reception
    sendMessage(msg);
877
    sendMessage(msg);
878
#endif
lm's avatar
lm committed
879
}
880

lm's avatar
lm committed
881 882
void UAS::enableRCChannelDataTransmission(bool enabled)
{
883
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
884 885 886 887 888 889 890 891 892 893 894 895 896 897 898
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 3;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
899 900
    // Send message twice to increase chance of reception
    sendMessage(msg);
901
    sendMessage(msg);
902
#endif
lm's avatar
lm committed
903 904 905 906
}

void UAS::enableRawControllerDataTransmission(bool enabled)
{
907
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
908 909 910 911 912 913 914 915 916 917 918 919 920 921 922
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 4;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
923 924
    // Send message twice to increase chance of reception
    sendMessage(msg);
925
    sendMessage(msg);
926
#endif
lm's avatar
lm committed
927 928 929 930
}

void UAS::enableRawSensorFusionTransmission(bool enabled)
{
931
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
932 933 934 935 936 937 938 939 940 941 942 943 944 945 946
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 5;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
947 948
    // Send message twice to increase chance of reception
    sendMessage(msg);
949
    sendMessage(msg);
950
#endif
951 952
}

pixhawk's avatar
pixhawk committed
953 954
void UAS::enablePositionTransmission(bool enabled)
{
955
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 6;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
974
#endif
pixhawk's avatar
pixhawk committed
975 976 977 978
}

void UAS::enableExtra1Transmission(bool enabled)
{
979
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 7;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
998
#endif
pixhawk's avatar
pixhawk committed
999 1000 1001 1002
}

void UAS::enableExtra2Transmission(bool enabled)
{
1003
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 8;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
1022
#endif
pixhawk's avatar
pixhawk committed
1023 1024 1025 1026
}

void UAS::enableExtra3Transmission(bool enabled)
{
1027
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
1028 1029 1030 1031 1032 1033 1034
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 9;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
1035 1036 1037 1038 1039 1040 1041 1042
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // 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);
1043 1044
    // Send message twice to increase chance of reception
    sendMessage(msg);
1045
    sendMessage(msg);
1046
#endif
1047 1048
}

lm's avatar
lm committed
1049 1050 1051 1052 1053 1054 1055
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1056
void UAS::setParameter(int component, QString id, float value)
1057
{    
1058 1059 1060
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1061 1062
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1063

1064
    // Copy string into buffer, ensuring not to exceed the buffer size    
1065
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1066
    {
lm's avatar
lm committed
1067
        // String characters
1068
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1069
        {
1070
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1071 1072
        }
        // Null termination at end of string or end of buffer
1073
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1074 1075 1076 1077 1078 1079 1080 1081
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1082
    }    
1083
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1084
    sendMessage(msg);
1085 1086
}

pixhawk's avatar
pixhawk committed
1087
/**
lm's avatar
lm committed
1088
 * Launches the system
pixhawk's avatar
pixhawk committed
1089 1090 1091 1092
 *
 **/
void UAS::launch()
{
1093
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1094
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1095
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1096 1097 1098
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1099 1100 1101 1102 1103 1104 1105 1106
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1107
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1108
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1109
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1110 1111 1112
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1113 1114 1115 1116 1117 1118 1119 1120
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1121
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1122
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1123
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1124 1125 1126
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140
}

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
1141 1142
//    if(mode == (int)MAV_MODE_MANUAL)
//    {
1143
      #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
1144
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
1145
        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
1146 1147 1148 1149
        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());
1150
      #endif
lm's avatar
lm committed
1151
//    }
pixhawk's avatar
pixhawk committed
1152 1153
}

1154 1155 1156 1157 1158
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1159 1160 1161 1162 1163
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1164

pixhawk's avatar
pixhawk committed
1165 1166
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1167

pixhawk's avatar
pixhawk committed
1168 1169 1170 1171 1172 1173 1174 1175 1176
        break;
    default:

        break;
    }
    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";

}

1177

1178
/*void UAS::requestWaypoints()
1179 1180 1181 1182 1183
{
//    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
1184 1185
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1186 1187
}

pixhawk's avatar
pixhawk committed
1188 1189
void UAS::setWaypoint(Waypoint* wp)
{
1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207
//    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
1208 1209 1210 1211
}

void UAS::setWaypointActive(int id)
{
1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234
//    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!";
1235
}*/
pixhawk's avatar
pixhawk committed
1236 1237 1238 1239


void UAS::halt()
{
1240
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1241
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1242
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1243 1244 1245
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1246 1247 1248 1249
}

void UAS::go()
{
1250
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1251
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1252
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1253 1254 1255
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1256 1257 1258 1259 1260
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1261
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1262
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1263
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1264 1265 1266
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1267 1268 1269 1270 1271 1272 1273 1274
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1275
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1276
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1277
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1278 1279 1280
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305
}

/**
 * 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)
    {
1306
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1307
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1308
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1309 1310 1311
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334
        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
1335
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1336
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1337
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1338 1339 1340
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1341 1342 1343 1344
        result = true;
    }
}

1345 1346 1347 1348 1349 1350 1351 1352 1353 1354
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
    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);
}

pixhawk's avatar
pixhawk committed
1355 1356 1357
/**
 * @return The name of this system as string in human-readable form
 */
1358
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398
{
    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
1399
    case NICD:
pixhawk's avatar
pixhawk committed
1400
        break;
lm's avatar
lm committed
1401
    case NIMH:
pixhawk's avatar
pixhawk committed
1402
        break;
lm's avatar
lm committed
1403
    case LIION:
pixhawk's avatar
pixhawk committed
1404
        break;
lm's avatar
lm committed
1405
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1406 1407 1408
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1409
    case LIFE:
pixhawk's avatar
pixhawk committed
1410
        break;
lm's avatar
lm committed
1411
    case AGZN:
pixhawk's avatar
pixhawk committed
1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428
        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
1429 1430 1431
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1432 1433
double UAS::getChargeLevel()
{
1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447
    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
1448 1449
}

lm's avatar
lm committed
1450 1451 1452 1453
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1454 1455
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467
        lowBattAlarm = true;
    }
}

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