UAS.cc 41.9 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41
/*=====================================================================

PIXHAWK Micro Air Vehicle Flying Robotics Toolkit

(c) 2009, 2010 PIXHAWK PROJECT  <http://pixhawk.ethz.ch>

This file is part of the PIXHAWK project

    PIXHAWK is free software: you can redistribute it and/or modify
    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.

    PIXHAWK is distributed in the hope that it will be useful,
    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
    along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.

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

/**
 * @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"
pixhawk's avatar
pixhawk committed
42
#include "GAudioOutput.h"
43 44
#include "MAVLinkProtocol.h"
#include <mavlink.h>
pixhawk's avatar
pixhawk committed
45

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

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

86
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
87 88 89 90
{
    return uasId;
}

91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107
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
    {
        if (mode > MAV_MODE_LOCKED && positionLock)
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

pixhawk's avatar
pixhawk committed
108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
    if (!links->contains(link))
    {
        addLink(link);
    }

    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
130
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
131
            {
pixhawk's avatar
pixhawk committed
132
                this->type = mavlink_msg_heartbeat_get_type(&message);
pixhawk's avatar
pixhawk committed
133 134 135 136 137 138 139 140
                emit systemTypeSet(this, type);
            }
            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
141 142
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
143 144
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
145

pixhawk's avatar
pixhawk committed
146
                // FIXME
147
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
148

pixhawk's avatar
pixhawk committed
149 150 151 152 153
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
154

pixhawk's avatar
pixhawk committed
155
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
156
                {
pixhawk's avatar
pixhawk committed
157 158 159 160
                    statechanged = true;
                    this->status = state.status;
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
161
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
162 163
                }

pixhawk's avatar
pixhawk committed
164
                if (static_cast<unsigned int>(this->mode) != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
165 166 167 168 169
                {
                    modechanged = true;
                    this->mode = state.mode;
                    QString mode;

pixhawk's avatar
pixhawk committed
170
                    switch ((unsigned int)(state.mode))
pixhawk's avatar
pixhawk committed
171 172 173 174 175 176 177 178 179 180
                    {
                    case MAV_MODE_LOCKED:
                        mode = "LOCKED MODE";
                        break;
                    case MAV_MODE_MANUAL:
                        mode = "MANUAL MODE";
                        break;
                    case MAV_MODE_AUTO:
                        mode = "AUTO MODE";
                        break;
181 182 183
                    case MAV_MODE_GUIDED:
                        mode = "GUIDED MODE";
                        break;
lm's avatar
lm committed
184 185 186
                    case MAV_MODE_READY:
                        mode = "READY";
                        break;
pixhawk's avatar
pixhawk committed
187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203
                    case MAV_MODE_TEST1:
                        mode = "TEST1 MODE";
                        break;
                    case MAV_MODE_TEST2:
                        mode = "TEST2 MODE";
                        break;
                    case MAV_MODE_TEST3:
                        mode = "TEST3 MODE";
                        break;
                    default:
                        mode = "UNINIT MODE";
                        break;
                    }

                    emit modeChanged(this->getUASID(), mode, "");
                    modeAudio = " is now in " + mode;
                }
lm's avatar
lm committed
204
                currentVoltage = state.vbat/1000.0f;
pixhawk's avatar
pixhawk committed
205
                lpVoltage = filterVoltage(currentVoltage);
pixhawk's avatar
pixhawk committed
206 207 208
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
pixhawk's avatar
pixhawk committed
209
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
pixhawk's avatar
pixhawk committed
210
                emit voltageChanged(message.sysid, state.vbat/1000.0f);
pixhawk's avatar
pixhawk committed
211

lm's avatar
lm committed
212 213 214 215 216 217 218 219 220 221 222
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
                if (chargeLevel <= 10.0f)
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
223 224 225 226
                // COMMUNICATIONS DROP RATE
                emit dropRateChanged(this->getUASID(), this->receiveDropRate, this->sendDropRate);

                // AUDIO
pixhawk's avatar
pixhawk committed
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
                if (state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
pixhawk's avatar
pixhawk committed
246 247
            }
            break;
lm's avatar
lm committed
248
        case MAVLINK_MSG_ID_AUX_STATUS:
lm's avatar
lm committed
249
            {
pixhawk's avatar
pixhawk committed
250 251
                mavlink_aux_status_t status;
                mavlink_msg_aux_status_decode(&message, &status);
252 253
                emit loadChanged(this, status.load/10.0f);
                emit valueChanged(this, "Load", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
lm's avatar
lm committed
254 255
            }
            break;
pixhawk's avatar
pixhawk committed
256
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
257
            {
pixhawk's avatar
pixhawk committed
258 259
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
260
                quint64 time = getUnixTime(raw.msec);
pixhawk's avatar
pixhawk committed
261

pixhawk's avatar
pixhawk committed
262 263 264 265 266 267 268 269 270
                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
271 272
            }
            break;
pixhawk's avatar
pixhawk committed
273
        case MAVLINK_MSG_ID_RAW_AUX:
lm's avatar
lm committed
274
            {
pixhawk's avatar
pixhawk committed
275 276
                mavlink_raw_aux_t raw;
                mavlink_msg_raw_aux_decode(&message, &raw);
277
                quint64 time = getUnixTime(0);
lm's avatar
lm committed
278
                emit valueChanged(uasId, "Pressure", raw.baro, time);
lm's avatar
lm committed
279
                emit valueChanged(uasId, "Temperature", raw.temp, time);
lm's avatar
lm committed
280 281
            }
            break;
pixhawk's avatar
pixhawk committed
282 283
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
284
            //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
285
            {
pixhawk's avatar
pixhawk committed
286 287
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
288
                quint64 time = getUnixTime(attitude.usec);
pixhawk's avatar
pixhawk committed
289 290 291 292 293 294
                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
295 296 297
                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
298
                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
299 300
            }
            break;
301 302 303 304
        case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
            {
                mavlink_vision_position_estimate_t pos;
                mavlink_msg_vision_position_estimate_decode(&message, &pos);
lm's avatar
lm committed
305 306 307 308 309 310 311
                quint64 time = getUnixTime(pos.usec);
                emit valueChanged(uasId, "vis. roll", pos.roll, time);
                emit valueChanged(uasId, "vis. pitch", pos.pitch, time);
                emit valueChanged(uasId, "vis. yaw", pos.yaw, time);
                emit valueChanged(uasId, "vis. x", pos.x, time);
                emit valueChanged(uasId, "vis. y", pos.y, time);
                emit valueChanged(uasId, "vis. z", pos.z, time);
lm's avatar
lm committed
312 313 314 315 316 317 318 319 320 321
                // FIXME Only for testing for now
                emit valueChanged(uasId, "vis. rot r1", pos.r1, time);
                emit valueChanged(uasId, "vis. rot r2", pos.r2, time);
                emit valueChanged(uasId, "vis. rot r3", pos.r3, time);
                emit valueChanged(uasId, "vis. rot r4", pos.r4, time);
                emit valueChanged(uasId, "vis. rot r5", pos.r5, time);
                emit valueChanged(uasId, "vis. rot r6", pos.r6, time);
                emit valueChanged(uasId, "vis. rot r7", pos.r7, time);
                emit valueChanged(uasId, "vis. rot r8", pos.r8, time);
                emit valueChanged(uasId, "vis. rot r9", pos.r9, time);
322 323 324 325 326 327 328
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
329 330
            }
            break;
lm's avatar
lm committed
331 332
        case MAVLINK_MSG_ID_POSITION:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
333
            //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
334
            {
pixhawk's avatar
pixhawk committed
335 336
                mavlink_position_t pos;
                mavlink_msg_position_decode(&message, &pos);
337
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
338 339 340 341 342 343 344 345 346
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
                emit valueChanged(uasId, "vx", pos.vx, time);
                emit valueChanged(uasId, "vy", pos.vy, time);
                emit valueChanged(uasId, "vz", pos.vz, time);
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
            }
            break;
347 348 349 350 351 352 353
        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
354
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
355
            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
356
            break;
357
        case MAVLINK_MSG_ID_WAYPOINT:
358
            {
359 360 361
//                mavlink_waypoint_t wp;
//                mavlink_msg_waypoint_decode(&message, &wp);
//                emit waypointUpdated(uasId, wp.id, wp.x, wp.y, wp.z, wp.yaw, wp.autocontinue, wp.active);
362
            }
pixhawk's avatar
pixhawk committed
363
            break;
364
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
365
            {
366 367 368
//                mavlink_waypoint_reached_t wp;
//                mavlink_msg_waypoint_reached_decode(&message, &wp);
//                emit waypointReached(this, wp.id);
369
            }
pixhawk's avatar
pixhawk committed
370
            break;
371
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
372 373 374
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
375
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
376 377
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
378
                int severity = mavlink_msg_statustext_get_severity(&message);
379
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
380
                //emit statusTextReceived(severity, text);
381
                emit textMessageReceived(uasId, severity, text);
lm's avatar
lm committed
382 383 384 385 386 387
            }
            break;
        case MAVLINK_MSG_ID_PATTERN_DETECTED:
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
388
                mavlink_msg_pattern_detected_get_file(&message, (int8_t*)b.data());
lm's avatar
lm committed
389 390
                b.append('\0');
                QString path = QString(b);
pixhawk's avatar
pixhawk committed
391 392
                bool detected (mavlink_msg_pattern_detected_get_detected(&message) == 1 ? true : false );
                emit detectionReceived(uasId, path, 0, 0, 0, 0, 0, 0, 0, 0, mavlink_msg_pattern_detected_get_confidence(&message), detected);
lm's avatar
lm committed
393 394
            }
            break;
pixhawk's avatar
pixhawk committed
395
        default:
lm's avatar
lm committed
396 397 398 399
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
400 401
                    //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
402 403 404
                    //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
405 406 407 408 409
            break;
        }
    }
}

410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431
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
432
    else if (time < 1261440000000000LLU)
433 434 435
    {
        if (onboardTimeOffset == 0)
        {
436
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
437
        }
438
        return time/1000 + onboardTimeOffset;
439 440 441 442 443
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
444
        return time/1000;
445 446 447
    }
}

pixhawk's avatar
pixhawk committed
448
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
449
{
pixhawk's avatar
pixhawk committed
450 451 452 453
    if (mode >= MAV_MODE_LOCKED && mode <= MAV_MODE_TEST3)
    {
        this->mode = mode;
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
454
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, (unsigned char)mode);
pixhawk's avatar
pixhawk committed
455
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
456
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << mode;
pixhawk's avatar
pixhawk committed
457
    }
pixhawk's avatar
pixhawk committed
458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474
}

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
475
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
476 477 478 479 480 481 482 483 484 485 486
    // 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
 */
487
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
488
{
489
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
490 491 492 493 494 495
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
496
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
497 498 499
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
500
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
501 502 503
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
504
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
505 506 507
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
508
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
509 510 511
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
512 513 514 515 516
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
517 518 519
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
520
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
521 522 523
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
524
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
525 526 527
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
528
    default:
pixhawk's avatar
pixhawk committed
529 530 531 532 533 534 535 536 537 538 539 540 541 542 543
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
544
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
545 546 547 548 549 550 551 552
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

553
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
554 555 556 557
{
    return commStatus;
}

558 559 560
void UAS::requestParameters()
{
    mavlink_message_t msg;
561
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
562 563
    // Send message twice to increase chance of reception
    sendMessage(msg);
564 565 566 567
}

void UAS::writeParameters()
{
lm's avatar
lm committed
568 569 570 571 572 573 574
    //mavlink_message_t msg;
    qDebug() << __FILE__ << __LINE__ << __func__ << "IS NOT IMPLEMENTED!";
}

void UAS::enableAllDataTransmission(bool enabled)
{
    // Buffers to write data to
575
    mavlink_message_t msg;
576
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
577 578
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
579
    stream.req_stream_id = 0;
lm's avatar
lm committed
580 581 582 583 584 585 586 587 588 589
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
    stream.req_message_rate = 0;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
590
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
591 592
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
593 594 595 596 597 598 599
    sendMessage(msg);
}

void UAS::enableRawSensorDataTransmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
600
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
601
    // Select the message to request from now on
602
    stream.req_stream_id = 1;
lm's avatar
lm committed
603 604 605 606 607 608 609 610 611
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
612
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
613 614
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
615 616 617 618 619
    sendMessage(msg);
}

void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
620 621 622 623 624 625 626 627 628 629 630 631 632 633 634
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 2;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 10;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
635 636
    // Send message twice to increase chance of reception
    sendMessage(msg);
637
    sendMessage(msg);
lm's avatar
lm committed
638
}
639

lm's avatar
lm committed
640 641
void UAS::enableRCChannelDataTransmission(bool enabled)
{
642 643 644 645 646 647 648 649 650 651 652 653 654 655 656
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 3;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
657 658
    // Send message twice to increase chance of reception
    sendMessage(msg);
659
    sendMessage(msg);
lm's avatar
lm committed
660 661 662 663
}

void UAS::enableRawControllerDataTransmission(bool enabled)
{
664 665 666 667 668 669 670 671 672 673 674 675 676 677 678
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 4;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
679 680
    // Send message twice to increase chance of reception
    sendMessage(msg);
681
    sendMessage(msg);
lm's avatar
lm committed
682 683 684 685
}

void UAS::enableRawSensorFusionTransmission(bool enabled)
{
686 687 688 689 690 691 692 693 694 695 696 697 698 699 700
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 5;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
701 702
    // Send message twice to increase chance of reception
    sendMessage(msg);
703
    sendMessage(msg);
704 705
}

pixhawk's avatar
pixhawk committed
706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780
void UAS::enablePositionTransmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 6;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

void UAS::enableExtra1Transmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 7;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

void UAS::enableExtra2Transmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 8;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

void UAS::enableExtra3Transmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 9;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
781 782 783 784 785 786 787 788
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
789 790
    // Send message twice to increase chance of reception
    sendMessage(msg);
791
    sendMessage(msg);
792 793 794 795 796 797 798
}

void UAS::setParameter(int component, QString id, float value)
{
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
799 800
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
801 802 803

    // Copy string into buffer, ensuring not to exceed the buffer size
    char* s = (char*)id.toStdString().c_str();
804
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
805
    {
lm's avatar
lm committed
806
        // String characters
807
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
808 809 810 811
        {
            p.param_id[i] = s[i];
        }
        // Null termination at end of string or end of buffer
812
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
813 814 815 816 817 818 819 820
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
821 822
    }
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
823
    sendMessage(msg);
824 825
}

pixhawk's avatar
pixhawk committed
826 827 828 829 830 831
/**
 * @brief Launches the system
 *
 **/
void UAS::launch()
{
832
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
833
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
834 835 836 837
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(int)MAV_ACTION_LAUNCH);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
838 839 840 841 842 843 844 845
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
846
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
847
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
848 849 850 851
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(int)MAV_ACTION_MOTORS_START);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
852 853 854 855 856 857 858 859
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
860
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
861
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
862 863 864 865
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(int)MAV_ACTION_MOTORS_STOP);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882
}

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;

    if(mode == MAV_MODE_MANUAL)
    {
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
883
        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
884 885 886 887 888 889 890 891 892 893 894 895
        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());
    }
}

void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
896

pixhawk's avatar
pixhawk committed
897 898
        break;
    case 1:
pixhawk's avatar
pixhawk committed
899

pixhawk's avatar
pixhawk committed
900 901 902 903 904 905 906 907 908
        break;
    default:

        break;
    }
    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";

}

909 910 911 912 913 914 915 916 917 918

void UAS::requestWaypoints()
{
//    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);
//    qDebug() << "UAS Request WPs";
}

pixhawk's avatar
pixhawk committed
919 920
void UAS::setWaypoint(Waypoint* wp)
{
921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938
//    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
939 940 941 942
}

void UAS::setWaypointActive(int id)
{
943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965
//    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!";
pixhawk's avatar
pixhawk committed
966 967 968 969 970
}


void UAS::halt()
{
971
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
972
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
973 974 975 976
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_HALT);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
977 978 979 980
}

void UAS::go()
{
981
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
982
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
983 984 985 986
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_CONTINUE);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
987 988 989 990 991
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
992
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
993
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
994 995 996 997
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_RETURN);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
998 999 1000 1001 1002 1003 1004 1005
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1006
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1007
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1008 1009 1010 1011
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_EMCY_LAND);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036
}

/**
 * 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)
    {
1037
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1038
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1039 1040 1041 1042
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_EMCY_KILL);
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065
        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
1066
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1067
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1068 1069 1070 1071
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_SHUTDOWN);
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1072 1073 1074 1075 1076 1077 1078
        result = true;
    }
}

/**
 * @return The name of this system as string in human-readable form
 */
1079
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119
{
    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
1120
    case NICD:
pixhawk's avatar
pixhawk committed
1121
        break;
lm's avatar
lm committed
1122
    case NIMH:
pixhawk's avatar
pixhawk committed
1123
        break;
lm's avatar
lm committed
1124
    case LIION:
pixhawk's avatar
pixhawk committed
1125
        break;
lm's avatar
lm committed
1126
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1127 1128 1129
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1130
    case LIFE:
pixhawk's avatar
pixhawk committed
1131
        break;
lm's avatar
lm committed
1132
    case AGZN:
pixhawk's avatar
pixhawk committed
1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149
        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
1150 1151 1152
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1153 1154
double UAS::getChargeLevel()
{
1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168
    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
1169 1170
}

lm's avatar
lm committed
1171 1172 1173 1174
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1175 1176
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188
        lowBattAlarm = true;
    }
}

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