UAS.cc 83 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
uasId(id),
32
startTime(QGC::groundTimeMilliseconds()),
33 34 35 36 37 38 39 40 41 42
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
mode(-1),
status(-1),
navMode(-1),
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73
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)),
74
paramsOnceRequested(false),
lm's avatar
lm committed
75
airframe(0),
76 77
attitudeKnown(false),
paramManager(NULL)
pixhawk's avatar
pixhawk committed
78
{
79
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
80
    setBattery(LIPOLY, 3);
81
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
82
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
83
    statusTimeout->start(500);
84
    readSettings();
pixhawk's avatar
pixhawk committed
85 86 87 88
}

UAS::~UAS()
{
89
    writeSettings();
pixhawk's avatar
pixhawk committed
90
    delete links;
91
    links=NULL;
pixhawk's avatar
pixhawk committed
92 93
}

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

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

120
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
121 122 123 124
{
    return uasId;
}

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
197 198 199 200
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
pixhawk's avatar
pixhawk committed
201

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

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

pixhawk's avatar
pixhawk committed
246
                // FIXME
247
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
248

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

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

265 266 267 268 269 270
                if (navMode != state.nav_mode)
                {
                    emit navModeChanged(uasId, state.nav_mode, getNavModeText(state.nav_mode));
                    navMode = state.nav_mode;
                }

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

274
                if (this->mode != static_cast<int>(state.mode))
pixhawk's avatar
pixhawk committed
275 276
                {
                    modechanged = true;
277
                    this->mode = static_cast<int>(state.mode);
pixhawk's avatar
pixhawk committed
278 279
                    QString mode;

lm's avatar
lm committed
280
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
281
                    {
lm's avatar
lm committed
282
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
283 284
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
285
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
286 287
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
288
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
289 290
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
291
                    case (uint8_t)MAV_MODE_GUIDED:
292 293
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
294
                    case (uint8_t)MAV_MODE_READY:
295
                        mode = "READY MODE";
lm's avatar
lm committed
296
                        break;
lm's avatar
lm committed
297
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
298 299
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
300
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
301 302
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
303
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
304 305
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
306 307 308
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
309 310 311 312 313 314 315 316
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
317
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
318
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
319 320
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
321 322 323 324
                if (!batteryRemainingEstimateEnabled)
                {
                    chargeLevel = state.battery_remaining/10.0f;
                }
pixhawk's avatar
pixhawk committed
325
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
326
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
327
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
328

lm's avatar
lm committed
329
                // LOW BATTERY ALARM
330
                if (lpVoltage < warnVoltage)
lm's avatar
lm committed
331 332 333 334 335 336 337 338
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
339
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
340
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
341
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
342 343

                // AUDIO
pixhawk's avatar
pixhawk committed
344 345 346 347 348 349 350 351 352 353
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
354
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
355 356 357 358 359 360 361 362
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
363 364 365 366 367 368

                if (state.status == MAV_STATE_POWEROFF)
                {
                    emit systemRemoved(this);
                    emit systemRemoved();
                }
pixhawk's avatar
pixhawk committed
369 370
            }
            break;
James Goppert's avatar
James Goppert committed
371 372

        #ifdef MAVLINK_ENABLED_PIXHAWK
373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388
        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
389
#endif // PIXHAWK
pixhawk's avatar
pixhawk committed
390
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
391
            {
pixhawk's avatar
pixhawk committed
392 393
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
394
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
395

pixhawk's avatar
pixhawk committed
396 397 398
                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);
399 400 401
                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
402 403 404
                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
405 406
            }
            break;
lm's avatar
lm committed
407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423
         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
424 425
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
426
            //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
427
            {
pixhawk's avatar
pixhawk committed
428 429
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
430
                quint64 time = getUnixTime(attitude.usec);
431 432 433 434 435 436 437 438

                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);
439 440 441
                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);
442 443

                // Emit in angles
lm's avatar
lm committed
444

445 446 447 448
                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
                while (compass > 360.0f)
lm's avatar
lm committed
449
                {
450
                    compass -= 360.0f;
lm's avatar
lm committed
451 452
                }

lm's avatar
lm committed
453 454
                attitudeKnown = true;

455 456
                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
457
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
458 459 460
                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);
461

462 463
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
464 465
            }
            break;
466 467 468 469 470 471 472 473 474 475 476
            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);
477
                emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
478
                emit thrustChanged(this, hud.throttle/100.0);
lm's avatar
lm committed
479 480 481 482 483 484 485

                if (!attitudeKnown)
                {
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }

lm's avatar
lm committed
486
                emit altitudeChanged(uasId, hud.alt);
487 488
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
lm's avatar
lm committed
489
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
490 491 492 493 494 495 496 497 498 499 500 501 502 503 504
            }
            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
505
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
pixhawk's avatar
pixhawk committed
506 507
            }
            break;
508
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
509
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
510
            //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
511
            {
512 513
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
514
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
515 516 517
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
518 519 520 521 522 523
                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
524
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
525
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
526

527 528
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
529

530
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
531 532 533 534 535 536 537
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
538 539
            }
            break;
540
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
541 542 543
            //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;
            {
544 545
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
546
                quint64 time = QGC::groundTimeUsecs()/1000;
547 548 549 550 551 552
                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;
553 554 555
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
556 557
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
558
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584
                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);
585 586
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
587
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
588
                emit speedChanged(this, speedX, speedY, speedZ, time);
pixhawk's avatar
pixhawk committed
589 590 591 592 593 594 595
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
596 597
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
598 599 600 601 602 603 604 605
            }
            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);
606 607 608

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

612 613
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
614

lm's avatar
lm committed
615
                if (pos.fix_type > 0)
616
                {
617
                    emit globalPositionChanged(this, pos.lat, pos.lon, pos.alt, time);
618
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
619 620 621
                    latitude = pos.lat;
                    longitude = pos.lon;
                    altitude = pos.alt;
lm's avatar
lm committed
622
                    positionLock = true;
lm's avatar
lm committed
623 624 625 626 627 628 629 630

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
631
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
632 633 634
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
635
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
636
                        //qDebug() << "GOT GPS RAW";
637
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
638 639 640 641 642
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
643
                }
644 645
            }
            break;
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662
        case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);

                // SANITY CHECK
                // only accept values in a realistic range
                // quint64 time = getUnixTime(pos.usec);
                quint64 time = getUnixTime();

                emit valueChanged(uasId, "latitude", "deg", pos.lat/(double)1E7, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon/(double)1E7, time);

                if (pos.fix_type > 0)
                {
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
663 664 665
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
lm's avatar
lm committed
666
                    positionLock = true;
667 668 669 670 671 672 673 674

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
675
                    emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
676 677 678 679 680 681 682 683 684 685 686 687 688 689
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
                        //qDebug() << "GOT GPS RAW";
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
                }
            }
            break;
lm's avatar
lm committed
690 691 692 693
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
694
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
695
                {
lm's avatar
lm committed
696
                    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
697 698 699
                }
            }
            break;
700 701 702 703 704 705 706
        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;
707 708 709 710
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
711
                quint64 time = this->getUnixTime(pressure.usec);
712 713 714
                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);
715
                emit valueChanged(uasId, "temperature", "deg C", pressure.temperature/100.0f, time);
716 717
            }
            break;
718
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
719
            {
720 721
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
722
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745
                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
746 747
            }
            break;
748 749 750 751
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
752 753
                QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
                QString parameterName = QString(bytes);
754 755 756 757 758 759 760 761 762 763 764 765 766 767 768
                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
769 770 771 772 773 774 775 776 777 778 779 780 781
                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));
782 783
            }
            break;
pixhawk's avatar
pixhawk committed
784
        case MAVLINK_MSG_ID_DEBUG:
785
            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
786
            break;
787 788 789 790 791
        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
792
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
793 794 795
                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);
796 797 798 799 800 801
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
802
                quint64 time = MG::TIME::getGroundTimeNow();
803
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
804 805 806
                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);
807 808
            }
            break;
pixhawk's avatar
pixhawk committed
809 810 811 812
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
813 814 815 816
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
817 818 819
            }
            break;

820
        case MAVLINK_MSG_ID_WAYPOINT:
821
            {
822 823
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
824
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
825 826 827 828
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
829
            }
pixhawk's avatar
pixhawk committed
830
            break;
pixhawk's avatar
pixhawk committed
831

832 833 834 835 836 837 838 839 840 841 842
        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
843 844 845 846
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
847 848 849 850
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
851 852 853
            }
            break;

854
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
855
            {
pixhawk's avatar
pixhawk committed
856 857 858
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
859 860 861
                QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
                GAudioOutput::instance()->say(text);
                emit textMessageReceived(message.sysid, message.compid, 0, text);
862
            }
pixhawk's avatar
pixhawk committed
863
            break;
pixhawk's avatar
pixhawk committed
864

865
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
866
            {
867 868 869
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
870
            }
pixhawk's avatar
pixhawk committed
871
            break;
pixhawk's avatar
pixhawk committed
872

873 874 875 876 877 878 879
        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;
880 881 882 883 884 885 886 887 888 889 890 891 892 893 894
        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;
895
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
896 897
            {
                QByteArray b;
lm's avatar
lm committed
898
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
pixhawk's avatar
pixhawk committed
899
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
900 901
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
902
                int severity = mavlink_msg_statustext_get_severity(&message);
903
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
904
                //emit statusTextReceived(severity, text);
905
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
906 907
            }
            break;
908
#ifdef MAVLINK_ENABLED_PIXHAWK
909 910 911 912 913 914 915 916 917
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
lm's avatar
lm committed
918
                imageStart = QGC::groundTimeMilliseconds();
919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952
            }
            break;

        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
                mavlink_encapsulated_data_t img;
                mavlink_msg_encapsulated_data_decode(&message, &img);
                int seq = img.seqnr;
                int pos = seq * imagePayload;

                for (int i = 0; i < imagePayload; ++i)
                {
                    if (pos <= imageSize)
                    {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }

                ++imagePacketsArrived;

                // emit signal if all packets arrived
                if ((imagePacketsArrived == imagePackets))
                {
                    image.loadFromData(imageRecBuffer);
                    emit imageReady(this);
                    // Restart statemachine
                    imagePacketsArrived = 0;

                    //this->requestImage();
                    //qDebug() << "SENDING REQUEST TO GET NEW IMAGE FROM SYSTEM" << uasId;
                }
            }
            break;
953
#endif
954
        case MAVLINK_MSG_ID_DEBUG_VECT:
955 956 957 958 959
            {
                mavlink_debug_vect_t vect;
                mavlink_msg_debug_vect_decode(&message, &vect);
                QString str((const char*)vect.name);
                quint64 time = getUnixTime(vect.usec);
960 961 962
                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);
963 964
            }
            break;
965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980
            //#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
981
#ifdef MAVLINK_ENABLED_UALBERTA
982 983 984 985 986
        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();
987 988 989 990 991 992
                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);
993 994
            }
            break;
995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018
       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];

1019
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
1020 1021 1022 1023 1024
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

1025
#endif
1026 1027 1028
            // Messages to ignore
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
            break;
pixhawk's avatar
pixhawk committed
1029
        default:
lm's avatar
lm committed
1030 1031 1032 1033
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
1034
                    QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
1035 1036
                    GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
                    emit textMessageReceived(uasId, message.compid, 255, errString);
1037
                    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
1038 1039 1040
                    //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
1041 1042 1043 1044 1045
            break;
        }
    }
}

1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059
void UAS::setHomePosition(double lat, double lon, double alt)
{
    // Send new home position to UAS
    mavlink_gps_set_global_origin_t home;
    home.target_system = uasId;
    home.target_component = 0; // ALL components
    home.latitude = lat*1E7;
    home.longitude = lon*1E7;
    home.altitude = alt*1000;
    mavlink_message_t msg;
    mavlink_msg_gps_set_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
    sendMessage(msg);
}

1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077
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;
1078
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
1079 1080 1081 1082 1083 1084 1085 1086 1087 1088
        // 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
1089 1090
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
1091
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
1092
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1093 1094
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
1095
#else
lm's avatar
lm committed
1096 1097 1098 1099
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
1100
#endif
pixhawk's avatar
pixhawk committed
1101 1102
}

pixhawk's avatar
pixhawk committed
1103 1104
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
1105
#ifdef MAVLINK_ENABLED_PIXHAWK
1106 1107 1108
    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
1109
#else
1110 1111 1112 1113
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
1114 1115 1116 1117 1118
#endif
}

void UAS::startRadioControlCalibration()
{
1119 1120 1121
    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
1122 1123
}

lm's avatar
lm committed
1124 1125
void UAS::startDataRecording()
{
1126 1127 1128
    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
1129 1130 1131 1132
}

void UAS::pauseDataRecording()
{
1133 1134 1135
    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
1136 1137 1138 1139
}

void UAS::stopDataRecording()
{
1140 1141 1142
    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
1143 1144
}

pixhawk's avatar
pixhawk committed
1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165
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);
}

1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187
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
1188
#ifndef _MSC_VER
1189
    else if (time < 1261440000000000LLU)
1190
#else
1191
        else if (time < 1261440000000000)
1192
#endif
1193
        {
1194 1195
        if (onboardTimeOffset == 0)
        {
1196
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
1197
        }
1198
        return time/1000 + onboardTimeOffset;
1199 1200 1201 1202 1203
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
1204
        return time/1000;
1205 1206 1207
    }
}

1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224
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
1225
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1226
{
lm's avatar
lm committed
1227
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1228
    {
1229
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1230
        mavlink_message_t msg;
lm's avatar
lm committed
1231
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1232
        sendMessage(msg);
lm's avatar
lm committed
1233
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1234
    }
pixhawk's avatar
pixhawk committed
1235 1236 1237 1238 1239
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
1240
    foreach (LinkInterface* link, *links)
pixhawk's avatar
pixhawk committed
1241
    {
1242 1243 1244 1245 1246 1247 1248 1249 1250
        if (link)
        {
            sendMessage(link, message);
        }
        else
        {
            // Remove from list
            links->removeAt(links->indexOf(link));
        }
pixhawk's avatar
pixhawk committed
1251 1252 1253
    }
}

1254 1255 1256 1257
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1258

1259 1260
    foreach(LinkInterface* link, link_list)
    {
1261
        if (link)
1262
        {
1263 1264
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1265
            {
1266 1267

                for(int i=0;i<links->size();i++)
1268
                {
1269 1270
                    if(serial != links->at(i))
                    {
1271
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1272 1273
                        sendMessage(serial, message);
                    }
1274 1275 1276 1277 1278 1279
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1280 1281
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1282
    if(!link) return;
pixhawk's avatar
pixhawk committed
1283 1284 1285
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1286
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1287
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298
    // 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
 */
1299
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1300
{
1301
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1302 1303
}

1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339
QString UAS::getNavModeText(int mode)
{
    switch (mode)
    {
    case MAV_NAV_GROUNDED:
        return QString("GROUNDED");
        break;
    case MAV_NAV_HOLD:
        return QString("HOLD");
        break;
    case MAV_NAV_LANDING:
        return QString("LANDING");
        break;
    case MAV_NAV_LIFTOFF:
        return QString("LIFTOFF");
        break;
    case MAV_NAV_LOITER:
        return QString("LOITER");
        break;
    case MAV_NAV_LOST:
        return QString("LOST");
        break;
    case MAV_NAV_RETURNING:
        return QString("RETURNING");
        break;
    case MAV_NAV_VECTOR:
        return QString("VECTOR");
        break;
    case MAV_NAV_WAYPOINT:
        return QString("WAYPOINT");
        break;
    default:
        return QString("UNKNOWN");
    }
}

pixhawk's avatar
pixhawk committed
1340 1341 1342 1343
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1344
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1345
        uasState = tr("UNINIT");
1346
        stateDescription = tr("Unitialized, booting up.");
pixhawk's avatar
pixhawk committed
1347
        break;
lm's avatar
lm committed
1348
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1349
        uasState = tr("BOOT");
1350
        stateDescription = tr("Booting system, please wait.");
pixhawk's avatar
pixhawk committed
1351
        break;
lm's avatar
lm committed
1352
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1353
        uasState = tr("CALIBRATING");
1354
        stateDescription = tr("Calibrating sensors, please wait.");
pixhawk's avatar
pixhawk committed
1355
        break;
lm's avatar
lm committed
1356
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1357
        uasState = tr("ACTIVE");
1358
        stateDescription = tr("Active, normal operation.");
pixhawk's avatar
pixhawk committed
1359
        break;
lm's avatar
lm committed
1360 1361
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1362
        stateDescription = tr("Standby mode, ready for liftoff.");
lm's avatar
lm committed
1363 1364
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1365
        uasState = tr("CRITICAL");
1366
        stateDescription = tr("FAILURE: Continuing operation.");
pixhawk's avatar
pixhawk committed
1367
        break;
lm's avatar
lm committed
1368
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1369
        uasState = tr("EMERGENCY");
1370
        stateDescription = tr("EMERGENCY: Land Immediately!");
pixhawk's avatar
pixhawk committed
1371
        break;
lm's avatar
lm committed
1372
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1373
        uasState = tr("SHUTDOWN");
1374
        stateDescription = tr("Powering off system.");
pixhawk's avatar
pixhawk committed
1375
        break;
lm's avatar
lm committed
1376
    default:
pixhawk's avatar
pixhawk committed
1377
        uasState = tr("UNKNOWN");
1378
        stateDescription = tr("Unknown system state");
pixhawk's avatar
pixhawk committed
1379 1380 1381 1382
        break;
    }
}

1383 1384 1385 1386 1387 1388 1389
QImage UAS::getImage()
{
    return image;
}

void UAS::requestImage()
{
1390
    #ifdef MAVLINK_ENABLED_PIXHAWK
1391 1392 1393 1394 1395 1396 1397 1398
    qDebug() << "trying to get an image from the uas...";

    if (imagePacketsArrived == 0)
    {
        mavlink_message_t msg;
        mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50);
        sendMessage(msg);
    }
1399
    else if (QGC::groundTimeMilliseconds() - imageStart >= 1000)
1400 1401 1402 1403 1404 1405 1406 1407
    {
        // handshake happened more than 1 second ago, packets should have arrived by now
        // maybe we missed some packets (dropped along the way)
        image.loadFromData(imageRecBuffer);
        emit imageReady(this);
        // Restart statemachine
        imagePacketsArrived = 0;
    }
1408
#endif
1409 1410
    // default else, wait?
}
pixhawk's avatar
pixhawk committed
1411 1412 1413 1414 1415 1416 1417 1418 1419


/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1420
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1421 1422 1423 1424 1425 1426 1427 1428
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1429
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1430 1431 1432 1433
{
    return commStatus;
}

1434 1435 1436
void UAS::requestParameters()
{
    mavlink_message_t msg;
1437
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1438 1439
    // Send message twice to increase chance of reception
    sendMessage(msg);
1440 1441
}

1442
void UAS::writeParametersToStorage()
1443
{
1444 1445 1446
    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
1447
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1448 1449 1450 1451 1452 1453 1454 1455 1456
    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
1457 1458
}

1459
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1460 1461
{
    // Buffers to write data to
1462
    mavlink_message_t msg;
1463
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1464 1465
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1466
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1467 1468
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1469 1470
    // 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
1471 1472
    stream.req_message_rate = 0;
    // Start / stop the message
1473
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1474 1475 1476 1477 1478
    // 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
1479
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1480 1481
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1482 1483 1484
    sendMessage(msg);
}

1485
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1486 1487 1488
{
    // Buffers to write data to
    mavlink_message_t msg;
1489
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1490
    // Select the message to request from now on
1491
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1492
    // Select the update rate in Hz the message should be send
1493
    stream.req_message_rate = rate;
lm's avatar
lm committed
1494
    // Start / stop the message
1495
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1496 1497 1498 1499 1500
    // 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
1501
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1502 1503
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1504 1505 1506
    sendMessage(msg);
}

1507
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1508
{
1509 1510 1511 1512
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1513
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1514
    // Select the update rate in Hz the message should be send
1515
    stream.req_message_rate = rate;
1516
    // Start / stop the message
1517
    stream.start_stop = (rate) ? 1 : 0;
1518 1519 1520 1521 1522 1523
    // 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);
1524 1525
    // Send message twice to increase chance of reception
    sendMessage(msg);
1526
    sendMessage(msg);
lm's avatar
lm committed
1527
}
1528

1529
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1530
{
1531 1532 1533 1534 1535
#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
1536 1537 1538
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1539
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1540
    // Select the update rate in Hz the message should be send
1541
    stream.req_message_rate = rate;
1542
    // Start / stop the message
1543
    stream.start_stop = (rate) ? 1 : 0;
1544 1545 1546 1547 1548 1549
    // 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);
1550 1551
    // Send message twice to increase chance of reception
    sendMessage(msg);
1552
    sendMessage(msg);
1553
#endif
lm's avatar
lm committed
1554 1555
}

1556
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1557
{
1558 1559 1560 1561
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1562
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1563
    // Select the update rate in Hz the message should be send
1564
    stream.req_message_rate = rate;
1565
    // Start / stop the message
1566
    stream.start_stop = (rate) ? 1 : 0;
1567 1568 1569 1570 1571 1572
    // 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);
1573 1574
    // Send message twice to increase chance of reception
    sendMessage(msg);
1575
    sendMessage(msg);
lm's avatar
lm committed
1576 1577
}

lm's avatar
lm committed
1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598
//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);
//}
1599

1600
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1601 1602 1603 1604 1605
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1606
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1607
    // Select the update rate in Hz the message should be send
1608
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1609
    // Start / stop the message
1610
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621
    // 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);
}

1622
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1623 1624 1625 1626 1627
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1628
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1629
    // Select the update rate in Hz the message should be send
1630
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1631
    // Start / stop the message
1632
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643
    // 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);
}

1644
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1645 1646 1647 1648 1649
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1650
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1651
    // Select the update rate in Hz the message should be send
1652
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1653
    // Start / stop the message
1654
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665
    // 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);
}

1666
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1667 1668 1669 1670 1671
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1672
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1673
    // Select the update rate in Hz the message should be send
1674
    stream.req_message_rate = rate;
1675
    // Start / stop the message
1676
    stream.start_stop = (rate) ? 1 : 0;
1677 1678 1679 1680 1681 1682
    // 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);
1683 1684
    // Send message twice to increase chance of reception
    sendMessage(msg);
1685
    sendMessage(msg);
1686 1687
}

lm's avatar
lm committed
1688 1689 1690 1691 1692 1693 1694
/**
 * 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
1695 1696 1697 1698
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1699 1700 1701
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1702 1703
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1704

1705
    // Copy string into buffer, ensuring not to exceed the buffer size    
1706
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1707
    {
lm's avatar
lm committed
1708
        // String characters
1709
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1710
        {
1711
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1712
        }
1713 1714 1715 1716 1717
//        // Null termination at end of string or end of buffer
//        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
//        {
//            p.param_id[i] = '\0';
//        }
lm's avatar
lm committed
1718 1719 1720 1721 1722
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1723
    }    
1724
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1725
    sendMessage(msg);
lm's avatar
lm committed
1726
    }
1727 1728
}

1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740
void UAS::requestParameter(int component, int parameter)
{
    mavlink_message_t msg;
    mavlink_param_request_read_t read;
    read.param_index = parameter;
    read.target_system = uasId;
    read.target_component = component;
    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
    sendMessage(msg);
    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << parameter;
}

1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759
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);
}

1760 1761 1762
void UAS::setUASName(const QString& name)
{
    this->name = name;
1763
    writeSettings();
1764
    emit nameChanged(name);
1765
    emit systemSpecsChanged(uasId);
1766 1767
}

lm's avatar
lm committed
1768 1769 1770 1771
void UAS::executeCommand(MAV_CMD command)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796
    cmd.command = (uint8_t)command;
    cmd.confirmation = 0;
    cmd.param1 = 0.0f;
    cmd.param2 = 0.0f;
    cmd.param3 = 0.0f;
    cmd.param4 = 0.0f;
    cmd.target_system = uasId;
    cmd.target_component = 0;
    mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
    sendMessage(msg);
}

void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
    mavlink_message_t msg;
    mavlink_command_t cmd;
    cmd.command = (uint8_t)command;
    cmd.confirmation = confirmation;
    cmd.param1 = param1;
    cmd.param2 = param2;
    cmd.param3 = param3;
    cmd.param4 = param4;
    cmd.target_system = uasId;
    cmd.target_component = component;
    mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
lm's avatar
lm committed
1797 1798 1799
    sendMessage(msg);
}

1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812
/**
 * 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
1813
/**
lm's avatar
lm committed
1814
 * Launches the system
pixhawk's avatar
pixhawk committed
1815 1816 1817 1818
 *
 **/
void UAS::launch()
{
1819
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1820
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1821
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
1822 1823 1824
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1825 1826 1827 1828 1829 1830 1831 1832
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1833
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1834
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1835
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1836 1837 1838
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1839 1840 1841 1842 1843 1844 1845 1846
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1847
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1848
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1849
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1850 1851 1852
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866
}

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;

1867 1868 1869 1870 1871 1872
    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
1873

1874 1875 1876 1877 1878 1879
        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
1880 1881
}

1882 1883 1884 1885 1886
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1887 1888 1889 1890 1891
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1892

pixhawk's avatar
pixhawk committed
1893 1894
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1895

pixhawk's avatar
pixhawk committed
1896 1897 1898 1899 1900
        break;
    default:

        break;
    }
1901
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1902 1903 1904

}

1905

1906
/*void UAS::requestWaypoints()
1907 1908 1909 1910 1911
{
//    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
1912 1913
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1914 1915
}

pixhawk's avatar
pixhawk committed
1916 1917
void UAS::setWaypoint(Waypoint* wp)
{
1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935
//    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
1936 1937 1938 1939
}

void UAS::setWaypointActive(int id)
{
1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962
//    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!";
1963
}*/
pixhawk's avatar
pixhawk committed
1964 1965 1966 1967


void UAS::halt()
{
1968
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1969
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1970
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1971 1972 1973
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1974 1975 1976 1977
}

void UAS::go()
{
1978
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1979
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1980
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1981 1982 1983
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1984 1985 1986 1987 1988
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1989
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1990
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1991
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1992 1993 1994
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1995 1996 1997 1998 1999 2000 2001 2002
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
2003
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2004
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
2005
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
2006 2007 2008
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033
}

/**
 * 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)
    {
2034
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2035
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2036
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
2037 2038 2039
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062
        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
2063
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
2064
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
2065
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
2066 2067 2068
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
2069 2070 2071 2072
        result = true;
    }
}

2073 2074
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
2075 2076 2077 2078 2079 2080
    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);
2081 2082
}

pixhawk's avatar
pixhawk committed
2083 2084 2085
/**
 * @return The name of this system as string in human-readable form
 */
2086
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104
{
    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);
2105
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
2106 2107 2108
    }
}

2109 2110 2111 2112 2113 2114 2115 2116 2117
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134
/**
 * @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
2135
    case NICD:
pixhawk's avatar
pixhawk committed
2136
        break;
lm's avatar
lm committed
2137
    case NIMH:
pixhawk's avatar
pixhawk committed
2138
        break;
lm's avatar
lm committed
2139
    case LIION:
pixhawk's avatar
pixhawk committed
2140
        break;
lm's avatar
lm committed
2141
    case LIPOLY:
pixhawk's avatar
pixhawk committed
2142 2143 2144
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
2145
    case LIFE:
pixhawk's avatar
pixhawk committed
2146
        break;
lm's avatar
lm committed
2147
    case AGZN:
pixhawk's avatar
pixhawk committed
2148 2149 2150 2151
        break;
    }
}

2152 2153
void UAS::setBatterySpecs(const QString& specs)
{
2154
    if (specs.length() == 0 || specs.contains("%"))
2155
    {
2156
        batteryRemainingEstimateEnabled = false;
2157
        bool ok;
2158 2159 2160
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
2161 2162 2163 2164 2165 2166 2167 2168
        if (ok)
        {
            warnLevelPercent = temp;
        }
        else
        {
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190
    }
    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;
        }
2191 2192 2193 2194
        else
        {
            emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
        }
2195 2196 2197 2198 2199
    }
}

QString UAS::getBatterySpecs()
{
2200 2201 2202 2203 2204 2205 2206 2207
    if (batteryRemainingEstimateEnabled)
    {
        return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
    }
    else
    {
        return QString("%1%").arg(warnLevelPercent);
    }
2208 2209
}

pixhawk's avatar
pixhawk committed
2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222
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
2223 2224 2225
/**
 * @return charge level in percent - 0 - 100
 */
2226
float UAS::getChargeLevel()
pixhawk's avatar
pixhawk committed
2227
{
2228
    if (batteryRemainingEstimateEnabled)
2229
    {
2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241
        if (lpVoltage < emptyVoltage)
        {
            chargeLevel = 0.0f;
        }
        else if (lpVoltage > fullVoltage)
        {
            chargeLevel = 100.0f;
        }
        else
        {
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
2242 2243
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
2244 2245
}

lm's avatar
lm committed
2246 2247 2248 2249
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
2250
        GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
2251
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
2252 2253 2254 2255 2256 2257 2258 2259 2260 2261 2262 2263
        lowBattAlarm = true;
    }
}

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