UAS.cc 76.5 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
warnLevelPercent(20.0f),
45 46
currentVoltage(12.0f),
lpVoltage(12.0f),
47
batteryRemainingEstimateEnabled(false),
48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72
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)),
73 74
paramsOnceRequested(false),
airframe(0)
pixhawk's avatar
pixhawk committed
75
{
76
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
77
    setBattery(LIPOLY, 3);
78
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
79
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
80
    statusTimeout->start(500);
81
    readSettings();
pixhawk's avatar
pixhawk committed
82 83 84 85
}

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
147 148
void UAS::setSelected()
{
149 150 151 152 153 154 155 156 157 158
    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
159 160
}

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
243
                // FIXME
244
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
245

246
                QString audiostring = "System " + getUASName();
pixhawk's avatar
pixhawk committed
247 248 249 250
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
251

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

lm's avatar
lm committed
262
                emit loadChanged(this,state.load/10.0f);
lm's avatar
lm committed
263
                emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
lm's avatar
lm committed
264

lm's avatar
lm committed
265
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
266 267
                {
                    modechanged = true;
lm's avatar
lm committed
268
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
269 270
                    QString mode;

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

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
308
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
309
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
310 311
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
312 313 314 315
                if (!batteryRemainingEstimateEnabled)
                {
                    chargeLevel = state.battery_remaining/10.0f;
                }
pixhawk's avatar
pixhawk committed
316
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
317
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
318
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
319

lm's avatar
lm committed
320
                // LOW BATTERY ALARM
321
                if (lpVoltage < warnVoltage)
lm's avatar
lm committed
322 323 324 325 326 327 328 329
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
330
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
331
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
332
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
333 334

                // AUDIO
pixhawk's avatar
pixhawk committed
335 336 337 338 339 340 341 342 343 344
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
345
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
346 347 348 349 350 351 352 353
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
354 355 356 357 358 359

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
360 361
            }
            break;
James Goppert's avatar
James Goppert committed
362 363

        #ifdef MAVLINK_ENABLED_PIXHAWK
364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379
        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;
lm's avatar
lm committed
380
#endif // PIXHAWK
pixhawk's avatar
pixhawk committed
381
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
382
            {
pixhawk's avatar
pixhawk committed
383 384
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
385
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
386

pixhawk's avatar
pixhawk committed
387 388 389
                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);
390 391 392
                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
393 394 395
                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
396 397
            }
            break;
lm's avatar
lm committed
398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414
         case MAVLINK_MSG_ID_SCALED_IMU:
            {
                mavlink_scaled_imu_t scaled;
                mavlink_msg_scaled_imu_decode(&message, &scaled);
                quint64 time = getUnixTime(scaled.usec);

                emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time);
                emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time);
                emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time);
                emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time);
                emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time);
                emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time);
                emit valueChanged(uasId, "mag x", "tesla", scaled.xmag/1000.0f, time);
                emit valueChanged(uasId, "mag y", "tesla", scaled.ymag/1000.0f, time);
                emit valueChanged(uasId, "mag z", "tesla", scaled.zmag/1000.0f, time);
            }
            break;
pixhawk's avatar
pixhawk committed
415 416
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
417
            //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
418
            {
pixhawk's avatar
pixhawk committed
419 420
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
421
                quint64 time = getUnixTime(attitude.usec);
422 423 424 425 426 427 428 429

                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);
430 431 432
                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);
433 434

                // Emit in angles
435 436 437 438 439 440 441 442 443 444 445

                // 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
446
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
447 448 449
                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);
450

451 452
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
453 454
            }
            break;
455 456 457 458 459 460 461 462 463 464 465
            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);
466
                emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
467
                emit thrustChanged(this, hud.throttle/100.0);
lm's avatar
lm committed
468
                emit altitudeChanged(uasId, hud.alt);
469 470
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
lm's avatar
lm committed
471
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
472 473 474 475 476 477 478 479 480 481 482 483 484 485 486
            }
            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
487
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
488 489
            }
            break;
490
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
491
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
492
            //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
493
            {
494 495
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
496
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
497 498 499
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
500 501 502 503 504 505
                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
506
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
507
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
508

509 510
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
511

512
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
513 514 515 516 517 518 519
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
520 521
            }
            break;
522
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
523 524 525
            //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;
            {
526 527
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
528
                quint64 time = QGC::groundTimeUsecs()/1000;
529 530 531 532 533 534
                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;
535 536 537 538 539 540
                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);
541
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568
                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);
569 570
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
571 572
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
573
                emit valueChanged(uasId, "gpsspeed", "m/s", sqrt(speedX*speedX+speedY*speedY+speedZ*speedZ), time);
pixhawk's avatar
pixhawk committed
574 575 576 577 578 579 580
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
581 582
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
583 584 585 586 587 588 589 590
            }
            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);
591 592 593

                // SANITY CHECK
                // only accept values in a realistic range
594
                // quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
595
                quint64 time = getUnixTime();
lm's avatar
lm committed
596

597 598
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
599

lm's avatar
lm committed
600
                if (pos.fix_type > 0)
601
                {
Laurens Mackay's avatar
Laurens Mackay committed
602
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
603
                    emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time);
lm's avatar
lm committed
604 605 606 607 608 609 610 611

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
612
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
613 614 615
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
616
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
617
                        //qDebug() << "GOT GPS RAW";
618
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
619 620 621 622 623
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
624
                }
625 626
            }
            break;
lm's avatar
lm committed
627 628 629 630
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
631
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
632
                {
lm's avatar
lm committed
633
                    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
634 635 636
                }
            }
            break;
637 638 639 640 641 642 643
        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;
644 645 646 647
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
648
                quint64 time = this->getUnixTime(pressure.usec);
649 650 651
                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);
652
                emit valueChanged(uasId, "temperature", "deg C", pressure.temperature/100.0f, time);
653 654
            }
            break;
655
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
656
            {
657 658
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
659
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682
                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
683 684
            }
            break;
685 686 687 688
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
689 690
                QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
                QString parameterName = QString(bytes);
691 692 693 694 695 696 697 698 699 700 701 702 703 704 705
                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);
lm's avatar
lm committed
706 707 708 709 710 711 712 713 714 715 716 717 718
                emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
            }
            break;
        case MAVLINK_MSG_ID_ACTION_ACK:
            mavlink_action_ack_t ack;
            mavlink_msg_action_ack_decode(&message, &ack);
            if (ack.result == 1)
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed action: %1").arg(ack.action));
            }
            else
            {
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected action: %1").arg(ack.action));
719 720
            }
            break;
pixhawk's avatar
pixhawk committed
721
        case MAVLINK_MSG_ID_DEBUG:
722
            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
723
            break;
724 725 726 727 728
        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
729
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
730 731 732
                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);
733 734 735 736 737 738
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
739
                quint64 time = MG::TIME::getGroundTimeNow();
740
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
741 742 743
                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);
744 745
            }
            break;
pixhawk's avatar
pixhawk committed
746 747 748 749
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
750 751 752 753
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
754 755 756
            }
            break;

757
        case MAVLINK_MSG_ID_WAYPOINT:
758
            {
759 760
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
761
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
762 763 764 765
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
766
            }
pixhawk's avatar
pixhawk committed
767
            break;
pixhawk's avatar
pixhawk committed
768

769 770 771 772 773 774 775 776 777 778 779
        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
780 781 782 783
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
784 785 786 787
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
788 789 790
            }
            break;

791
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
792
            {
pixhawk's avatar
pixhawk committed
793 794 795
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
796
                GAudioOutput::instance()->say(QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq));
797
            }
pixhawk's avatar
pixhawk committed
798
            break;
pixhawk's avatar
pixhawk committed
799

800
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
801
            {
802 803 804
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
805
            }
pixhawk's avatar
pixhawk committed
806
            break;
pixhawk's avatar
pixhawk committed
807

808 809 810 811 812 813 814
        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;
815 816 817 818 819 820 821 822 823 824 825 826 827 828 829
        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;
830
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
831 832
            {
                QByteArray b;
lm's avatar
lm committed
833
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
pixhawk's avatar
pixhawk committed
834
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
835 836
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
837
                int severity = mavlink_msg_statustext_get_severity(&message);
838
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
839
                //emit statusTextReceived(severity, text);
840
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
841 842
            }
            break;
843 844 845 846 847 848
    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);
849 850 851
                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);
852 853
            }
            break;
854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869
            //#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
870
#ifdef MAVLINK_ENABLED_UALBERTA
871 872 873 874 875
        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();
876 877 878 879 880 881
                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);
882 883
            }
            break;
884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907
       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];

908
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
909 910 911 912 913
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

914
#endif
915 916 917
            // Messages to ignore
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
            break;
pixhawk's avatar
pixhawk committed
918
        default:
lm's avatar
lm committed
919 920 921 922
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
923
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
924 925
                    GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
926
                    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
927 928 929
                    //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
930 931 932 933 934
            break;
        }
    }
}

935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964
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
965 966
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
967
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
968
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
969 970
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
971
#else
lm's avatar
lm committed
972 973 974 975
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
976
#endif
pixhawk's avatar
pixhawk committed
977 978
}

pixhawk's avatar
pixhawk committed
979 980
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
981
#ifdef MAVLINK_ENABLED_PIXHAWK
982 983 984
    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
985
#else
986 987 988 989
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
990 991 992 993 994
#endif
}

void UAS::startRadioControlCalibration()
{
995 996 997
    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
998 999
}

lm's avatar
lm committed
1000 1001
void UAS::startDataRecording()
{
1002 1003 1004
    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
1005 1006 1007 1008
}

void UAS::pauseDataRecording()
{
1009 1010 1011
    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
1012 1013 1014 1015
}

void UAS::stopDataRecording()
{
1016 1017 1018
    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
1019 1020
}

pixhawk's avatar
pixhawk committed
1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041
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);
}

1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063
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
1064
#ifndef _MSC_VER
1065
    else if (time < 1261440000000000LLU)
1066
#else
1067
        else if (time < 1261440000000000)
1068
#endif
1069
        {
1070 1071
        if (onboardTimeOffset == 0)
        {
1072
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
1073
        }
1074
        return time/1000 + onboardTimeOffset;
1075 1076 1077 1078 1079
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1080
        return time/1000;
1081 1082 1083
    }
}

1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100
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
1101
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1102
{
lm's avatar
lm committed
1103
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1104
    {
1105
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1106
        mavlink_message_t msg;
lm's avatar
lm committed
1107
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1108
        sendMessage(msg);
lm's avatar
lm committed
1109
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1110
    }
pixhawk's avatar
pixhawk committed
1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122
}

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

1123 1124 1125 1126
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1127

1128 1129
    foreach(LinkInterface* link, link_list)
    {
1130
        if (link)
1131
        {
1132 1133
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1134
            {
1135 1136

                for(int i=0;i<links->size();i++)
1137
                {
1138 1139
                    if(serial != links->at(i))
                    {
1140
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1141 1142
                        sendMessage(serial, message);
                    }
1143 1144 1145 1146 1147 1148
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1149 1150
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1151
    if(!link) return;
pixhawk's avatar
pixhawk committed
1152 1153 1154
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1155
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1156
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167
    // 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
 */
1168
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1169
{
1170
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1171 1172 1173 1174 1175 1176
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1177
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1178
        uasState = tr("UNINIT");
1179
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
1180
        break;
lm's avatar
lm committed
1181
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1182
        uasState = tr("BOOT");
1183
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
1184
        break;
lm's avatar
lm committed
1185
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1186
        uasState = tr("CALIBRATING");
1187
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
1188
        break;
lm's avatar
lm committed
1189
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1190
        uasState = tr("ACTIVE");
1191
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
1192
        break;
lm's avatar
lm committed
1193 1194
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1195
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
1196 1197
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1198
        uasState = tr("CRITICAL");
1199
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
1200
        break;
lm's avatar
lm committed
1201
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1202
        uasState = tr("EMERGENCY");
1203
        stateDescription = tr("EMERGENCY: Land!");
pixhawk's avatar
pixhawk committed
1204
        break;
lm's avatar
lm committed
1205
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1206
        uasState = tr("SHUTDOWN");
1207
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
1208
        break;
lm's avatar
lm committed
1209
    default:
pixhawk's avatar
pixhawk committed
1210
        uasState = tr("UNKNOWN");
1211
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1225
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1226 1227 1228 1229 1230 1231 1232 1233
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1234
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1235 1236 1237 1238
{
    return commStatus;
}

1239 1240 1241
void UAS::requestParameters()
{
    mavlink_message_t msg;
1242
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1243 1244
    // Send message twice to increase chance of reception
    sendMessage(msg);
1245 1246
}

1247
void UAS::writeParametersToStorage()
1248
{
1249 1250 1251
    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
1252
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1253 1254 1255 1256 1257 1258 1259 1260 1261
    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
1262 1263
}

1264
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1265 1266
{
    // Buffers to write data to
1267
    mavlink_message_t msg;
1268
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1269 1270
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1271
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1272 1273
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1274 1275
    // 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
1276 1277
    stream.req_message_rate = 0;
    // Start / stop the message
1278
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1279 1280 1281 1282 1283
    // 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
1284
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1285 1286
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1287 1288 1289
    sendMessage(msg);
}

1290
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1291 1292 1293
{
    // Buffers to write data to
    mavlink_message_t msg;
1294
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1295
    // Select the message to request from now on
1296
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1297
    // Select the update rate in Hz the message should be send
1298
    stream.req_message_rate = rate;
lm's avatar
lm committed
1299
    // Start / stop the message
1300
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1301 1302 1303 1304 1305
    // 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
1306
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1307 1308
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1309 1310 1311
    sendMessage(msg);
}

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

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

1361
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1362
{
1363 1364 1365 1366
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1367
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1368
    // Select the update rate in Hz the message should be send
1369
    stream.req_message_rate = rate;
1370
    // Start / stop the message
1371
    stream.start_stop = (rate) ? 1 : 0;
1372 1373 1374 1375 1376 1377
    // 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);
1378 1379
    // Send message twice to increase chance of reception
    sendMessage(msg);
1380
    sendMessage(msg);
lm's avatar
lm committed
1381 1382
}

lm's avatar
lm committed
1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403
//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);
//}
1404

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

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

1449
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1450 1451 1452 1453 1454
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1455
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1456
    // Select the update rate in Hz the message should be send
1457
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1458
    // Start / stop the message
1459
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470
    // 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);
}

1471
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1472 1473 1474 1475 1476
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1477
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1478
    // Select the update rate in Hz the message should be send
1479
    stream.req_message_rate = rate;
1480
    // Start / stop the message
1481
    stream.start_stop = (rate) ? 1 : 0;
1482 1483 1484 1485 1486 1487
    // 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);
1488 1489
    // Send message twice to increase chance of reception
    sendMessage(msg);
1490
    sendMessage(msg);
1491 1492
}

lm's avatar
lm committed
1493 1494 1495 1496 1497 1498 1499
/**
 * 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
1500 1501 1502 1503
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1504 1505 1506
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1507 1508
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1509

1510
    // Copy string into buffer, ensuring not to exceed the buffer size    
1511
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1512
    {
lm's avatar
lm committed
1513
        // String characters
1514
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1515
        {
1516
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1517 1518
        }
        // Null termination at end of string or end of buffer
1519
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1520 1521 1522 1523 1524 1525 1526 1527
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1528
    }    
1529
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1530
    sendMessage(msg);
lm's avatar
lm committed
1531
    }
1532 1533
}

1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552
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);
}

1553 1554 1555
void UAS::setUASName(const QString& name)
{
    this->name = name;
1556
    writeSettings();
1557
    emit nameChanged(name);
1558
    emit systemSpecsChanged(uasId);
1559 1560
}

1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573
/**
 * 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
1574
/**
lm's avatar
lm committed
1575
 * Launches the system
pixhawk's avatar
pixhawk committed
1576 1577 1578 1579
 *
 **/
void UAS::launch()
{
1580
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1581
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1582
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
1583 1584 1585
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1586 1587 1588 1589 1590 1591 1592 1593
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1594
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1595
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1596
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1597 1598 1599
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1600 1601 1602 1603 1604 1605 1606 1607
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1608
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1609
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1610
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1611 1612 1613
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627
}

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;

1628 1629 1630 1631 1632 1633
    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
1634

1635 1636 1637 1638 1639 1640
        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
1641 1642
}

1643 1644 1645 1646 1647
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1648 1649 1650 1651 1652
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1653

pixhawk's avatar
pixhawk committed
1654 1655
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1656

pixhawk's avatar
pixhawk committed
1657 1658 1659 1660 1661
        break;
    default:

        break;
    }
1662
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1663 1664 1665

}

1666

1667
/*void UAS::requestWaypoints()
1668 1669 1670 1671 1672
{
//    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
1673 1674
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1675 1676
}

pixhawk's avatar
pixhawk committed
1677 1678
void UAS::setWaypoint(Waypoint* wp)
{
1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696
//    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
1697 1698 1699 1700
}

void UAS::setWaypointActive(int id)
{
1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723
//    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!";
1724
}*/
pixhawk's avatar
pixhawk committed
1725 1726 1727 1728


void UAS::halt()
{
1729
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1730
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1731
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1732 1733 1734
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1735 1736 1737 1738
}

void UAS::go()
{
1739
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1740
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1741
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1742 1743 1744
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1745 1746 1747 1748 1749
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1750
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1751
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1752
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1753 1754 1755
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1756 1757 1758 1759 1760 1761 1762 1763
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1764
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1765
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1766
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1767 1768 1769
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794
}

/**
 * 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)
    {
1795
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1796
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1797
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1798 1799 1800
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823
        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
1824
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1825
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1826
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1827 1828 1829
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1830 1831 1832 1833
        result = true;
    }
}

1834 1835
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1836 1837 1838 1839 1840 1841
    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);
1842 1843
}

pixhawk's avatar
pixhawk committed
1844 1845 1846
/**
 * @return The name of this system as string in human-readable form
 */
1847
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865
{
    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);
1866
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1867 1868
    }
    //links->append(link);
1869
    //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
1870 1871
}

1872 1873 1874 1875 1876 1877 1878 1879 1880
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897
/**
 * @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
1898
    case NICD:
pixhawk's avatar
pixhawk committed
1899
        break;
lm's avatar
lm committed
1900
    case NIMH:
pixhawk's avatar
pixhawk committed
1901
        break;
lm's avatar
lm committed
1902
    case LIION:
pixhawk's avatar
pixhawk committed
1903
        break;
lm's avatar
lm committed
1904
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1905 1906 1907
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1908
    case LIFE:
pixhawk's avatar
pixhawk committed
1909
        break;
lm's avatar
lm committed
1910
    case AGZN:
pixhawk's avatar
pixhawk committed
1911 1912 1913 1914
        break;
    }
}

1915 1916
void UAS::setBatterySpecs(const QString& specs)
{
1917
    if (specs.length() == 0 || specs.contains("%"))
1918
    {
1919
        batteryRemainingEstimateEnabled = false;
1920
        bool ok;
1921 1922 1923
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
1924 1925 1926 1927 1928 1929 1930 1931
        if (ok)
        {
            warnLevelPercent = temp;
        }
        else
        {
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953
    }
    else
    {
        batteryRemainingEstimateEnabled = true;
        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;
        }
1954 1955 1956 1957
        else
        {
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
1958 1959 1960 1961 1962
    }
}

QString UAS::getBatterySpecs()
{
1963 1964 1965 1966 1967 1968 1969 1970
    if (batteryRemainingEstimateEnabled)
    {
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
    }
    else
    {
        return QString("%1%").arg(warnLevelPercent);
    }
1971 1972
}

pixhawk's avatar
pixhawk committed
1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985
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
1986 1987 1988
/**
 * @return charge level in percent - 0 - 100
 */
1989
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
1990
{
1991
    if (batteryRemainingEstimateEnabled)
1992
    {
1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004
        if (lpVoltage < emptyVoltage)
        {
            chargeLevel = 0.0f;
        }
        else if (lpVoltage > fullVoltage)
        {
            chargeLevel = 100.0f;
        }
        else
        {
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2005 2006
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2007 2008
}

lm's avatar
lm committed
2009 2010 2011 2012
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
2013
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2014
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026
        lowBattAlarm = true;
    }
}

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