UAS.cc 59.9 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

lm's avatar
lm committed
3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

lm's avatar
lm committed
5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

lm's avatar
lm committed
7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

lm's avatar
lm committed
9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

lm's avatar
lm committed
14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
lm's avatar
lm committed
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41

======================================================================*/

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

#include <QList>
#include <QMessageBox>
#include <QTimer>
#include <iostream>
#include <QDebug>
#include <cmath>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "MG.h"
42
#include "QGC.h"
pixhawk's avatar
pixhawk committed
43
#include "GAudioOutput.h"
44
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
45
#include "QGCMAVLink.h"
pixhawk's avatar
pixhawk committed
46

47

48
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
49
        uasId(id),
pixhawk's avatar
pixhawk committed
50 51 52
        startTime(MG::TIME::getGroundTimeNow()),
        commStatus(COMM_DISCONNECTED),
        name(""),
53
        autopilot(-1),
pixhawk's avatar
pixhawk committed
54
        links(new QList<LinkInterface*>()),
55
        unknownPackets(),
56
        mavlink(protocol),
57
        waypointManager(*this),
pixhawk's avatar
pixhawk committed
58
        thrustSum(0),
pixhawk's avatar
pixhawk committed
59
        thrustMax(10),
pixhawk's avatar
pixhawk committed
60
        startVoltage(0),
61 62
        currentVoltage(12.0f),
        lpVoltage(12.0f),
pixhawk's avatar
pixhawk committed
63 64 65
        mode(MAV_MODE_UNINIT),
        status(MAV_STATE_UNINIT),
        onboardTimeOffset(0),
pixhawk's avatar
pixhawk committed
66 67 68 69
        controlRollManual(true),
        controlPitchManual(true),
        controlYawManual(true),
        controlThrustManual(true),
pixhawk's avatar
pixhawk committed
70 71 72
        manualRollAngle(0),
        manualPitchAngle(0),
        manualYawAngle(0),
lm's avatar
lm committed
73 74
        manualThrust(0),
        receiveDropRate(0),
lm's avatar
lm committed
75
        sendDropRate(0),
76 77
        lowBattAlarm(false),
        positionLock(false),
78 79 80 81 82 83 84 85 86
        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),
87
        statusTimeout(new QTimer(this))
pixhawk's avatar
pixhawk committed
88
{
89
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
90
    setBattery(LIPOLY, 3);
91 92
    statusTimeout->setInterval(500);
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
pixhawk's avatar
pixhawk committed
93 94 95 96 97 98 99
}

UAS::~UAS()
{
    delete links;
}

100
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
101 102 103 104
{
    return uasId;
}

105 106 107 108 109 110 111 112 113 114
void UAS::updateState()
{
    // 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
115
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
116 117 118 119 120 121
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
122 123 124 125 126 127 128 129 130 131
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
    if (!links->contains(link))
    {
        addLink(link);
132
//        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
133
    }
134 135 136 137
//    else
//    {
//        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
//    }
pixhawk's avatar
pixhawk committed
138

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

pixhawk's avatar
pixhawk committed
141 142 143 144 145 146 147 148 149 150
    if (message.sysid == uasId)
    {
        QString uasState;
        QString stateDescription;
        QString patternPath;
        switch (message.msgid)
        {
        case MAVLINK_MSG_ID_HEARTBEAT:
            emit heartbeat(this);
            // Set new type if it has changed
pixhawk's avatar
pixhawk committed
151
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
152
            {
pixhawk's avatar
pixhawk committed
153
                this->type = mavlink_msg_heartbeat_get_type(&message);
154
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
155 156
                emit systemTypeSet(this, type);
            }
157

pixhawk's avatar
pixhawk committed
158 159 160 161 162 163
            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
164 165
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
166 167
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
168

pixhawk's avatar
pixhawk committed
169
                // FIXME
170
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
171

pixhawk's avatar
pixhawk committed
172 173 174 175 176
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
177

pixhawk's avatar
pixhawk committed
178
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
179
                {
pixhawk's avatar
pixhawk committed
180
                    statechanged = true;
lm's avatar
lm committed
181
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
182 183
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
184
                    emit statusChanged(this->status);
185 186
                    emit loadChanged(this,state.load/10.0f);
                    emit UAS::valueChanged(this, "Load", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
187
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
188 189
                }

lm's avatar
lm committed
190
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
191 192
                {
                    modechanged = true;
lm's avatar
lm committed
193
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
194 195
                    QString mode;

lm's avatar
lm committed
196
                    switch (state.mode)
pixhawk's avatar
pixhawk committed
197
                    {
lm's avatar
lm committed
198
                    case (uint8_t)MAV_MODE_LOCKED:
pixhawk's avatar
pixhawk committed
199 200
                        mode = "LOCKED MODE";
                        break;
lm's avatar
lm committed
201
                    case (uint8_t)MAV_MODE_MANUAL:
pixhawk's avatar
pixhawk committed
202 203
                        mode = "MANUAL MODE";
                        break;
lm's avatar
lm committed
204
                    case (uint8_t)MAV_MODE_AUTO:
pixhawk's avatar
pixhawk committed
205 206
                        mode = "AUTO MODE";
                        break;
lm's avatar
lm committed
207
                    case (uint8_t)MAV_MODE_GUIDED:
208 209
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
210
                    case (uint8_t)MAV_MODE_READY:
lm's avatar
lm committed
211 212
                        mode = "READY";
                        break;
lm's avatar
lm committed
213
                    case (uint8_t)MAV_MODE_TEST1:
pixhawk's avatar
pixhawk committed
214 215
                        mode = "TEST1 MODE";
                        break;
lm's avatar
lm committed
216
                    case (uint8_t)MAV_MODE_TEST2:
pixhawk's avatar
pixhawk committed
217 218
                        mode = "TEST2 MODE";
                        break;
lm's avatar
lm committed
219
                    case (uint8_t)MAV_MODE_TEST3:
pixhawk's avatar
pixhawk committed
220 221
                        mode = "TEST3 MODE";
                        break;
lm's avatar
lm committed
222 223 224
                    case (uint8_t)MAV_MODE_RC_TRAINING:
                        mode = "RC TRAINING MODE";
                        break;
pixhawk's avatar
pixhawk committed
225 226 227 228 229 230 231 232
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
233
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
234
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
235 236 237
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
238
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
239
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
240

lm's avatar
lm committed
241 242
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
243
                if (chargeLevel <= 20.0f)
lm's avatar
lm committed
244 245 246 247 248 249 250 251
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
252
                // COMMUNICATIONS DROP RATE
lm's avatar
lm committed
253
                emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
254
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
255 256

                // AUDIO
pixhawk's avatar
pixhawk committed
257 258 259 260 261 262 263 264 265 266
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
267
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
268 269 270 271 272 273 274 275
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
pixhawk's avatar
pixhawk committed
276 277 278
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
279
            {
pixhawk's avatar
pixhawk committed
280 281
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
282
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
283

pixhawk's avatar
pixhawk committed
284 285 286 287 288 289 290 291 292
                emit valueChanged(uasId, "Accel. X", raw.xacc, time);
                emit valueChanged(uasId, "Accel. Y", raw.yacc, time);
                emit valueChanged(uasId, "Accel. Z", raw.zacc, time);
                emit valueChanged(uasId, "Gyro Phi", raw.xgyro, time);
                emit valueChanged(uasId, "Gyro Theta", raw.ygyro, time);
                emit valueChanged(uasId, "Gyro Psi", raw.zgyro, time);
                emit valueChanged(uasId, "Mag. X", raw.xmag, time);
                emit valueChanged(uasId, "Mag. Y", raw.ymag, time);
                emit valueChanged(uasId, "Mag. Z", raw.zmag, time);
pixhawk's avatar
pixhawk committed
293 294 295 296
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
297
            //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
298
            {
pixhawk's avatar
pixhawk committed
299 300
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
301
                quint64 time = getUnixTime(attitude.usec);
lm's avatar
lm committed
302 303 304
                roll = attitude.roll;
                pitch = attitude.pitch;
                yaw = attitude.yaw;
pixhawk's avatar
pixhawk committed
305 306 307 308 309 310
                emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
                emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
                emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
                emit valueChanged(this, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
                emit valueChanged(this, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
                emit valueChanged(this, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
lm's avatar
lm committed
311 312 313
                emit valueChanged(uasId, "rollspeed IMU", attitude.rollspeed, time);
                emit valueChanged(uasId, "pitchspeed IMU", attitude.pitchspeed, time);
                emit valueChanged(uasId, "yawspeed IMU", attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
314
                emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time);
pixhawk's avatar
pixhawk committed
315 316
            }
            break;
317
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
318
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
319
            //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
320
            {
321 322
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
323
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
324 325 326
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
lm's avatar
lm committed
327 328 329
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
330 331 332
                emit valueChanged(uasId, "Vx", pos.vx, time);
                emit valueChanged(uasId, "Vy", pos.vy, time);
                emit valueChanged(uasId, "Vz", pos.vz, time);
lm's avatar
lm committed
333
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
334
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
335 336 337 338

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

339
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
340 341 342 343 344 345 346
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
347 348
            }
            break;
349 350 351 352 353 354 355
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            //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_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
356 357 358
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
359 360 361 362 363 364 365
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
                emit valueChanged(uasId, "alt", pos.alt, time);
                emit valueChanged(uasId, "g-vx", pos.vx, time);
                emit valueChanged(uasId, "g-vy", pos.vy, time);
                emit valueChanged(uasId, "g-vz", pos.vz, time);
                emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
pixhawk's avatar
pixhawk committed
366 367 368 369 370 371 372 373
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
374 375 376 377 378

                // Send to patch antenna
                mavlink_message_t msg;
                mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
                sendMessage(msg);
379 380 381 382 383 384 385 386
            }
            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);
387 388 389

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

393 394
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
lm's avatar
lm committed
395

lm's avatar
lm committed
396
                if (pos.fix_type > 0)
397
                {
Laurens Mackay's avatar
Laurens Mackay committed
398
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "alt", pos.alt, time);
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
                        emit valueChanged(uasId, "speed", 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));
                    }
419
                }
420 421
            }
            break;
lm's avatar
lm committed
422 423 424 425
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
426
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
427
                {
lm's avatar
lm committed
428
                    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
429 430 431
                }
            }
            break;
432 433 434 435 436 437 438
        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;
439
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
440
            {
441 442
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
443
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466
                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
467 468
            }
            break;
469 470 471 472 473 474 475
        case MAVLINK_MSG_ID_PARAM_VALUE:
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
                emit parameterChanged(uasId, message.compid, QString((char*)value.param_id), value.param_value);
            }
            break;
pixhawk's avatar
pixhawk committed
476
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
477
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
478
            break;
479 480 481 482 483
        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
484
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
485 486 487 488 489 490 491 492 493
                emit valueChanged(uasId, "att control roll", out.roll, time/1000.0f);
                emit valueChanged(uasId, "att control pitch", out.pitch, time/1000.0f);
                emit valueChanged(uasId, "att control yaw", out.yaw, time/1000.0f);
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
494
                quint64 time = MG::TIME::getGroundTimeNow();
495
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
496 497 498
                emit valueChanged(uasId, "pos control x", out.x, time);
                emit valueChanged(uasId, "pos control y", out.y, time);
                emit valueChanged(uasId, "pos control z", out.z, time);
499 500
            }
            break;
pixhawk's avatar
pixhawk committed
501 502 503 504
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
505 506 507 508
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
509 510 511
            }
            break;

512
        case MAVLINK_MSG_ID_WAYPOINT:
513
            {
514 515
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
516
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
517 518 519 520
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
521
            }
pixhawk's avatar
pixhawk committed
522
            break;
pixhawk's avatar
pixhawk committed
523

524 525 526 527 528 529 530 531 532 533 534
        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
535 536 537 538
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
539 540 541 542
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
543 544 545
            }
            break;

546
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
547
            {
pixhawk's avatar
pixhawk committed
548 549 550
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
551
            }
pixhawk's avatar
pixhawk committed
552
            break;
pixhawk's avatar
pixhawk committed
553

554
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
555
            {
556 557 558
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
559
            }
pixhawk's avatar
pixhawk committed
560
            break;
pixhawk's avatar
pixhawk committed
561

562 563 564 565 566 567 568
        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
569

570
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
571 572 573
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
574
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
575 576
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
577
                int severity = mavlink_msg_statustext_get_severity(&message);
578
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
579
                //emit statusTextReceived(severity, text);
580
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
581 582
            }
            break;
583 584 585 586 587 588 589 590 591 592 593
    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);
                emit valueChanged(uasId, str+".x", vect.x, time);
                emit valueChanged(uasId, str+".y", vect.y, time);
                emit valueChanged(uasId, str+".z", vect.z, time);
            }
            break;
594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609
//#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
610
#ifdef MAVLINK_ENABLED_UALBERTA
611 612 613 614 615 616 617 618 619 620 621 622 623
        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();
                emit valueChanged(uasId, "b_f[0]", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", bias.gyro_2, time);
            }
            break;
624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647
       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];

648
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
649 650 651 652 653
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

654
#endif
pixhawk's avatar
pixhawk committed
655
        default:
lm's avatar
lm committed
656 657 658 659
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
660 661
                    //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
662 663 664
                    //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
665 666 667 668 669
            break;
        }
    }
}

670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699
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
700 701
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
702
    #ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
703
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
704 705
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
lm's avatar
lm committed
706 707 708 709 710 711
    #else
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
    #endif
pixhawk's avatar
pixhawk committed
712 713
}

pixhawk's avatar
pixhawk committed
714 715
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
716
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
717 718 719
  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
720 721 722 723 724
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
725 726 727 728 729 730 731 732 733 734
#endif
}

void UAS::startRadioControlCalibration()
{
  mavlink_message_t msg;
  mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_RC);
  sendMessage(msg);
}

lm's avatar
lm committed
735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755
void UAS::startDataRecording()
{
  mavlink_message_t msg;
  mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
  sendMessage(msg);
}

void UAS::pauseDataRecording()
{
  mavlink_message_t msg;
  mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
  sendMessage(msg);
}

void UAS::stopDataRecording()
{
  mavlink_message_t msg;
  mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
  sendMessage(msg);
}

pixhawk's avatar
pixhawk committed
756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776
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);
}

777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798
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
799
#ifndef _MSVC_VER
800
    else if (time < 1261440000000000LLU)
801
#else
802
    else if (time < 1261440000000000)
803
#endif
804 805 806
    {
        if (onboardTimeOffset == 0)
        {
807
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
808
        }
809
        return time/1000 + onboardTimeOffset;
810 811 812 813 814
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
815
        return time/1000;
816 817 818
    }
}

pixhawk's avatar
pixhawk committed
819
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
820
{
lm's avatar
lm committed
821
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
822 823
    {
        mavlink_message_t msg;
lm's avatar
lm committed
824
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
825
        sendMessage(msg);
lm's avatar
lm committed
826
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
827
    }
pixhawk's avatar
pixhawk committed
828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844
}

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

void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
845
    int len = mavlink_msg_to_send_buffer(buffer, &message);
846
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
847 848 849 850 851 852 853 854 855 856 857
    // 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
 */
858
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
859
{
860
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
861 862 863 864 865 866
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
867
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
868 869 870
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
871
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
872 873 874
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
875
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
876 877 878
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
879
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
880 881 882
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
883 884 885 886 887
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
888 889 890
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
891
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
892 893 894
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
895
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
896 897 898
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
899
    default:
pixhawk's avatar
pixhawk committed
900 901 902 903 904 905 906 907 908 909 910 911 912 913 914
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
915
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
916 917 918 919 920 921 922 923
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

924
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
925 926 927 928
{
    return commStatus;
}

929 930 931
void UAS::requestParameters()
{
    mavlink_message_t msg;
932
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
933 934
    // Send message twice to increase chance of reception
    sendMessage(msg);
935 936
}

937
void UAS::writeParametersToStorage()
938
{
939 940 941
    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
942
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
943 944 945 946 947 948 949 950 951
    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
952 953
}

954
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
955 956
{
    // Buffers to write data to
957
    mavlink_message_t msg;
958
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
959 960
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
961
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
962 963
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
964 965
    // 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
966 967
    stream.req_message_rate = 0;
    // Start / stop the message
968
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
969 970 971 972 973
    // 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
974
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
975 976
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
977 978 979
    sendMessage(msg);
}

980
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
981 982 983
{
    // Buffers to write data to
    mavlink_message_t msg;
984
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
985
    // Select the message to request from now on
986
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
987
    // Select the update rate in Hz the message should be send
988
    stream.req_message_rate = rate;
lm's avatar
lm committed
989
    // Start / stop the message
990
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
991 992 993 994 995
    // 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
996
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
997 998
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
999 1000 1001
    sendMessage(msg);
}

1002
void UAS::enableExtendedSystemStatusTransmission(int rate)
lm's avatar
lm committed
1003
{
1004 1005 1006 1007
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1008
    stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
1009
    // Select the update rate in Hz the message should be send
1010
    stream.req_message_rate = rate;
1011
    // Start / stop the message
1012
    stream.start_stop = (rate) ? 1 : 0;
1013 1014 1015 1016 1017 1018
    // 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);
1019 1020
    // Send message twice to increase chance of reception
    sendMessage(msg);
1021
    sendMessage(msg);
lm's avatar
lm committed
1022
}
1023

1024
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1025
{
1026 1027 1028 1029 1030
#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
1031 1032 1033
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1034
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1035
    // Select the update rate in Hz the message should be send
1036
    stream.req_message_rate = rate;
1037
    // Start / stop the message
1038
    stream.start_stop = (rate) ? 1 : 0;
1039 1040 1041 1042 1043 1044
    // 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);
1045 1046
    // Send message twice to increase chance of reception
    sendMessage(msg);
1047
    sendMessage(msg);
1048
#endif
lm's avatar
lm committed
1049 1050
}

1051
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1052
{
1053 1054 1055 1056
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1057
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1058
    // Select the update rate in Hz the message should be send
1059
    stream.req_message_rate = rate;
1060
    // Start / stop the message
1061
    stream.start_stop = (rate) ? 1 : 0;
1062 1063 1064 1065 1066 1067
    // 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);
1068 1069
    // Send message twice to increase chance of reception
    sendMessage(msg);
1070
    sendMessage(msg);
lm's avatar
lm committed
1071 1072
}

1073
void UAS::enableRawSensorFusionTransmission(int rate)
lm's avatar
lm committed
1074
{
1075 1076 1077 1078
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1079
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
1080
    // Select the update rate in Hz the message should be send
1081
    stream.req_message_rate = rate;
1082
    // Start / stop the message
1083
    stream.start_stop = (rate) ? 1 : 0;
1084 1085 1086 1087 1088 1089
    // 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);
1090 1091
    // Send message twice to increase chance of reception
    sendMessage(msg);
1092
    sendMessage(msg);
1093 1094
}

1095
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1096 1097 1098 1099 1100
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1101
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1102
    // Select the update rate in Hz the message should be send
1103
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1104
    // Start / stop the message
1105
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116
    // 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);
}

1117
void UAS::enableExtra1Transmission(int rate)
pixhawk's avatar
pixhawk committed
1118 1119 1120 1121 1122
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1123
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
pixhawk's avatar
pixhawk committed
1124
    // Select the update rate in Hz the message should be send
1125
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1126
    // Start / stop the message
1127
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138
    // 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);
}

1139
void UAS::enableExtra2Transmission(int rate)
pixhawk's avatar
pixhawk committed
1140 1141 1142 1143 1144
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1145
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
pixhawk's avatar
pixhawk committed
1146
    // Select the update rate in Hz the message should be send
1147
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1148
    // Start / stop the message
1149
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160
    // 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);
}

1161
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1162 1163 1164 1165 1166
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1167
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1168
    // Select the update rate in Hz the message should be send
1169
    stream.req_message_rate = rate;
1170
    // Start / stop the message
1171
    stream.start_stop = (rate) ? 1 : 0;
1172 1173 1174 1175 1176 1177
    // 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);
1178 1179
    // Send message twice to increase chance of reception
    sendMessage(msg);
1180
    sendMessage(msg);
1181 1182
}

lm's avatar
lm committed
1183 1184 1185 1186 1187 1188 1189
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1190
void UAS::setParameter(int component, QString id, float value)
1191
{    
1192 1193 1194
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1195 1196
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1197

1198
    // Copy string into buffer, ensuring not to exceed the buffer size    
1199
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1200
    {
lm's avatar
lm committed
1201
        // String characters
1202
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1203
        {
1204
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1205 1206
        }
        // Null termination at end of string or end of buffer
1207
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1208 1209 1210 1211 1212 1213 1214 1215
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1216
    }    
1217
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1218
    sendMessage(msg);
1219 1220
}

pixhawk's avatar
pixhawk committed
1221
/**
lm's avatar
lm committed
1222
 * Launches the system
pixhawk's avatar
pixhawk committed
1223 1224 1225 1226
 *
 **/
void UAS::launch()
{
1227
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1228
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1229
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1230 1231 1232
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1233 1234 1235 1236 1237 1238 1239 1240
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1241
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1242
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1243
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1244 1245 1246
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1247 1248 1249 1250 1251 1252 1253 1254
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1255
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1256
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1257
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1258 1259 1260
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274
}

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;

lm's avatar
lm committed
1275 1276
//    if(mode == (int)MAV_MODE_MANUAL)
//    {
pixhawk's avatar
pixhawk committed
1277
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
1278
        mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
pixhawk's avatar
pixhawk committed
1279 1280 1281 1282
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;

        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
lm's avatar
lm committed
1283
//    }
pixhawk's avatar
pixhawk committed
1284 1285
}

1286 1287 1288 1289 1290
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1291 1292 1293 1294 1295
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1296

pixhawk's avatar
pixhawk committed
1297 1298
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1299

pixhawk's avatar
pixhawk committed
1300 1301 1302 1303 1304
        break;
    default:

        break;
    }
1305
//    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1306 1307 1308

}

1309

1310
/*void UAS::requestWaypoints()
1311 1312 1313 1314 1315
{
//    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
1316 1317
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1318 1319
}

pixhawk's avatar
pixhawk committed
1320 1321
void UAS::setWaypoint(Waypoint* wp)
{
1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339
//    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
1340 1341 1342 1343
}

void UAS::setWaypointActive(int id)
{
1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366
//    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!";
1367
}*/
pixhawk's avatar
pixhawk committed
1368 1369 1370 1371


void UAS::halt()
{
1372
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1373
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1374
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1375 1376 1377
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1378 1379 1380 1381
}

void UAS::go()
{
1382
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1383
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1384
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1385 1386 1387
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1388 1389 1390 1391 1392
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1393
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1394
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1395
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1396 1397 1398
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1399 1400 1401 1402 1403 1404 1405 1406
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1407
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1408
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1409
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1410 1411 1412
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437
}

/**
 * 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)
    {
1438
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1439
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1440
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1441 1442 1443
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466
        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
1467
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1468
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1469
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1470 1471 1472
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1473 1474 1475 1476
        result = true;
    }
}

1477 1478
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1479 1480 1481 1482 1483 1484
    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);
1485 1486
}

pixhawk's avatar
pixhawk committed
1487 1488 1489
/**
 * @return The name of this system as string in human-readable form
 */
1490
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530
{
    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);
    }
    //links->append(link);
    //qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
}

/**
 * @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
1531
    case NICD:
pixhawk's avatar
pixhawk committed
1532
        break;
lm's avatar
lm committed
1533
    case NIMH:
pixhawk's avatar
pixhawk committed
1534
        break;
lm's avatar
lm committed
1535
    case LIION:
pixhawk's avatar
pixhawk committed
1536
        break;
lm's avatar
lm committed
1537
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1538 1539 1540
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1541
    case LIFE:
pixhawk's avatar
pixhawk committed
1542
        break;
lm's avatar
lm committed
1543
    case AGZN:
pixhawk's avatar
pixhawk committed
1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560
        break;
    }
}

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
1561 1562 1563
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1564 1565
double UAS::getChargeLevel()
{
1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579
    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
1580 1581
}

lm's avatar
lm committed
1582 1583 1584 1585
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1586 1587
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599
        lowBattAlarm = true;
    }
}

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