UAS.cc 72.8 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5 6 7 8 9 10 11 12 13 14
======================================================================*/

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

#include <QList>
#include <QMessageBox>
#include <QTimer>
15
#include <QSettings>
pixhawk's avatar
pixhawk committed
16 17 18
#include <iostream>
#include <QDebug>
#include <cmath>
19
#include <qmath.h>
pixhawk's avatar
pixhawk committed
20 21 22
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
23
#include "QGC.h"
pixhawk's avatar
pixhawk committed
24
#include "GAudioOutput.h"
25
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
26
#include "QGCMAVLink.h"
27 28
#include "LinkManager.h"
#include "SerialLink.h"
pixhawk's avatar
pixhawk committed
29

30
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
31 32 33 34 35 36 37 38 39 40 41 42
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
pixhawk's avatar
pixhawk committed
43
warnVoltage(9.5f),
44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70
currentVoltage(12.0f),
lpVoltage(12.0f),
mode(MAV_MODE_UNINIT),
status(MAV_STATE_UNINIT),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
receiveDropRate(0),
sendDropRate(0),
lowBattAlarm(false),
positionLock(false),
localX(0.0),
localY(0.0),
localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
71 72
paramsOnceRequested(false),
airframe(0)
pixhawk's avatar
pixhawk committed
73
{
74
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
75
    setBattery(LIPOLY, 3);
76
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
77
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
78
    statusTimeout->start(500);
79
    readSettings();
pixhawk's avatar
pixhawk committed
80 81 82 83
}

UAS::~UAS()
{
84
    writeSettings();
pixhawk's avatar
pixhawk committed
85
    delete links;
86
    links=NULL;
pixhawk's avatar
pixhawk committed
87 88
}

89 90 91 92 93
void UAS::writeSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    settings.setValue("NAME", this->name);
94 95
    settings.setValue("AIRFRAME", this->airframe);
    settings.setValue("AP_TYPE", this->autopilot);
96
    settings.setValue("BATTERY_SPECS", getBatterySpecs());
97 98 99 100 101 102 103 104 105
    settings.endGroup();
    settings.sync();
}

void UAS::readSettings()
{
    QSettings settings;
    settings.beginGroup(QString("MAV%1").arg(uasId));
    this->name = settings.value("NAME", this->name).toString();
106 107
    this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
    this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
108 109 110 111
    if (settings.contains("BATTERY_SPECS"))
    {
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
112 113 114
    settings.endGroup();
}

115
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
116 117 118 119
{
    return uasId;
}

120 121
void UAS::updateState()
{
122 123 124 125 126 127 128 129
    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

130 131 132 133 134 135 136 137
    // 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
138
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
139 140 141 142 143 144
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
145 146
void UAS::setSelected()
{
147 148 149 150 151 152 153 154 155 156
    if (UASManager::instance()->getActiveUAS() != this)
    {
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
157 158
}

159 160 161 162
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
163 164
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
165
        emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime());
166 167 168
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
169 170
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
171
        emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime());
172 173 174
    }
}

pixhawk's avatar
pixhawk committed
175 176
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
177
    if (!link) return;
pixhawk's avatar
pixhawk committed
178 179 180
    if (!links->contains(link))
    {
        addLink(link);
181
        //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
182
    }
183 184 185 186
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed
187

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

pixhawk's avatar
pixhawk committed
190 191 192 193
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
194 195 196 197

        // Receive named value message
        receiveMessageNamedValue(message);

pixhawk's avatar
pixhawk committed
198 199 200
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
201
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
202 203
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
204
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
205
            {
pixhawk's avatar
pixhawk committed
206
                this->type = mavlink_msg_heartbeat_get_type(&message);
207 208 209 210 211 212 213 214 215 216 217 218 219 220 221
                if (airframe == 0)
                {
                    switch (type)
                    {
                    case MAV_FIXED_WING:
                        setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                        break;
                    case MAV_QUADROTOR:
                        setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                        break;
                    default:
                        // Do nothing
                        break;
                    }
                }
222
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
223 224
                emit systemTypeSet(this, type);
            }
225

pixhawk's avatar
pixhawk committed
226 227 228 229 230 231
            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
232 233
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
234 235
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
236

pixhawk's avatar
pixhawk committed
237
                // FIXME
238
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
239

pixhawk's avatar
pixhawk committed
240 241 242 243 244
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
245

pixhawk's avatar
pixhawk committed
246
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
247
                {
pixhawk's avatar
pixhawk committed
248
                    statechanged = true;
lm's avatar
lm committed
249
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
250 251
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
252
                    emit statusChanged(this->status);
253
                    emit loadChanged(this,state.load/10.0f);
254
                    emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
255
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
256 257
                }

lm's avatar
lm committed
258
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
259 260
                {
                    modechanged = true;
lm's avatar
lm committed
261
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
262 263
                    QString mode;

lm's avatar
lm committed
264
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
265
                    {
lm's avatar
lm committed
266
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
267 268
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
269
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
270 271
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
272
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
273 274
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
275
                    case (uint8_t)MAV_MODE_GUIDED:
276 277
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
278
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
279 280
                        mode = "READY";
                        break;
lm's avatar
lm committed
281
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
282 283
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
284
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
285 286
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
287
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
288 289
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
290 291 292
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
293 294 295 296 297 298 299 300
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
301
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
302
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
303 304 305
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
306
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
307
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
308

lm's avatar
lm committed
309
                // LOW BATTERY ALARM
310
                if (lpVoltage < warnVoltage)
lm's avatar
lm committed
311 312 313 314 315 316 317 318
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
319
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
320
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
321
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
322 323

                // AUDIO
pixhawk's avatar
pixhawk committed
324 325 326 327 328 329 330 331 332 333
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
334
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
335 336 337 338 339 340 341 342
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
343 344 345 346 347 348

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
349 350
            }
            break;
James Goppert's avatar
James Goppert committed
351 352

        #ifdef MAVLINK_ENABLED_PIXHAWK
353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368
        case MAVLINK_MSG_ID_CONTROL_STATUS:
            {
                mavlink_control_status_t status;
                mavlink_msg_control_status_decode(&message, &status);
                // Emit control status vector
                emit attitudeControlEnabled(static_cast<bool>(status.control_att));
                emit positionXYControlEnabled(static_cast<bool>(status.control_pos_xy));
                emit positionZControlEnabled(static_cast<bool>(status.control_pos_z));
                emit positionYawControlEnabled(static_cast<bool>(status.control_pos_yaw));

                // Emit localization status vector
                emit localizationChanged(this, status.position_fix);
                emit visionLocalizationChanged(this, status.vision_fix);
                emit gpsLocalizationChanged(this, status.gps_fix);
            }
            break;
James Goppert's avatar
James Goppert committed
369
		#endif // PIXHAWK 
pixhawk's avatar
pixhawk committed
370
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
371
            {
pixhawk's avatar
pixhawk committed
372 373
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
374
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
375

pixhawk's avatar
pixhawk committed
376 377 378
                emit valueChanged(uasId, "accel x", "raw", static_cast<double>(raw.xacc), time);
                emit valueChanged(uasId, "accel y", "raw", static_cast<double>(raw.yacc), time);
                emit valueChanged(uasId, "accel z", "raw", static_cast<double>(raw.zacc), time);
379 380 381
                emit valueChanged(uasId, "gyro roll", "raw", static_cast<double>(raw.xgyro), time);
                emit valueChanged(uasId, "gyro pitch", "raw", static_cast<double>(raw.ygyro), time);
                emit valueChanged(uasId, "gyro yaw", "raw", static_cast<double>(raw.zgyro), time);
pixhawk's avatar
pixhawk committed
382 383 384
                emit valueChanged(uasId, "mag x", "raw", static_cast<double>(raw.xmag), time);
                emit valueChanged(uasId, "mag y", "raw", static_cast<double>(raw.ymag), time);
                emit valueChanged(uasId, "mag z", "raw", static_cast<double>(raw.zmag), time);
pixhawk's avatar
pixhawk committed
385 386 387 388
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
389
            //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
390
            {
pixhawk's avatar
pixhawk committed
391 392
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
393
                quint64 time = getUnixTime(attitude.usec);
394 395 396 397 398 399 400 401

                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);

                emit valueChanged(uasId, "roll", "rad", roll, time);
                emit valueChanged(uasId, "pitch", "rad", pitch, time);
                emit valueChanged(uasId, "yaw", "rad", yaw, time);
402 403 404
                emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time);
                emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time);
                emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time);
405 406

                // Emit in angles
407 408 409 410 411 412 413 414 415 416 417

                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
                while (compass > 360.0f)
                {
                    compass -= 360.0f;
                }

                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
pixhawk's avatar
pixhawk committed
418
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
419 420 421
                emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
422

423 424
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
425 426
            }
            break;
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457
            case MAVLINK_MSG_ID_VFR_HUD:
            {
                mavlink_vfr_hud_t hud;
                mavlink_msg_vfr_hud_decode(&message, &hud);
                quint64 time = getUnixTime();
                // Display updated values
                emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
                emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
                emit valueChanged(uasId, "altitude", "m", hud.alt, time);
                emit valueChanged(uasId, "heading", "deg", hud.heading, time);
                emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
                emit valueChanged(uasId, "throttle", "m/s", hud.throttle, time);
                emit thrustChanged(this, hud.throttle/100.0);
            }
            break;
            case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
                mavlink_nav_controller_output_t nav;
                mavlink_msg_nav_controller_output_decode(&message, &nav);
                quint64 time = getUnixTime();
                // Update UI
                emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
                emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
                emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
                emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
                emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
                emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
                emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
                //emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
            }
            break;
458
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
459
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
460
            //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
461
            {
462 463
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
464
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
465 466 467
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
468 469 470 471 472 473
                emit valueChanged(uasId, "x", "m", pos.x, time);
                emit valueChanged(uasId, "y", "m", pos.y, time);
                emit valueChanged(uasId, "z", "m", pos.z, time);
                emit valueChanged(uasId, "x speed", "m/s", pos.vx, time);
                emit valueChanged(uasId, "y speed", "m/s", pos.vy, time);
                emit valueChanged(uasId, "z speed", "m/s", pos.vz, time);
lm's avatar
lm committed
474
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
475
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
476

477 478
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
479

480
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
481 482 483 484 485 486 487
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
488 489
            }
            break;
490
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
491 492 493
            //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;
            {
494 495
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
496
                quint64 time = QGC::groundTimeUsecs()/1000;
497 498 499 500 501 502
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                speedX = pos.vx/100.0;
                speedY = pos.vy/100.0;
                speedZ = pos.vz/100.0;
503 504 505 506 507 508
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                emit valueChanged(uasId, "gps x speed", "m/s", speedX, time);
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
509
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536
                emit speedChanged(this, speedX, speedY, speedZ, time);
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
            }
            break;
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = QGC::groundTimeUsecs()/1000;
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                emit valueChanged(uasId, "gps x speed", "m/s", speedX, time);
537 538
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
539 540
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
541
                emit valueChanged(uasId, "gpsspeed", "m/s", sqrt(speedX*speedX+speedY*speedY+speedZ*speedZ), time);
pixhawk's avatar
pixhawk committed
542 543 544 545 546 547 548
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
549 550
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
551 552 553 554 555 556 557 558
            }
            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);
559 560 561

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

565 566
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
567

lm's avatar
lm committed
568
                if (pos.fix_type > 0)
569
                {
Laurens Mackay's avatar
Laurens Mackay committed
570
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
571
                    emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time);
lm's avatar
lm committed
572 573 574 575 576 577 578 579

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
580
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
581 582 583
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
584
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
585
                        //qDebug() << "GOT GPS RAW";
586
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
587 588 589 590 591
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
592
                }
593 594
            }
            break;
lm's avatar
lm committed
595 596 597 598
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
599
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
600
                {
lm's avatar
lm committed
601
                    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
602 603 604
                }
            }
            break;
605 606 607 608 609 610 611
        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;
612 613 614 615
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
616
                quint64 time = this->getUnixTime(0);
617 618 619
                emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time);
620 621
            }
            break;
622
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
623
            {
624 625
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
626
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649
                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
650 651
            }
            break;
652 653 654 655
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672

                QString parameterName = QString((char*)value.param_id);
                int component = message.compid;
                float val = value.param_value;

                // Insert component if necessary
                if (!parameters.contains(component))
                {
                    parameters.insert(component, new QMap<QString, float>());
                }

                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                parameters.value(component)->insert(parameterName, val);

                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
673 674
            }
            break;
pixhawk's avatar
pixhawk committed
675
        case MAVLINK_MSG_ID_DEBUG:
676
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
677
            break;
678 679 680 681 682
        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
683
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
684 685 686
                emit valueChanged(uasId, "att control roll", "raw", out.roll, time/1000.0f);
                emit valueChanged(uasId, "att control pitch", "raw", out.pitch, time/1000.0f);
                emit valueChanged(uasId, "att control yaw", "raw", out.yaw, time/1000.0f);
687 688 689 690 691 692
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
693
                quint64 time = MG::TIME::getGroundTimeNow();
694
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
695 696 697
                emit valueChanged(uasId, "pos control x", "raw", out.x, time);
                emit valueChanged(uasId, "pos control y", "raw", out.y, time);
                emit valueChanged(uasId, "pos control z", "raw", out.z, time);
698 699
            }
            break;
pixhawk's avatar
pixhawk committed
700 701 702 703
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
704 705 706 707
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
708 709 710
            }
            break;

711
        case MAVLINK_MSG_ID_WAYPOINT:
712
            {
713 714
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
715
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
716 717 718 719
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
720
            }
pixhawk's avatar
pixhawk committed
721
            break;
pixhawk's avatar
pixhawk committed
722

723 724 725 726 727 728 729 730 731 732 733
        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
734 735 736 737
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
738 739 740 741
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
742 743 744
            }
            break;

745
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
746
            {
pixhawk's avatar
pixhawk committed
747 748 749
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
750
            }
pixhawk's avatar
pixhawk committed
751
            break;
pixhawk's avatar
pixhawk committed
752

753
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
754
            {
755 756 757
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
758
            }
pixhawk's avatar
pixhawk committed
759
            break;
pixhawk's avatar
pixhawk committed
760

761 762 763 764 765 766 767
        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;
768 769 770 771 772 773 774 775 776 777 778 779 780 781 782
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
                mavlink_servo_output_raw_t servos;
                mavlink_msg_servo_output_raw_decode(&message, &servos);
                quint64 time = getUnixTime(0);
                emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time);
                emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time);
                emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time);
                emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time);
                emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time);
                emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time);
                emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time);
                emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time);
            }
            break;
783
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
784 785 786
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
787
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
788 789
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
790
                int severity = mavlink_msg_statustext_get_severity(&message);
791
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
792
                //emit statusTextReceived(severity, text);
793
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
794 795
            }
            break;
796 797 798 799 800 801
    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);
802 803 804
                emit valueChanged(uasId, str+".x", "raw", vect.x, time);
                emit valueChanged(uasId, str+".y", "raw", vect.y, time);
                emit valueChanged(uasId, str+".z", "raw", vect.z, time);
805 806
            }
            break;
807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822
            //#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
823
#ifdef MAVLINK_ENABLED_UALBERTA
824 825 826 827 828
        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();
829 830 831 832 833 834
                emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
835 836
            }
            break;
837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860
       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];

861
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
862 863 864 865 866
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

867
#endif
pixhawk's avatar
pixhawk committed
868
        default:
lm's avatar
lm committed
869 870 871 872
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
873 874 875
                    QString errString = tr("UNABLE TO DECODE MESSAGE WITH ID %1").arg(message.msgid);
                    GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
876
                    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
877 878 879
                    //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
880 881 882 883 884
            break;
        }
    }
}

885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914
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
915 916
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
917
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
918
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
919 920
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
921
#else
lm's avatar
lm committed
922 923 924 925
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
926
#endif
pixhawk's avatar
pixhawk committed
927 928
}

pixhawk's avatar
pixhawk committed
929 930
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
931
#ifdef MAVLINK_ENABLED_PIXHAWK
932 933 934
    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
935
#else
936 937 938 939
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
940 941 942 943 944
#endif
}

void UAS::startRadioControlCalibration()
{
945 946 947
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_RC);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
948 949
}

lm's avatar
lm committed
950 951
void UAS::startDataRecording()
{
952 953 954
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
    sendMessage(msg);
lm's avatar
lm committed
955 956 957 958
}

void UAS::pauseDataRecording()
{
959 960 961
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
    sendMessage(msg);
lm's avatar
lm committed
962 963 964 965
}

void UAS::stopDataRecording()
{
966 967 968
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
    sendMessage(msg);
lm's avatar
lm committed
969 970
}

pixhawk's avatar
pixhawk committed
971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991
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);
}

992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013
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
1014
#ifndef _MSC_VER
1015
    else if (time < 1261440000000000LLU)
1016
#else
1017
        else if (time < 1261440000000000)
1018
#endif
1019
        {
1020 1021
        if (onboardTimeOffset == 0)
        {
1022
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
1023
        }
1024
        return time/1000 + onboardTimeOffset;
1025 1026 1027 1028 1029
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1030
        return time/1000;
1031 1032 1033
    }
}

1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050
QList<QString> UAS::getParameterNames(int component)
{
    if (parameters.contains(component))
    {
        return parameters.value(component)->keys();
    }
    else
    {
        return QList<QString>();
    }
}

QList<int> UAS::getComponentIds()
{
    return parameters.keys();
}

pixhawk's avatar
pixhawk committed
1051
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1052
{
lm's avatar
lm committed
1053
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1054
    {
1055
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1056
        mavlink_message_t msg;
lm's avatar
lm committed
1057
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1058
        sendMessage(msg);
lm's avatar
lm committed
1059
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1060
    }
pixhawk's avatar
pixhawk committed
1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072
}

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

1073 1074 1075 1076
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1077

1078 1079
    foreach(LinkInterface* link, link_list)
    {
1080
        if (link)
1081
        {
1082 1083
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1084
            {
1085 1086

                for(int i=0;i<links->size();i++)
1087
                {
1088 1089
                    if(serial != links->at(i))
                    {
1090
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1091 1092
                        sendMessage(serial, message);
                    }
1093 1094 1095 1096 1097 1098
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1099 1100
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1101
    if(!link) return;
pixhawk's avatar
pixhawk committed
1102 1103 1104
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1105
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1106
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117
    // 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
 */
1118
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1119
{
1120
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1121 1122 1123 1124 1125 1126
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1127
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1128
        uasState = tr("UNINIT");
1129
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
1130
        break;
lm's avatar
lm committed
1131
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1132
        uasState = tr("BOOT");
1133
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
1134
        break;
lm's avatar
lm committed
1135
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1136
        uasState = tr("CALIBRATING");
1137
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
1138
        break;
lm's avatar
lm committed
1139
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1140
        uasState = tr("ACTIVE");
1141
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
1142
        break;
lm's avatar
lm committed
1143 1144
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1145
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
1146 1147
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1148
        uasState = tr("CRITICAL");
1149
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
1150
        break;
lm's avatar
lm committed
1151
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1152
        uasState = tr("EMERGENCY");
1153
        stateDescription = tr("EMERGENCY: Land!");
pixhawk's avatar
pixhawk committed
1154
        break;
lm's avatar
lm committed
1155
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1156
        uasState = tr("SHUTDOWN");
1157
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
1158
        break;
lm's avatar
lm committed
1159
    default:
pixhawk's avatar
pixhawk committed
1160
        uasState = tr("UNKNOWN");
1161
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1175
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1176 1177 1178 1179 1180 1181 1182 1183
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1184
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1185 1186 1187 1188
{
    return commStatus;
}

1189 1190 1191
void UAS::requestParameters()
{
    mavlink_message_t msg;
1192
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1193 1194
    // Send message twice to increase chance of reception
    sendMessage(msg);
1195 1196
}

1197
void UAS::writeParametersToStorage()
1198
{
1199 1200 1201
    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
1202
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1203 1204 1205 1206 1207 1208 1209 1210 1211
    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
1212 1213
}

1214
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1215 1216
{
    // Buffers to write data to
1217
    mavlink_message_t msg;
1218
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1219 1220
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1221
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1222 1223
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1224 1225
    // 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
1226 1227
    stream.req_message_rate = 0;
    // Start / stop the message
1228
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1229 1230 1231 1232 1233
    // 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
1234
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1235 1236
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1237 1238 1239
    sendMessage(msg);
}

1240
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1241 1242 1243
{
    // Buffers to write data to
    mavlink_message_t msg;
1244
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1245
    // Select the message to request from now on
1246
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1247
    // Select the update rate in Hz the message should be send
1248
    stream.req_message_rate = rate;
lm's avatar
lm committed
1249
    // Start / stop the message
1250
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1251 1252 1253 1254 1255
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
1256
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1257 1258
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1259 1260 1261
    sendMessage(msg);
}

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

1284
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1285
{
1286 1287 1288 1289 1290
#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
1291 1292 1293
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1294
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1295
    // Select the update rate in Hz the message should be send
1296
    stream.req_message_rate = rate;
1297
    // Start / stop the message
1298
    stream.start_stop = (rate) ? 1 : 0;
1299 1300 1301 1302 1303 1304
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1305 1306
    // Send message twice to increase chance of reception
    sendMessage(msg);
1307
    sendMessage(msg);
1308
#endif
lm's avatar
lm committed
1309 1310
}

1311
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1312
{
1313 1314 1315 1316
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1317
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1318
    // Select the update rate in Hz the message should be send
1319
    stream.req_message_rate = rate;
1320
    // Start / stop the message
1321
    stream.start_stop = (rate) ? 1 : 0;
1322 1323 1324 1325 1326 1327
    // 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);
1328 1329
    // Send message twice to increase chance of reception
    sendMessage(msg);
1330
    sendMessage(msg);
lm's avatar
lm committed
1331 1332
}

1333
void UAS::enableRawSensorFusionTransmission(int rate)
lm's avatar
lm committed
1334
{
1335 1336 1337 1338
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1339
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
1340
    // Select the update rate in Hz the message should be send
1341
    stream.req_message_rate = rate;
1342
    // Start / stop the message
1343
    stream.start_stop = (rate) ? 1 : 0;
1344 1345 1346 1347 1348 1349
    // 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);
1350 1351
    // Send message twice to increase chance of reception
    sendMessage(msg);
1352
    sendMessage(msg);
1353 1354
}

1355
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1356 1357 1358 1359 1360
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1361
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1362
    // Select the update rate in Hz the message should be send
1363
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1364
    // Start / stop the message
1365
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376
    // 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);
}

1377
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1378 1379 1380 1381 1382
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1383
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1384
    // Select the update rate in Hz the message should be send
1385
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1386
    // Start / stop the message
1387
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398
    // 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);
}

1399
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1400 1401 1402 1403 1404
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1405
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1406
    // Select the update rate in Hz the message should be send
1407
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1408
    // Start / stop the message
1409
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420
    // 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);
}

1421
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1422 1423 1424 1425 1426
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1427
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1428
    // Select the update rate in Hz the message should be send
1429
    stream.req_message_rate = rate;
1430
    // Start / stop the message
1431
    stream.start_stop = (rate) ? 1 : 0;
1432 1433 1434 1435 1436 1437
    // 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);
1438 1439
    // Send message twice to increase chance of reception
    sendMessage(msg);
1440
    sendMessage(msg);
1441 1442
}

lm's avatar
lm committed
1443 1444 1445 1446 1447 1448 1449
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
lm's avatar
lm committed
1450 1451 1452 1453
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1454 1455 1456
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1457 1458
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1459

1460
    // Copy string into buffer, ensuring not to exceed the buffer size    
1461
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1462
    {
lm's avatar
lm committed
1463
        // String characters
1464
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1465
        {
1466
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1467 1468
        }
        // Null termination at end of string or end of buffer
1469
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1470 1471 1472 1473 1474 1475 1476 1477
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1478
    }    
1479
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1480
    sendMessage(msg);
lm's avatar
lm committed
1481
    }
1482 1483
}

1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502
void UAS::setSystemType(int systemType)
{
    type = systemType;
    // If the airframe is still generic, change it to a close default type
    if (airframe == 0)
    {
        switch (systemType)
        {
        case MAV_FIXED_WING:
            airframe = QGC_AIRFRAME_EASYSTAR;
            break;
        case MAV_QUADROTOR:
            airframe = QGC_AIRFRAME_MIKROKOPTER;
            break;
        }
    }
    emit systemSpecsChanged(uasId);
}

1503 1504 1505
void UAS::setUASName(const QString& name)
{
    this->name = name;
1506
    writeSettings();
1507
    emit nameChanged(name);
1508
    emit systemSpecsChanged(uasId);
1509 1510
}

1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523
/**
 * Sets an action
 *
 **/
void UAS::setAction(MAV_ACTION action)
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, action);
    // Send message twice to increase chance that it reaches its goal
    sendMessage(msg);
    sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
1524
/**
lm's avatar
lm committed
1525
 * Launches the system
pixhawk's avatar
pixhawk committed
1526 1527 1528 1529
 *
 **/
void UAS::launch()
{
1530
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1531
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1532
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
1533 1534 1535
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1536 1537 1538 1539 1540 1541 1542 1543
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1544
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1545
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1546
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1547 1548 1549
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1550 1551 1552 1553 1554 1555 1556 1557
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1558
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1559
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1560
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1561 1562 1563
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577
}

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;

1578 1579 1580 1581 1582 1583
    if(mode == (int)MAV_MODE_MANUAL)
    {
        mavlink_message_t message;
        mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
pixhawk's avatar
pixhawk committed
1584

1585 1586 1587 1588 1589 1590
        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    }
    else
    {
        qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    }
pixhawk's avatar
pixhawk committed
1591 1592
}

1593 1594 1595 1596 1597
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1598 1599 1600 1601 1602
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1603

pixhawk's avatar
pixhawk committed
1604 1605
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1606

pixhawk's avatar
pixhawk committed
1607 1608 1609 1610 1611
        break;
    default:

        break;
    }
1612
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1613 1614 1615

}

1616

1617
/*void UAS::requestWaypoints()
1618 1619 1620 1621 1622
{
//    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
1623 1624
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1625 1626
}

pixhawk's avatar
pixhawk committed
1627 1628
void UAS::setWaypoint(Waypoint* wp)
{
1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646
//    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
1647 1648 1649 1650
}

void UAS::setWaypointActive(int id)
{
1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673
//    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!";
1674
}*/
pixhawk's avatar
pixhawk committed
1675 1676 1677 1678


void UAS::halt()
{
1679
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1680
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1681
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1682 1683 1684
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1685 1686 1687 1688
}

void UAS::go()
{
1689
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1690
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1691
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1692 1693 1694
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1695 1696 1697 1698 1699
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1700
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1701
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1702
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1703 1704 1705
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1706 1707 1708 1709 1710 1711 1712 1713
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1714
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1715
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1716
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1717 1718 1719
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744
}

/**
 * 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)
    {
1745
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1746
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1747
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1748 1749 1750
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773
        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
1774
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1775
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1776
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1777 1778 1779
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1780 1781 1782 1783
        result = true;
    }
}

1784 1785
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1786 1787 1788 1789 1790 1791
    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);
1792 1793
}

pixhawk's avatar
pixhawk committed
1794 1795 1796
/**
 * @return The name of this system as string in human-readable form
 */
1797
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815
{
    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);
1816
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1817 1818
    }
    //links->append(link);
1819
    //qDebug() << link<<" ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
pixhawk's avatar
pixhawk committed
1820 1821
}

1822 1823 1824 1825 1826 1827 1828 1829 1830
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847
/**
 * @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
1848
    case NICD:
pixhawk's avatar
pixhawk committed
1849
        break;
lm's avatar
lm committed
1850
    case NIMH:
pixhawk's avatar
pixhawk committed
1851
        break;
lm's avatar
lm committed
1852
    case LIION:
pixhawk's avatar
pixhawk committed
1853
        break;
lm's avatar
lm committed
1854
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1855 1856 1857
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1858
    case LIFE:
pixhawk's avatar
pixhawk committed
1859
        break;
lm's avatar
lm committed
1860
    case AGZN:
pixhawk's avatar
pixhawk committed
1861 1862 1863 1864
        break;
    }
}

1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891
void UAS::setBatterySpecs(const QString& specs)
{
    QString stringList = specs;
    stringList = stringList.remove("V");
    stringList = stringList.remove("v");
    QStringList parts = stringList.split(",");
    if (parts.length() == 3)
    {
        float temp;
        bool ok;
        // Get the empty voltage
        temp = parts.at(0).toFloat(&ok);
        if (ok) emptyVoltage = temp;
        // Get the warning voltage
        temp = parts.at(1).toFloat(&ok);
        if (ok) warnVoltage = temp;
        // Get the full voltage
        temp = parts.at(2).toFloat(&ok);
        if (ok) fullVoltage = temp;
    }
}

QString UAS::getBatterySpecs()
{
    return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
}

pixhawk's avatar
pixhawk committed
1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904
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
1905 1906 1907
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1908 1909
double UAS::getChargeLevel()
{
1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923
    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
1924 1925
}

lm's avatar
lm committed
1926 1927 1928 1929
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1930 1931
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943
        lowBattAlarm = true;
    }
}

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