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

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

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

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

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

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

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

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

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

130 131 132 133 134 135 136 137
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
    if (positionLock)
    {
        positionLock = false;
    }
    else
    {
pixhawk's avatar
pixhawk committed
138
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
139 140 141 142 143 144
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

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

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

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

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

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

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

        // Receive named value message
        receiveMessageNamedValue(message);

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

                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);
403 404 405
                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);
406 407

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

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

                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
pixhawk's avatar
pixhawk committed
419
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
420 421 422
                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);
423

424 425
                emit attitudeChanged(this, roll, pitch, yaw, time);
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
426 427
            }
            break;
428
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
429
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
430
            //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
431
            {
432 433
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
434
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
435 436 437
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
438 439 440 441 442 443
                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
444
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
445
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
446

447 448
                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
449

450
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
451 452 453 454 455 456 457
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
458 459
            }
            break;
460
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
461 462 463
            //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;
            {
464 465
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
466
                quint64 time = QGC::groundTimeUsecs()/1000;
467 468 469 470 471 472
                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;
473 474 475 476 477 478
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                emit valueChanged(uasId, "gps x speed", "m/s", speedX, time);
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
479
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506
                emit speedChanged(this, speedX, speedY, speedZ, time);
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
            }
            break;
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            {
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = QGC::groundTimeUsecs()/1000;
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
                speedX = pos.vx;
                speedY = pos.vy;
                speedZ = pos.vz;
                emit valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                emit valueChanged(uasId, "gps x speed", "m/s", speedX, time);
507 508
                emit valueChanged(uasId, "gps y speed", "m/s", speedY, time);
                emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
509 510
                emit globalPositionChanged(this, longitude, latitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
511
                emit valueChanged(uasId, "gpsspeed", "m/s", sqrt(speedX*speedX+speedY*speedY+speedZ*speedZ), time);
pixhawk's avatar
pixhawk committed
512 513 514 515 516 517 518
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
519 520
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
521 522 523 524 525 526 527 528
            }
            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);
529 530 531

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

535 536
                emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
                emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
lm's avatar
lm committed
537

lm's avatar
lm committed
538
                if (pos.fix_type > 0)
539
                {
Laurens Mackay's avatar
Laurens Mackay committed
540
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
541
                    emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time);
lm's avatar
lm committed
542 543 544 545 546 547 548 549

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
550
                    emit valueChanged(uasId, "altitude", "m", pos.alt, time);
lm's avatar
lm committed
551 552 553
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
554
                        emit valueChanged(uasId, "speed", "m/s", pos.v, time);
lm's avatar
lm committed
555
                        //qDebug() << "GOT GPS RAW";
556
                       // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
lm's avatar
lm committed
557 558 559 560 561
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
562
                }
563 564
            }
            break;
lm's avatar
lm committed
565 566 567 568
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
569
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
570
                {
lm's avatar
lm committed
571
                    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
572 573 574
                }
            }
            break;
575 576 577 578 579 580 581
        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;
582 583 584 585
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            {
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
586
                quint64 time = this->getUnixTime(0);
587 588 589
                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);
590 591
            }
            break;
592
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
593
            {
594 595
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
596
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619
                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
620 621
            }
            break;
622 623 624 625
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642

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

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

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

                // Emit change
                emit parameterChanged(uasId, message.compid, parameterName, val);
643 644
            }
            break;
pixhawk's avatar
pixhawk committed
645
        case MAVLINK_MSG_ID_DEBUG:
646
            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
647
            break;
648 649 650 651 652
        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
653
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
654 655 656
                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);
657 658 659 660 661 662
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
663
                quint64 time = MG::TIME::getGroundTimeNow();
664
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
665 666 667
                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);
668 669
            }
            break;
pixhawk's avatar
pixhawk committed
670 671 672 673
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
674 675 676 677
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
678 679 680
            }
            break;

681
        case MAVLINK_MSG_ID_WAYPOINT:
682
            {
683 684
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
685
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
686 687 688 689
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
690
            }
pixhawk's avatar
pixhawk committed
691
            break;
pixhawk's avatar
pixhawk committed
692

693 694 695 696 697 698 699 700 701 702 703
        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
704 705 706 707
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
708 709 710 711
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
712 713 714
            }
            break;

715
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
716
            {
pixhawk's avatar
pixhawk committed
717 718 719
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
720
            }
pixhawk's avatar
pixhawk committed
721
            break;
pixhawk's avatar
pixhawk committed
722

723
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
724
            {
725 726 727
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
728
            }
pixhawk's avatar
pixhawk committed
729
            break;
pixhawk's avatar
pixhawk committed
730

731 732 733 734 735 736 737
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
                mavlink_local_position_setpoint_t p;
                mavlink_msg_local_position_setpoint_decode(&message, &p);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
            }
            break;
pixhawk's avatar
pixhawk committed
738

739
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
740 741 742
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
743
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
744 745
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
746
                int severity = mavlink_msg_statustext_get_severity(&message);
747
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
748
                //emit statusTextReceived(severity, text);
749
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
750 751
            }
            break;
752 753 754 755 756 757
    case MAVLINK_MSG_ID_DEBUG_VECT:
            {
                mavlink_debug_vect_t vect;
                mavlink_msg_debug_vect_decode(&message, &vect);
                QString str((const char*)vect.name);
                quint64 time = getUnixTime(vect.usec);
758 759 760
                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);
761 762
            }
            break;
763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778
            //#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
779
#ifdef MAVLINK_ENABLED_UALBERTA
780 781 782 783 784
        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();
785 786 787 788 789 790
                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);
791 792
            }
            break;
793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816
       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];

817
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
818 819 820 821 822
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

823
#endif
pixhawk's avatar
pixhawk committed
824
        default:
lm's avatar
lm committed
825 826 827 828
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
829 830
                    //GAudioOutput::instance()->say("UNABLE TO DECODE MESSAGE WITH ID " + QString::number(message.msgid) + " FROM SYSTEM " + QString::number(message.sysid));
                    std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
lm's avatar
lm committed
831 832 833
                    //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
834 835 836 837 838
            break;
        }
    }
}

839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868
void UAS::setLocalOriginAtCurrentGPSPosition()
{

    bool result = false;
    QMessageBox msgBox;
    msgBox.setIcon(QMessageBox::Warning);
    msgBox.setText("Setting new World Coordinate Frame Origin");
    msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
    msgBox.setDefaultButton(QMessageBox::Cancel);
    int ret = msgBox.exec();

    // Close the message box shortly after the click to prevent accidental clicks
    QTimer::singleShot(5000, &msgBox, SLOT(reject()));


    if (ret == QMessageBox::Yes)
    {
        mavlink_message_t msg;
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getSystemId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
        // Send message twice to increase chance that it reaches its goal
        sendMessage(msg);
        // Wait 5 ms
        MG::SLEEP::usleep(5000);
        // Send again
        sendMessage(msg);
        result = true;
    }
}

pixhawk's avatar
pixhawk committed
869 870
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
871
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
872
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
873 874
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
875
#else
lm's avatar
lm committed
876 877 878 879
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
880
#endif
pixhawk's avatar
pixhawk committed
881 882
}

pixhawk's avatar
pixhawk committed
883 884
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
885
#ifdef MAVLINK_ENABLED_PIXHAWK
886 887 888
    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
889
#else
890 891 892 893
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
894 895 896 897 898
#endif
}

void UAS::startRadioControlCalibration()
{
899 900 901
    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
902 903
}

lm's avatar
lm committed
904 905
void UAS::startDataRecording()
{
906 907 908
    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
909 910 911 912
}

void UAS::pauseDataRecording()
{
913 914 915
    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
916 917 918 919
}

void UAS::stopDataRecording()
{
920 921 922
    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
923 924
}

pixhawk's avatar
pixhawk committed
925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945
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);
}

946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967
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
968
#ifndef _MSC_VER
969
    else if (time < 1261440000000000LLU)
970
#else
971
        else if (time < 1261440000000000)
972
#endif
973
        {
974 975
        if (onboardTimeOffset == 0)
        {
976
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
977
        }
978
        return time/1000 + onboardTimeOffset;
979 980 981 982 983
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
984
        return time/1000;
985 986 987
    }
}

988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004
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
1005
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
1006
{
lm's avatar
lm committed
1007
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
1008
    {
1009
        this->mode = mode;
pixhawk's avatar
pixhawk committed
1010
        mavlink_message_t msg;
lm's avatar
lm committed
1011
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
1012
        sendMessage(msg);
lm's avatar
lm committed
1013
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
1014
    }
pixhawk's avatar
pixhawk committed
1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026
}

void UAS::sendMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>::iterator i;
    for (i = links->begin(); i != links->end(); ++i)
    {
        sendMessage(*i, message);
    }
}

1027 1028 1029 1030
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
1031

1032 1033
    foreach(LinkInterface* link, link_list)
    {
1034
        if (link)
1035
        {
1036 1037
            SerialLink* serial = dynamic_cast<SerialLink*>(link);
            if(serial != 0)
1038
            {
1039 1040

                for(int i=0;i<links->size();i++)
1041
                {
1042 1043
                    if(serial != links->at(i))
                    {
1044
                        qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
1045 1046
                        sendMessage(serial, message);
                    }
1047 1048 1049 1050 1051 1052
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
1053 1054
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
1055
    if(!link) return;
pixhawk's avatar
pixhawk committed
1056 1057 1058
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
1059
    int len = mavlink_msg_to_send_buffer(buffer, &message);
1060
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071
    // 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
 */
1072
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
1073
{
1074
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
1075 1076 1077 1078 1079 1080
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
1081
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
1082
        uasState = tr("UNINIT");
1083
        stateDescription = tr("Waiting..");
pixhawk's avatar
pixhawk committed
1084
        break;
lm's avatar
lm committed
1085
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
1086
        uasState = tr("BOOT");
1087
        stateDescription = tr("Booting..");
pixhawk's avatar
pixhawk committed
1088
        break;
lm's avatar
lm committed
1089
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
1090
        uasState = tr("CALIBRATING");
1091
        stateDescription = tr("Calibrating..");
pixhawk's avatar
pixhawk committed
1092
        break;
lm's avatar
lm committed
1093
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
1094
        uasState = tr("ACTIVE");
1095
        stateDescription = tr("Normal");
pixhawk's avatar
pixhawk committed
1096
        break;
lm's avatar
lm committed
1097 1098
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
1099
        stateDescription = tr("Standby, OK");
lm's avatar
lm committed
1100 1101
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
1102
        uasState = tr("CRITICAL");
1103
        stateDescription = tr("FAILURE: Continue");
pixhawk's avatar
pixhawk committed
1104
        break;
lm's avatar
lm committed
1105
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
1106
        uasState = tr("EMERGENCY");
1107
        stateDescription = tr("EMERGENCY: Land!");
pixhawk's avatar
pixhawk committed
1108
        break;
lm's avatar
lm committed
1109
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
1110
        uasState = tr("SHUTDOWN");
1111
        stateDescription = tr("Powering off");
pixhawk's avatar
pixhawk committed
1112
        break;
lm's avatar
lm committed
1113
    default:
pixhawk's avatar
pixhawk committed
1114
        uasState = tr("UNKNOWN");
1115
        stateDescription = tr("Unknown state");
pixhawk's avatar
pixhawk committed
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
1129
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
1130 1131 1132 1133 1134 1135 1136 1137
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

1138
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
1139 1140 1141 1142
{
    return commStatus;
}

1143 1144 1145
void UAS::requestParameters()
{
    mavlink_message_t msg;
1146
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
1147 1148
    // Send message twice to increase chance of reception
    sendMessage(msg);
1149 1150
}

1151
void UAS::writeParametersToStorage()
1152
{
1153 1154 1155
    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
1156
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
1157 1158 1159 1160 1161 1162 1163 1164 1165
    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
1166 1167
}

1168
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
1169 1170
{
    // Buffers to write data to
1171
    mavlink_message_t msg;
1172
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1173 1174
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
1175
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
1176 1177
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
1178 1179
    // 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
1180 1181
    stream.req_message_rate = 0;
    // Start / stop the message
1182
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1183 1184 1185 1186 1187
    // 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
1188
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1189 1190
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1191 1192 1193
    sendMessage(msg);
}

1194
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
1195 1196 1197
{
    // Buffers to write data to
    mavlink_message_t msg;
1198
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
1199
    // Select the message to request from now on
1200
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
1201
    // Select the update rate in Hz the message should be send
1202
    stream.req_message_rate = rate;
lm's avatar
lm committed
1203
    // Start / stop the message
1204
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
1205 1206 1207 1208 1209
    // 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
1210
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
1211 1212
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1213 1214 1215
    sendMessage(msg);
}

1216
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1217
{
1218 1219 1220 1221
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1222
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1223
    // Select the update rate in Hz the message should be send
1224
    stream.req_message_rate = rate;
1225
    // Start / stop the message
1226
    stream.start_stop = (rate) ? 1 : 0;
1227 1228 1229 1230 1231 1232
    // 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);
1233 1234
    // Send message twice to increase chance of reception
    sendMessage(msg);
1235
    sendMessage(msg);
lm's avatar
lm committed
1236
}
1237

1238
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1239
{
1240 1241 1242 1243 1244
#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
1245 1246 1247
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1248
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1249
    // Select the update rate in Hz the message should be send
1250
    stream.req_message_rate = rate;
1251
    // Start / stop the message
1252
    stream.start_stop = (rate) ? 1 : 0;
1253 1254 1255 1256 1257 1258
    // 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);
1259 1260
    // Send message twice to increase chance of reception
    sendMessage(msg);
1261
    sendMessage(msg);
1262
#endif
lm's avatar
lm committed
1263 1264
}

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

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

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

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

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

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

lm's avatar
lm committed
1397 1398 1399 1400 1401 1402 1403
/**
 * 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
1404 1405 1406 1407
void UAS::setParameter(const int component, const QString& id, const float value)
{
    if (!id.isNull())
    {
1408 1409 1410
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1411 1412
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1413

1414
    // Copy string into buffer, ensuring not to exceed the buffer size    
1415
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1416
    {
lm's avatar
lm committed
1417
        // String characters
1418
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1419
        {
1420
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1421 1422
        }
        // Null termination at end of string or end of buffer
1423
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1424 1425 1426 1427 1428 1429 1430 1431
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1432
    }    
1433
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1434
    sendMessage(msg);
lm's avatar
lm committed
1435
    }
1436 1437
}

1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456
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);
}

1457 1458 1459
void UAS::setUASName(const QString& name)
{
    this->name = name;
1460
    writeSettings();
1461
    emit nameChanged(name);
1462
    emit systemSpecsChanged(uasId);
1463 1464
}

1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477
/**
 * 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
1478
/**
lm's avatar
lm committed
1479
 * Launches the system
pixhawk's avatar
pixhawk committed
1480 1481 1482 1483
 *
 **/
void UAS::launch()
{
1484
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1485
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1486
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
1487 1488 1489
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1490 1491 1492 1493 1494 1495 1496 1497
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1498
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1499
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1500
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1501 1502 1503
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1504 1505 1506 1507 1508 1509 1510 1511
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1512
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1513
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1514
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1515 1516 1517
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531
}

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;

1532 1533 1534 1535 1536 1537
    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
1538

1539 1540 1541 1542 1543 1544
        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
1545 1546
}

1547 1548 1549 1550 1551
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1552 1553 1554 1555 1556
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1557

pixhawk's avatar
pixhawk committed
1558 1559
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1560

pixhawk's avatar
pixhawk committed
1561 1562 1563 1564 1565
        break;
    default:

        break;
    }
1566
    //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1567 1568 1569

}

1570

1571
/*void UAS::requestWaypoints()
1572 1573 1574 1575 1576
{
//    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
1577 1578
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1579 1580
}

pixhawk's avatar
pixhawk committed
1581 1582
void UAS::setWaypoint(Waypoint* wp)
{
1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600
//    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
1601 1602 1603 1604
}

void UAS::setWaypointActive(int id)
{
1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627
//    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!";
1628
}*/
pixhawk's avatar
pixhawk committed
1629 1630 1631 1632


void UAS::halt()
{
1633
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1634
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1635
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1636 1637 1638
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1639 1640 1641 1642
}

void UAS::go()
{
1643
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1644
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1645
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1646 1647 1648
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1649 1650 1651 1652 1653
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1654
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1655
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1656
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1657 1658 1659
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1660 1661 1662 1663 1664 1665 1666 1667
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1668
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1669
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1670
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1671 1672 1673
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698
}

/**
 * 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)
    {
1699
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1700
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1701
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1702 1703 1704
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727
        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
1728
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1729
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1730
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1731 1732 1733
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1734 1735 1736 1737
        result = true;
    }
}

1738 1739
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1740 1741 1742 1743 1744 1745
    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);
1746 1747
}

pixhawk's avatar
pixhawk committed
1748 1749 1750
/**
 * @return The name of this system as string in human-readable form
 */
1751
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769
{
    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);
1770
        connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
1771 1772
    }
    //links->append(link);
1773
    //qDebug() << link<<" ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
pixhawk's avatar
pixhawk committed
1774 1775
}

1776 1777 1778 1779 1780 1781 1782 1783 1784
void UAS::removeLink(QObject* object)
{
    LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    if (link)
    {
        links->removeAt(links->indexOf(link));
    }
}

pixhawk's avatar
pixhawk committed
1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801
/**
 * @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
1802
    case NICD:
pixhawk's avatar
pixhawk committed
1803
        break;
lm's avatar
lm committed
1804
    case NIMH:
pixhawk's avatar
pixhawk committed
1805
        break;
lm's avatar
lm committed
1806
    case LIION:
pixhawk's avatar
pixhawk committed
1807
        break;
lm's avatar
lm committed
1808
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1809 1810 1811
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1812
    case LIFE:
pixhawk's avatar
pixhawk committed
1813
        break;
lm's avatar
lm committed
1814
    case AGZN:
pixhawk's avatar
pixhawk committed
1815 1816 1817 1818
        break;
    }
}

1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845
void UAS::setBatterySpecs(const QString& specs)
{
    QString stringList = specs;
    stringList = stringList.remove("V");
    stringList = stringList.remove("v");
    QStringList parts = stringList.split(",");
    if (parts.length() == 3)
    {
        float temp;
        bool ok;
        // Get the empty voltage
        temp = parts.at(0).toFloat(&ok);
        if (ok) emptyVoltage = temp;
        // Get the warning voltage
        temp = parts.at(1).toFloat(&ok);
        if (ok) warnVoltage = temp;
        // Get the full voltage
        temp = parts.at(2).toFloat(&ok);
        if (ok) fullVoltage = temp;
    }
}

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

pixhawk's avatar
pixhawk committed
1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858
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
1859 1860 1861
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1862 1863
double UAS::getChargeLevel()
{
1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877
    float chargeLevel;
    if (lpVoltage < emptyVoltage)
    {
        chargeLevel = 0.0f;
    }
    else if (lpVoltage > fullVoltage)
    {
        chargeLevel = 100.0f;
    }
    else
    {
        chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
    }
    return chargeLevel;
pixhawk's avatar
pixhawk committed
1878 1879
}

lm's avatar
lm committed
1880 1881 1882 1883
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1884 1885
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897
        lowBattAlarm = true;
    }
}

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