UAS.cc 42.6 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) : UASInterface(),
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
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
77
    setBattery(LIPOLY, 3);
78 79
    statusTimeout->setInterval(500);
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
pixhawk's avatar
pixhawk committed
80 81 82 83 84 85 86
}

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

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

92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108
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
109 110 111 112 113 114 115 116 117 118 119 120
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

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

121
    //qDebug() << "UAS RECEIVED" << message.sysid << message.compid << message.msgid;
pixhawk's avatar
pixhawk committed
122

pixhawk's avatar
pixhawk committed
123 124 125 126 127 128 129 130 131 132
    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
133
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
134
            {
pixhawk's avatar
pixhawk committed
135
                this->type = mavlink_msg_heartbeat_get_type(&message);
pixhawk's avatar
pixhawk committed
136 137 138 139 140 141 142 143
                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
144 145
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
146 147
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
148

pixhawk's avatar
pixhawk committed
149
                // FIXME
150
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
151

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

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

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

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

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

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

lm's avatar
lm committed
226
                // COMMUNICATIONS DROP RATE
227
                emit dropRateChanged(this->getUASID(), state.packet_drop);
228
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
229 230

                // AUDIO
pixhawk's avatar
pixhawk committed
231 232 233 234 235 236 237 238 239 240
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio;
                }
241
                if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
pixhawk's avatar
pixhawk committed
242 243 244 245 246 247 248 249
                {
                    GAudioOutput::instance()->startEmergency();
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
                    GAudioOutput::instance()->say(audiostring);
                }
pixhawk's avatar
pixhawk committed
250 251 252
            }
            break;
        case MAVLINK_MSG_ID_RAW_IMU:
pixhawk's avatar
pixhawk committed
253
            {
pixhawk's avatar
pixhawk committed
254 255
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
256
                quint64 time = getUnixTime(raw.usec);
pixhawk's avatar
pixhawk committed
257

pixhawk's avatar
pixhawk committed
258 259 260 261 262 263 264 265 266
                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
267 268 269 270
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
271
            //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
272
            {
pixhawk's avatar
pixhawk committed
273 274
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
275
                quint64 time = getUnixTime(attitude.usec);
pixhawk's avatar
pixhawk committed
276 277 278 279 280 281
                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
282 283 284
                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
285
                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
286 287
            }
            break;
288
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
289
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
290
            //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
291
            {
292 293
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
294
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
295 296 297 298 299 300 301 302 303
                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;
304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325
        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);
                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);
            }
            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);
326 327 328

                // SANITY CHECK
                // only accept values in a realistic range
pixhawk's avatar
pixhawk committed
329 330
               // quint64 time = getUnixTime(pos.usec);
                quint64 time = MG::TIME::getGroundTimeNow();
331 332
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
333 334 335 336 337 338 339
                // Check for NaN
                int alt = pos.alt;
                if (alt != alt)
                {
                    alt = 0;
                    emit textMessageReceived(uasId, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                }
340
                emit valueChanged(uasId, "alt", pos.alt, time);
341 342 343 344 345 346 347 348 349 350 351 352
                // 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, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                }
                emit globalPositionChanged(this, pos.lon, pos.lat, alt, time);
353 354
            }
            break;
lm's avatar
lm committed
355 356 357 358
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
359
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
360
                {
lm's avatar
lm committed
361
                    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
362 363 364
                }
            }
            break;
365 366 367 368 369 370 371
        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
372
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
373
            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
374
            break;
375
        case MAVLINK_MSG_ID_WAYPOINT:
376
            {
377 378 379
//                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);
380
            }
pixhawk's avatar
pixhawk committed
381
            break;
382
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
383
            {
384 385 386
//                mavlink_waypoint_reached_t wp;
//                mavlink_msg_waypoint_reached_decode(&message, &wp);
//                emit waypointReached(this, wp.id);
387
            }
pixhawk's avatar
pixhawk committed
388
            break;
389
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
390 391 392
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
393
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
394 395
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
396
                int severity = mavlink_msg_statustext_get_severity(&message);
397
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
398
                //emit statusTextReceived(severity, text);
399
                emit textMessageReceived(uasId, severity, text);
lm's avatar
lm committed
400 401
            }
            break;
pixhawk's avatar
pixhawk committed
402
        default:
lm's avatar
lm committed
403 404 405 406
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
407 408
                    //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
409 410 411
                    //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
412 413 414 415 416
            break;
        }
    }
}

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

pixhawk's avatar
pixhawk committed
455
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
456
{
lm's avatar
lm committed
457
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_TEST3)
pixhawk's avatar
pixhawk committed
458 459
    {
        mavlink_message_t msg;
lm's avatar
lm committed
460
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
461
        sendMessage(msg);
lm's avatar
lm committed
462
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
463
    }
pixhawk's avatar
pixhawk committed
464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480
}

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

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



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
550
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
551 552 553 554 555 556 557 558
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

559
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
560 561 562 563
{
    return commStatus;
}

564 565 566
void UAS::requestParameters()
{
    mavlink_message_t msg;
567
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
568 569
    // Send message twice to increase chance of reception
    sendMessage(msg);
570 571 572 573
}

void UAS::writeParameters()
{
lm's avatar
lm committed
574 575 576 577 578 579 580
    //mavlink_message_t msg;
    qDebug() << __FILE__ << __LINE__ << __func__ << "IS NOT IMPLEMENTED!";
}

void UAS::enableAllDataTransmission(bool enabled)
{
    // Buffers to write data to
581
    mavlink_message_t msg;
582
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
583 584
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
585
    stream.req_stream_id = 0;
lm's avatar
lm committed
586 587 588 589 590 591 592 593 594 595
    // 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
596
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
597 598
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
599 600 601 602 603 604 605
    sendMessage(msg);
}

void UAS::enableRawSensorDataTransmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
606
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
607
    // Select the message to request from now on
608
    stream.req_stream_id = 1;
lm's avatar
lm committed
609 610 611 612 613 614 615 616 617
    // 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
618
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
619 620
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
621 622 623 624 625
    sendMessage(msg);
}

void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
626 627 628 629 630 631 632 633 634 635 636 637 638 639 640
    // 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);
641 642
    // Send message twice to increase chance of reception
    sendMessage(msg);
643
    sendMessage(msg);
lm's avatar
lm committed
644
}
645

lm's avatar
lm committed
646 647
void UAS::enableRCChannelDataTransmission(bool enabled)
{
648 649 650 651 652 653 654 655 656 657 658 659 660 661 662
    // 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);
663 664
    // Send message twice to increase chance of reception
    sendMessage(msg);
665
    sendMessage(msg);
lm's avatar
lm committed
666 667 668 669
}

void UAS::enableRawControllerDataTransmission(bool enabled)
{
670 671 672 673 674 675 676 677 678 679 680 681 682 683 684
    // 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);
685 686
    // Send message twice to increase chance of reception
    sendMessage(msg);
687
    sendMessage(msg);
lm's avatar
lm committed
688 689 690 691
}

void UAS::enableRawSensorFusionTransmission(bool enabled)
{
692 693 694 695 696 697 698 699 700 701 702 703 704 705 706
    // 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);
707 708
    // Send message twice to increase chance of reception
    sendMessage(msg);
709
    sendMessage(msg);
710 711
}

pixhawk's avatar
pixhawk committed
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 781 782 783 784 785 786
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;
787 788 789 790 791 792 793 794
    // 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);
795 796
    // Send message twice to increase chance of reception
    sendMessage(msg);
797
    sendMessage(msg);
798 799 800 801 802 803 804
}

void UAS::setParameter(int component, QString id, float value)
{
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
805 806
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
807 808 809

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

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

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

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

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
886
    if(mode == (int)MAV_MODE_MANUAL)
pixhawk's avatar
pixhawk committed
887 888
    {
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
889
        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
890 891 892 893 894 895 896 897 898 899 900 901
        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
902

pixhawk's avatar
pixhawk committed
903 904
        break;
    case 1:
pixhawk's avatar
pixhawk committed
905

pixhawk's avatar
pixhawk committed
906 907 908 909 910 911 912 913 914
        break;
    default:

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

}

915 916 917 918 919 920 921 922 923 924

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
925 926
void UAS::setWaypoint(Waypoint* wp)
{
927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944
//    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
945 946 947 948
}

void UAS::setWaypointActive(int id)
{
949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971
//    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
972 973 974 975 976
}


void UAS::halt()
{
977
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
978
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
979 980 981 982
    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
983 984 985 986
}

void UAS::go()
{
987
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
988
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
989 990 991 992
    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
993 994 995 996 997
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
998
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
999
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1000 1001 1002 1003
    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
1004 1005 1006 1007 1008 1009 1010 1011
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1012
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1013
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1014 1015 1016 1017
    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
1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042
}

/**
 * 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)
    {
1043
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1044
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1045 1046 1047 1048
        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
1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071
        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
1072
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1073
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1074 1075 1076 1077
        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
1078 1079 1080 1081 1082 1083 1084
        result = true;
    }
}

/**
 * @return The name of this system as string in human-readable form
 */
1085
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
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 1120 1121 1122 1123 1124 1125
{
    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
1126
    case NICD:
pixhawk's avatar
pixhawk committed
1127
        break;
lm's avatar
lm committed
1128
    case NIMH:
pixhawk's avatar
pixhawk committed
1129
        break;
lm's avatar
lm committed
1130
    case LIION:
pixhawk's avatar
pixhawk committed
1131
        break;
lm's avatar
lm committed
1132
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1133 1134 1135
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1136
    case LIFE:
pixhawk's avatar
pixhawk committed
1137
        break;
lm's avatar
lm committed
1138
    case AGZN:
pixhawk's avatar
pixhawk committed
1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155
        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
1156 1157 1158
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1159 1160
double UAS::getChargeLevel()
{
1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174
    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
1175 1176
}

lm's avatar
lm committed
1177 1178 1179 1180
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1181 1182
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194
        lowBattAlarm = true;
    }
}

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