UAS.cc 43.8 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),
54
        waypointManager(*this),
pixhawk's avatar
pixhawk committed
55
        thrustSum(0),
pixhawk's avatar
pixhawk committed
56
        thrustMax(10),
pixhawk's avatar
pixhawk committed
57
        startVoltage(0),
58 59
        currentVoltage(12.0f),
        lpVoltage(12.0f),
pixhawk's avatar
pixhawk committed
60 61 62
        mode(MAV_MODE_UNINIT),
        status(MAV_STATE_UNINIT),
        onboardTimeOffset(0),
pixhawk's avatar
pixhawk committed
63 64 65 66
        controlRollManual(true),
        controlPitchManual(true),
        controlYawManual(true),
        controlThrustManual(true),
pixhawk's avatar
pixhawk committed
67 68 69
        manualRollAngle(0),
        manualPitchAngle(0),
        manualYawAngle(0),
lm's avatar
lm committed
70 71
        manualThrust(0),
        receiveDropRate(0),
lm's avatar
lm committed
72
        sendDropRate(0),
73 74 75
        lowBattAlarm(false),
        positionLock(false),
        statusTimeout(new QTimer(this))
pixhawk's avatar
pixhawk committed
76
{
77
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
78
    setBattery(LIPOLY, 3);
79 80
    statusTimeout->setInterval(500);
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
pixhawk's avatar
pixhawk committed
81 82 83 84 85 86 87
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

                // SANITY CHECK
                // only accept values in a realistic range
pixhawk's avatar
pixhawk committed
331 332
               // quint64 time = getUnixTime(pos.usec);
                quint64 time = MG::TIME::getGroundTimeNow();
333 334
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
335 336 337 338 339 340 341
                // Check for NaN
                int alt = pos.alt;
                if (alt != alt)
                {
                    alt = 0;
                    emit textMessageReceived(uasId, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                }
342
                emit valueChanged(uasId, "alt", pos.alt, time);
343 344 345 346 347 348 349 350 351 352 353 354
                // 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);
355 356
            }
            break;
lm's avatar
lm committed
357 358 359 360
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
361
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
362
                {
lm's avatar
lm committed
363
                    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
364 365 366
                }
            }
            break;
367 368 369 370 371 372 373
        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
374
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
375
            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
376
            break;
pixhawk's avatar
pixhawk committed
377 378 379 380 381

        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
382 383 384 385
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
386 387 388
            }
            break;

389
        case MAVLINK_MSG_ID_WAYPOINT:
390
            {
391 392
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
393 394 395 396
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
397
            }
pixhawk's avatar
pixhawk committed
398
            break;
pixhawk's avatar
pixhawk committed
399 400 401 402 403

        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
404 405 406 407
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
408 409 410
            }
            break;

411
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
412
            {
413 414 415
//                mavlink_waypoint_reached_t wp;
//                mavlink_msg_waypoint_reached_decode(&message, &wp);
//                emit waypointReached(this, wp.id);
416
            }
pixhawk's avatar
pixhawk committed
417
            break;
418
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
419 420 421
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
422
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
423 424
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
425
                int severity = mavlink_msg_statustext_get_severity(&message);
426
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
427
                //emit statusTextReceived(severity, text);
428
                emit textMessageReceived(uasId, severity, text);
lm's avatar
lm committed
429 430
            }
            break;
pixhawk's avatar
pixhawk committed
431
        default:
lm's avatar
lm committed
432 433 434 435
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
436 437
                    //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
438 439 440
                    //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
441 442 443 444 445
            break;
        }
    }
}

446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467
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
468
    else if (time < 1261440000000000LLU)
469 470 471
    {
        if (onboardTimeOffset == 0)
        {
472
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
473
        }
474
        return time/1000 + onboardTimeOffset;
475 476 477 478 479
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
480
        return time/1000;
481 482 483
    }
}

pixhawk's avatar
pixhawk committed
484
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
485
{
lm's avatar
lm committed
486
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_TEST3)
pixhawk's avatar
pixhawk committed
487 488
    {
        mavlink_message_t msg;
lm's avatar
lm committed
489
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
490
        sendMessage(msg);
lm's avatar
lm committed
491
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
492
    }
pixhawk's avatar
pixhawk committed
493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509
}

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
510
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
511 512 513 514 515 516 517 518 519 520 521
    // 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
 */
522
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
523
{
524
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
525 526 527 528 529 530
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
531
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
532 533 534
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
535
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
536 537 538
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
539
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
540 541 542
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
543
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
544 545 546
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
547 548 549 550 551
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
552 553 554
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
555
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
556 557 558
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
559
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
560 561 562
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
563
    default:
pixhawk's avatar
pixhawk committed
564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
579
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
580 581 582 583 584 585 586 587
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

588
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
589 590 591 592
{
    return commStatus;
}

593 594 595
void UAS::requestParameters()
{
    mavlink_message_t msg;
596
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
597 598
    // Send message twice to increase chance of reception
    sendMessage(msg);
599 600 601 602
}

void UAS::writeParameters()
{
lm's avatar
lm committed
603 604 605 606 607 608 609
    //mavlink_message_t msg;
    qDebug() << __FILE__ << __LINE__ << __func__ << "IS NOT IMPLEMENTED!";
}

void UAS::enableAllDataTransmission(bool enabled)
{
    // Buffers to write data to
610
    mavlink_message_t msg;
611
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
612 613
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
614
    stream.req_stream_id = 0;
lm's avatar
lm committed
615 616 617 618 619 620 621 622 623 624
    // 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
625
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
626 627
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
628 629 630 631 632 633 634
    sendMessage(msg);
}

void UAS::enableRawSensorDataTransmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
635
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
636
    // Select the message to request from now on
637
    stream.req_stream_id = 1;
lm's avatar
lm committed
638 639 640 641 642 643 644 645 646
    // 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
647
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
648 649
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
650 651 652 653 654
    sendMessage(msg);
}

void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
655 656 657 658 659 660 661 662 663 664 665 666 667 668 669
    // 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);
670 671
    // Send message twice to increase chance of reception
    sendMessage(msg);
672
    sendMessage(msg);
lm's avatar
lm committed
673
}
674

lm's avatar
lm committed
675 676
void UAS::enableRCChannelDataTransmission(bool enabled)
{
677 678 679 680 681 682 683 684 685 686 687 688 689 690 691
    // 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);
692 693
    // Send message twice to increase chance of reception
    sendMessage(msg);
694
    sendMessage(msg);
lm's avatar
lm committed
695 696 697 698
}

void UAS::enableRawControllerDataTransmission(bool enabled)
{
699 700 701 702 703 704 705 706 707 708 709 710 711 712 713
    // 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);
714 715
    // Send message twice to increase chance of reception
    sendMessage(msg);
716
    sendMessage(msg);
lm's avatar
lm committed
717 718 719 720
}

void UAS::enableRawSensorFusionTransmission(bool enabled)
{
721 722 723 724 725 726 727 728 729 730 731 732 733 734 735
    // 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);
736 737
    // Send message twice to increase chance of reception
    sendMessage(msg);
738
    sendMessage(msg);
739 740
}

pixhawk's avatar
pixhawk committed
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 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815
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;
816 817 818 819 820 821 822 823
    // 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);
824 825
    // Send message twice to increase chance of reception
    sendMessage(msg);
826
    sendMessage(msg);
827 828 829 830 831 832 833
}

void UAS::setParameter(int component, QString id, float value)
{
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
834 835
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
836 837 838

    // Copy string into buffer, ensuring not to exceed the buffer size
    char* s = (char*)id.toStdString().c_str();
839
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
840
    {
lm's avatar
lm committed
841
        // String characters
842
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
843 844 845 846
        {
            p.param_id[i] = s[i];
        }
        // Null termination at end of string or end of buffer
847
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
848 849 850 851 852 853 854 855
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
856 857
    }
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
858
    sendMessage(msg);
859 860
}

pixhawk's avatar
pixhawk committed
861 862 863 864 865 866
/**
 * @brief Launches the system
 *
 **/
void UAS::launch()
{
867
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
868
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
lm's avatar
lm committed
869
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_LAUNCH);
870 871 872
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
873 874 875 876 877 878 879 880
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
881
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
882
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
lm's avatar
lm committed
883
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_MOTORS_START);
884 885 886
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
887 888 889 890 891 892 893 894
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
895
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
896
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
lm's avatar
lm committed
897
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_MOTORS_STOP);
898 899 900
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
901 902 903 904 905 906 907 908 909 910 911 912 913 914
}

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
915
    if(mode == (int)MAV_MODE_MANUAL)
pixhawk's avatar
pixhawk committed
916 917
    {
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
918
        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
919 920 921 922 923 924 925 926 927 928 929 930
        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
931

pixhawk's avatar
pixhawk committed
932 933
        break;
    case 1:
pixhawk's avatar
pixhawk committed
934

pixhawk's avatar
pixhawk committed
935 936 937 938 939 940 941 942 943
        break;
    default:

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

}

944

945
/*void UAS::requestWaypoints()
946 947 948 949 950
{
//    mavlink_message_t msg;
//    mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25);
//    // Send message twice to increase chance of reception
//    sendMessage(msg);
pixhawk's avatar
pixhawk committed
951 952
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
953 954
}

pixhawk's avatar
pixhawk committed
955 956
void UAS::setWaypoint(Waypoint* wp)
{
957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974
//    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
975 976 977 978
}

void UAS::setWaypointActive(int id)
{
979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001
//    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!";
1002
}*/
pixhawk's avatar
pixhawk committed
1003 1004 1005 1006


void UAS::halt()
{
1007
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1008
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1009 1010 1011 1012
    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
1013 1014 1015 1016
}

void UAS::go()
{
1017
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1018
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1019 1020 1021 1022
    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
1023 1024 1025 1026 1027
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1028
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1029
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1030 1031 1032 1033
    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
1034 1035 1036 1037 1038 1039 1040 1041
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1042
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1043
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1044 1045 1046 1047
    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
1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072
}

/**
 * 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)
    {
1073
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1074
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1075 1076 1077 1078
        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
1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101
        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
1102
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1103
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1104 1105 1106 1107
        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
1108 1109 1110 1111 1112 1113 1114
        result = true;
    }
}

/**
 * @return The name of this system as string in human-readable form
 */
1115
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155
{
    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
1156
    case NICD:
pixhawk's avatar
pixhawk committed
1157
        break;
lm's avatar
lm committed
1158
    case NIMH:
pixhawk's avatar
pixhawk committed
1159
        break;
lm's avatar
lm committed
1160
    case LIION:
pixhawk's avatar
pixhawk committed
1161
        break;
lm's avatar
lm committed
1162
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1163 1164 1165
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1166
    case LIFE:
pixhawk's avatar
pixhawk committed
1167
        break;
lm's avatar
lm committed
1168
    case AGZN:
pixhawk's avatar
pixhawk committed
1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185
        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
1186 1187 1188
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1189 1190
double UAS::getChargeLevel()
{
1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204
    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
1205 1206
}

lm's avatar
lm committed
1207 1208 1209 1210
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1211 1212
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224
        lowBattAlarm = true;
    }
}

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