UAS.cc 73.4 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

pixhawk's avatar
pixhawk committed
195 196 197
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
198
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
199 200
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
201
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
202
            {
pixhawk's avatar
pixhawk committed
203
                this->type = mavlink_msg_heartbeat_get_type(&message);
204 205 206 207 208 209 210 211 212 213 214 215 216 217 218
                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;
                    }
                }
219
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
220 221
                emit systemTypeSet(this, type);
            }
222

223 224 225 226 227
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
pixhawk's avatar
pixhawk committed
228 229 230 231 232 233
            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
234 235
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
236 237
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
238

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

242
                QString audiostring = "System " + getUASName();
pixhawk's avatar
pixhawk committed
243 244 245 246
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
247

pixhawk's avatar
pixhawk committed
248
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
249
                {
pixhawk's avatar
pixhawk committed
250
                    statechanged = true;
lm's avatar
lm committed
251
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
252 253
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
254
                    emit statusChanged(this->status);
255
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
256 257
                }

lm's avatar
lm committed
258 259 260
                emit loadChanged(this,state.load/10.0f);
                emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, getUnixTime());

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

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

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

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

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

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

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
352 353
            }
            break;
James Goppert's avatar
James Goppert committed
354 355

        #ifdef MAVLINK_ENABLED_PIXHAWK
356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371
        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
372
		#endif // PIXHAWK 
pixhawk's avatar
pixhawk committed
373
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
374
            {
pixhawk's avatar
pixhawk committed
375 376
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
377
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
378

pixhawk's avatar
pixhawk committed
379 380 381
                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);
382 383 384
                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
385 386 387
                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
388 389 390 391
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
392
            //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
393
            {
pixhawk's avatar
pixhawk committed
394 395
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
396
                quint64 time = getUnixTime(attitude.usec);
397 398 399 400 401 402 403 404

                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);
405 406 407
                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);
408 409

                // Emit in angles
410 411 412 413 414 415 416 417 418 419 420

                // 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
421
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
422 423 424
                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);
425

426 427
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
428 429
            }
            break;
430 431 432 433 434 435 436 437 438 439 440 441 442
            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);
lm's avatar
lm committed
443
                emit altitudeChanged(uasId, hud.alt);
444 445
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
lm's avatar
lm committed
446
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
447 448 449 450 451 452 453 454 455 456 457 458 459 460 461
            }
            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);
lm's avatar
lm committed
462
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
463 464
            }
            break;
465
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
466
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
467
            //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
468
            {
469 470
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
471
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
472 473 474
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
475 476 477 478 479 480
                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
481
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
482
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
483

484 485
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
486

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

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

572 573
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
574

lm's avatar
lm committed
575
                if (pos.fix_type > 0)
576
                {
Laurens Mackay's avatar
Laurens Mackay committed
577
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
578
                    emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time);
lm's avatar
lm committed
579 580 581 582 583 584 585 586

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

                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);
680 681
            }
            break;
pixhawk's avatar
pixhawk committed
682
        case MAVLINK_MSG_ID_DEBUG:
683
            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
684
            break;
685 686 687 688 689
        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
690
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
691 692 693
                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);
694 695 696 697 698 699
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
700
                quint64 time = MG::TIME::getGroundTimeNow();
701
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
702 703 704
                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);
705 706
            }
            break;
pixhawk's avatar
pixhawk committed
707 708 709 710
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
711 712 713 714
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
715 716 717
            }
            break;

718
        case MAVLINK_MSG_ID_WAYPOINT:
719
            {
720 721
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
722
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
723 724 725 726
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
727
            }
pixhawk's avatar
pixhawk committed
728
            break;
pixhawk's avatar
pixhawk committed
729

730 731 732 733 734 735 736 737 738 739 740
        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
741 742 743 744
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
745 746 747 748
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
749 750 751
            }
            break;

752
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
753
            {
pixhawk's avatar
pixhawk committed
754 755 756
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
757
                GAudioOutput::instance()->say(QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq));
758
            }
pixhawk's avatar
pixhawk committed
759
            break;
pixhawk's avatar
pixhawk committed
760

761
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
762
            {
763 764 765
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
766
            }
pixhawk's avatar
pixhawk committed
767
            break;
pixhawk's avatar
pixhawk committed
768

769 770 771 772 773 774 775
        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;
776 777 778 779 780 781 782 783 784 785 786 787 788 789 790
        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;
791
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
792 793 794
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
795
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
796 797
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
798
                int severity = mavlink_msg_statustext_get_severity(&message);
799
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
800
                //emit statusTextReceived(severity, text);
801
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
802 803
            }
            break;
804 805 806 807 808 809
    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);
810 811 812
                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);
813 814
            }
            break;
815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830
            //#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
831
#ifdef MAVLINK_ENABLED_UALBERTA
832 833 834 835 836
        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();
837 838 839 840 841 842
                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);
843 844
            }
            break;
845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868
       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];

869
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
870 871 872 873 874
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

875
#endif
876 877 878
            // Messages to ignore
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
            break;
pixhawk's avatar
pixhawk committed
879
        default:
lm's avatar
lm committed
880 881 882 883
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
884
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
885 886
                    GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
887
                    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
888 889 890
                    //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
891 892 893 894 895
            break;
        }
    }
}

896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925
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
926 927
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
928
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
929
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
930 931
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
932
#else
lm's avatar
lm committed
933 934 935 936
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
937
#endif
pixhawk's avatar
pixhawk committed
938 939
}

pixhawk's avatar
pixhawk committed
940 941
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
942
#ifdef MAVLINK_ENABLED_PIXHAWK
943 944 945
    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
946
#else
947 948 949 950
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
951 952 953 954 955
#endif
}

void UAS::startRadioControlCalibration()
{
956 957 958
    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
959 960
}

lm's avatar
lm committed
961 962
void UAS::startDataRecording()
{
963 964 965
    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
966 967 968 969
}

void UAS::pauseDataRecording()
{
970 971 972
    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
973 974 975 976
}

void UAS::stopDataRecording()
{
977 978 979
    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
980 981
}

pixhawk's avatar
pixhawk committed
982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002
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);
}

1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024
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
1025
#ifndef _MSC_VER
1026
    else if (time < 1261440000000000LLU)
1027
#else
1028
        else if (time < 1261440000000000)
1029
#endif
1030
        {
1031 1032
        if (onboardTimeOffset == 0)
        {
1033
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
1034
        }
1035
        return time/1000 + onboardTimeOffset;
1036 1037 1038 1039 1040
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1041
        return time/1000;
1042 1043 1044
    }
}

1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061
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
1062
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1063
{
lm's avatar
lm committed
1064
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1065
    {
1066
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1067
        mavlink_message_t msg;
lm's avatar
lm committed
1068
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1069
        sendMessage(msg);
lm's avatar
lm committed
1070
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1071
    }
pixhawk's avatar
pixhawk committed
1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083
}

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

1084 1085 1086 1087
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1088

1089 1090
    foreach(LinkInterface* link, link_list)
    {
1091
        if (link)
1092
        {
1093 1094
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1095
            {
1096 1097

                for(int i=0;i<links->size();i++)
1098
                {
1099 1100
                    if(serial != links->at(i))
                    {
1101
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1102 1103
                        sendMessage(serial, message);
                    }
1104 1105 1106 1107 1108 1109
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1110 1111
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1112
    if(!link) return;
pixhawk's avatar
pixhawk committed
1113 1114 1115
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1116
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1117
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128
    // 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
 */
1129
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1130
{
1131
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1132 1133 1134 1135 1136 1137
}

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



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1186
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1187 1188 1189 1190 1191 1192 1193 1194
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1195
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1196 1197 1198 1199
{
    return commStatus;
}

1200 1201 1202
void UAS::requestParameters()
{
    mavlink_message_t msg;
1203
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1204 1205
    // Send message twice to increase chance of reception
    sendMessage(msg);
1206 1207
}

1208
void UAS::writeParametersToStorage()
1209
{
1210 1211 1212
    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
1213
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1214 1215 1216 1217 1218 1219 1220 1221 1222
    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
1223 1224
}

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

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

1273
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1274
{
1275 1276 1277 1278
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1279
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1280
    // Select the update rate in Hz the message should be send
1281
    stream.req_message_rate = rate;
1282
    // Start / stop the message
1283
    stream.start_stop = (rate) ? 1 : 0;
1284 1285 1286 1287 1288 1289
    // 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);
1290 1291
    // Send message twice to increase chance of reception
    sendMessage(msg);
1292
    sendMessage(msg);
lm's avatar
lm committed
1293
}
1294

1295
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1296
{
1297 1298 1299 1300 1301
#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
1302 1303 1304
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1305
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1306
    // Select the update rate in Hz the message should be send
1307
    stream.req_message_rate = rate;
1308
    // Start / stop the message
1309
    stream.start_stop = (rate) ? 1 : 0;
1310 1311 1312 1313 1314 1315
    // 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);
1316 1317
    // Send message twice to increase chance of reception
    sendMessage(msg);
1318
    sendMessage(msg);
1319
#endif
lm's avatar
lm committed
1320 1321
}

1322
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1323
{
1324 1325 1326 1327
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1328
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1329
    // Select the update rate in Hz the message should be send
1330
    stream.req_message_rate = rate;
1331
    // Start / stop the message
1332
    stream.start_stop = (rate) ? 1 : 0;
1333 1334 1335 1336 1337 1338
    // 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);
1339 1340
    // Send message twice to increase chance of reception
    sendMessage(msg);
1341
    sendMessage(msg);
lm's avatar
lm committed
1342 1343
}

lm's avatar
lm committed
1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364
//void UAS::enableRawSensorFusionTransmission(int rate)
//{
//    // Buffers to write data to
//    mavlink_message_t msg;
//    mavlink_request_data_stream_t stream;
//    // Select the message to request from now on
//    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
//    // Select the update rate in Hz the message should be send
//    stream.req_message_rate = rate;
//    // Start / stop the message
//    stream.start_stop = (rate) ? 1 : 0;
//    // The system which should take this command
//    stream.target_system = uasId;
//    // The component / subsystem which should take this command
//    stream.target_component = 0;
//    // Encode and send the message
//    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
//    sendMessage(msg);
//}
1365

1366
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1367 1368 1369 1370 1371
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1372
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1373
    // Select the update rate in Hz the message should be send
1374
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1375
    // Start / stop the message
1376
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387
    // 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);
}

1388
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1389 1390 1391 1392 1393
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1394
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1395
    // Select the update rate in Hz the message should be send
1396
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1397
    // Start / stop the message
1398
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409
    // 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);
}

1410
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1411 1412 1413 1414 1415
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1416
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1417
    // Select the update rate in Hz the message should be send
1418
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1419
    // Start / stop the message
1420
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431
    // 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);
}

1432
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1433 1434 1435 1436 1437
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1438
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1439
    // Select the update rate in Hz the message should be send
1440
    stream.req_message_rate = rate;
1441
    // Start / stop the message
1442
    stream.start_stop = (rate) ? 1 : 0;
1443 1444 1445 1446 1447 1448
    // 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);
1449 1450
    // Send message twice to increase chance of reception
    sendMessage(msg);
1451
    sendMessage(msg);
1452 1453
}

lm's avatar
lm committed
1454 1455 1456 1457 1458 1459 1460
/**
 * 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
1461 1462 1463 1464
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1465 1466 1467
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1468 1469
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1470

1471
    // Copy string into buffer, ensuring not to exceed the buffer size    
1472
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1473
    {
lm's avatar
lm committed
1474
        // String characters
1475
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1476
        {
1477
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1478 1479
        }
        // Null termination at end of string or end of buffer
1480
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1481 1482 1483 1484 1485 1486 1487 1488
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1489
    }    
1490
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1491
    sendMessage(msg);
lm's avatar
lm committed
1492
    }
1493 1494
}

1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513
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);
}

1514 1515 1516
void UAS::setUASName(const QString& name)
{
    this->name = name;
1517
    writeSettings();
1518
    emit nameChanged(name);
1519
    emit systemSpecsChanged(uasId);
1520 1521
}

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

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1555
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1556
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1557
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1558 1559 1560
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1561 1562 1563 1564 1565 1566 1567 1568
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1569
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1570
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1571
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1572 1573 1574
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588
}

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;

1589 1590 1591 1592 1593 1594
    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
1595

1596 1597 1598 1599 1600 1601
        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
1602 1603
}

1604 1605 1606 1607 1608
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1609 1610 1611 1612 1613
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1614

pixhawk's avatar
pixhawk committed
1615 1616
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1617

pixhawk's avatar
pixhawk committed
1618 1619 1620 1621 1622
        break;
    default:

        break;
    }
1623
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1624 1625 1626

}

1627

1628
/*void UAS::requestWaypoints()
1629 1630 1631 1632 1633
{
//    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
1634 1635
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1636 1637
}

pixhawk's avatar
pixhawk committed
1638 1639
void UAS::setWaypoint(Waypoint* wp)
{
1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657
//    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
1658 1659 1660 1661
}

void UAS::setWaypointActive(int id)
{
1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684
//    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!";
1685
}*/
pixhawk's avatar
pixhawk committed
1686 1687 1688 1689


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

void UAS::go()
{
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_CONTINUE);
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
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1711
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1712
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1713
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1714 1715 1716
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1717 1718 1719 1720 1721 1722 1723 1724
}

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

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

1795 1796
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1797 1798 1799 1800 1801 1802
    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);
1803 1804
}

pixhawk's avatar
pixhawk committed
1805 1806 1807
/**
 * @return The name of this system as string in human-readable form
 */
1808
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826
{
    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);
1827
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1828 1829
    }
    //links->append(link);
1830
    //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
1831 1832
}

1833 1834 1835 1836 1837 1838 1839 1840 1841
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858
/**
 * @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
1859
    case NICD:
pixhawk's avatar
pixhawk committed
1860
        break;
lm's avatar
lm committed
1861
    case NIMH:
pixhawk's avatar
pixhawk committed
1862
        break;
lm's avatar
lm committed
1863
    case LIION:
pixhawk's avatar
pixhawk committed
1864
        break;
lm's avatar
lm committed
1865
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1866 1867 1868
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1869
    case LIFE:
pixhawk's avatar
pixhawk committed
1870
        break;
lm's avatar
lm committed
1871
    case AGZN:
pixhawk's avatar
pixhawk committed
1872 1873 1874 1875
        break;
    }
}

1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902
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
1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915
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
1916 1917 1918
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1919 1920
double UAS::getChargeLevel()
{
1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934
    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
1935 1936
}

lm's avatar
lm committed
1937 1938 1939 1940
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1941
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
1942
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954
        lowBattAlarm = true;
    }
}

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