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

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

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

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

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

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

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

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

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

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

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

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

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

103 104 105 106 107 108 109 110 111 112
void UAS::updateState()
{
    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
    if (positionLock)
    {
        positionLock = false;
    }
    else
    {
pixhawk's avatar
pixhawk committed
113
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
114 115 116 117 118 119
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

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

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

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

pixhawk's avatar
pixhawk committed
139 140 141 142 143 144 145 146 147 148
    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
149
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
150
            {
pixhawk's avatar
pixhawk committed
151
                this->type = mavlink_msg_heartbeat_get_type(&message);
pixhawk's avatar
pixhawk committed
152 153 154 155 156 157 158 159
                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
160 161
        case MAVLINK_MSG_ID_SYS_STATUS:
            {
pixhawk's avatar
pixhawk committed
162 163
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
pixhawk's avatar
pixhawk committed
164

pixhawk's avatar
pixhawk committed
165
                // FIXME
166
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
167

pixhawk's avatar
pixhawk committed
168 169 170 171 172
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
173

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

lm's avatar
lm committed
186
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
187 188
                {
                    modechanged = true;
lm's avatar
lm committed
189
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
190 191
                    QString mode;

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

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

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

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

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

pixhawk's avatar
pixhawk committed
280 281 282 283 284 285 286 287 288
                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
289 290 291 292
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
293
            //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
294
            {
pixhawk's avatar
pixhawk committed
295 296
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
297
                quint64 time = getUnixTime(attitude.usec);
lm's avatar
lm committed
298 299 300
                roll = attitude.roll;
                pitch = attitude.pitch;
                yaw = attitude.yaw;
pixhawk's avatar
pixhawk committed
301 302 303 304 305 306
                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
307 308 309
                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
310
                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
311 312
            }
            break;
313
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
314
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
315
            //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
316
            {
317 318
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
319
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
320 321 322
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
lm's avatar
lm committed
323 324 325
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
326 327 328
                emit valueChanged(uasId, "Vx", pos.vx, time);
                emit valueChanged(uasId, "Vy", pos.vy, time);
                emit valueChanged(uasId, "Vz", pos.vz, time);
lm's avatar
lm committed
329
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
330 331
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
332 333 334 335 336 337 338
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
339 340
            }
            break;
341 342 343 344 345 346 347
        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);
348 349 350
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
351 352 353 354 355 356 357
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
                emit valueChanged(uasId, "alt", pos.alt, time);
                emit valueChanged(uasId, "g-vx", pos.vx, time);
                emit valueChanged(uasId, "g-vy", pos.vy, time);
                emit valueChanged(uasId, "g-vz", pos.vz, time);
                emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
pixhawk's avatar
pixhawk committed
358 359 360 361 362 363 364 365
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
366 367 368 369 370

                // Send to patch antenna
                mavlink_message_t msg;
                mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
                sendMessage(msg);
371 372 373 374 375 376 377 378
            }
            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);
379 380 381

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

385 386
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
lm's avatar
lm committed
387

lm's avatar
lm committed
388
                if (pos.fix_type > 0)
389
                {
Laurens Mackay's avatar
Laurens Mackay committed
390
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
lm's avatar
lm committed
391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt)
                    {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "alt", pos.alt, time);
                    // Smaller than threshold and not NaN
                    if (pos.v < 1000000 && pos.v == pos.v)
                    {
                        emit valueChanged(uasId, "speed", pos.v, time);
                        //qDebug() << "GOT GPS RAW";
                        emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
                    }
411
                }
412 413
            }
            break;
lm's avatar
lm committed
414 415 416 417
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
418
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
419
                {
lm's avatar
lm committed
420
                    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
421 422 423
                }
            }
            break;
424 425 426 427 428 429 430
        case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
            {
                mavlink_gps_local_origin_set_t pos;
                mavlink_msg_gps_local_origin_set_decode(&message, &pos);
                // FIXME Emit to other components
            }
            break;
431
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
lm's avatar
lm committed
432
            {
433 434
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
pixhawk's avatar
pixhawk committed
435
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458
                emit remoteControlChannelRawChanged(0, channels.chan1_raw);
                emit remoteControlChannelRawChanged(1, channels.chan2_raw);
                emit remoteControlChannelRawChanged(2, channels.chan3_raw);
                emit remoteControlChannelRawChanged(3, channels.chan4_raw);
                emit remoteControlChannelRawChanged(4, channels.chan5_raw);
                emit remoteControlChannelRawChanged(5, channels.chan6_raw);
                emit remoteControlChannelRawChanged(6, channels.chan7_raw);
                emit remoteControlChannelRawChanged(7, channels.chan8_raw);
            }
            break;
        case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
                mavlink_rc_channels_scaled_t channels;
                mavlink_msg_rc_channels_scaled_decode(&message, &channels);
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
                emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f);
lm's avatar
lm committed
459 460
            }
            break;
461 462 463 464 465 466 467
        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
468
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
469
            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
470
            break;
471 472 473 474 475
        case MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT:
            {
                mavlink_attitude_controller_output_t out;
                mavlink_msg_attitude_controller_output_decode(&message, &out);
                quint64 time = MG::TIME::getGroundTimeNowUsecs();
lm's avatar
lm committed
476
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
477 478 479 480 481 482 483 484 485
                emit valueChanged(uasId, "att control roll", out.roll, time/1000.0f);
                emit valueChanged(uasId, "att control pitch", out.pitch, time/1000.0f);
                emit valueChanged(uasId, "att control yaw", out.yaw, time/1000.0f);
            }
            break;
        case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
            {
                mavlink_position_controller_output_t out;
                mavlink_msg_position_controller_output_decode(&message, &out);
486
                quint64 time = MG::TIME::getGroundTimeNow();
487
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
488 489 490
                emit valueChanged(uasId, "pos control x", out.x, time);
                emit valueChanged(uasId, "pos control y", out.y, time);
                emit valueChanged(uasId, "pos control z", out.z, time);
491 492
            }
            break;
pixhawk's avatar
pixhawk committed
493 494 495 496
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
497 498 499 500
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
501 502 503
            }
            break;

504
        case MAVLINK_MSG_ID_WAYPOINT:
505
            {
506 507
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
508
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
509 510 511 512
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
513
            }
pixhawk's avatar
pixhawk committed
514
            break;
pixhawk's avatar
pixhawk committed
515

516 517 518 519 520 521 522 523 524 525 526
        case MAVLINK_MSG_ID_WAYPOINT_ACK:
            {
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
            }
            break;

pixhawk's avatar
pixhawk committed
527 528 529 530
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
531 532 533 534
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
535 536 537
            }
            break;

538
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
539
            {
pixhawk's avatar
pixhawk committed
540 541 542
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
543
            }
pixhawk's avatar
pixhawk committed
544
            break;
pixhawk's avatar
pixhawk committed
545

546
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
547
            {
548 549 550
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
551
            }
pixhawk's avatar
pixhawk committed
552
            break;
pixhawk's avatar
pixhawk committed
553

554 555 556 557 558 559 560
        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
                mavlink_local_position_setpoint_t p;
                mavlink_msg_local_position_setpoint_decode(&message, &p);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
            }
            break;
pixhawk's avatar
pixhawk committed
561

562
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
563 564 565
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
566
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
567 568
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
569
                int severity = mavlink_msg_statustext_get_severity(&message);
570
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
571
                //emit statusTextReceived(severity, text);
572
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
573 574
            }
            break;
575 576 577 578 579 580 581 582 583 584 585
    case MAVLINK_MSG_ID_DEBUG_VECT:
            {
                mavlink_debug_vect_t vect;
                mavlink_msg_debug_vect_decode(&message, &vect);
                QString str((const char*)vect.name);
                quint64 time = getUnixTime(vect.usec);
                emit valueChanged(uasId, str+".x", vect.x, time);
                emit valueChanged(uasId, str+".y", vect.y, time);
                emit valueChanged(uasId, str+".z", vect.z, time);
            }
            break;
586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601
//#ifdef MAVLINK_ENABLED_PIXHAWK
//            case MAVLINK_MSG_ID_POINT_OF_INTEREST:
//            {
//                mavlink_point_of_interest_t poi;
//                mavlink_msg_point_of_interest_decode(&message, &poi);
//                emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
//            }
//            break;
//            case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
//            {
//                mavlink_point_of_interest_connection_t poi;
//                mavlink_msg_point_of_interest_connection_decode(&message, &poi);
//                emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
//            }
//            break;
//#endif
lm's avatar
lm committed
602
#ifdef MAVLINK_ENABLED_UALBERTA
603 604 605 606 607 608 609 610 611 612 613 614 615
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = MG::TIME::getGroundTimeNow();
                emit valueChanged(uasId, "b_f[0]", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", bias.gyro_2, time);
            }
            break;
616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645
       case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
                QVector<float> aileron;
                QVector<float> elevator;
                QVector<float> rudder;
                QVector<float> gyro;
                QVector<float> pitch;
                QVector<float> throttle;

                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
                    aileron << radioMsg.aileron[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
                    elevator << radioMsg.elevator[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
                    rudder << radioMsg.rudder[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
                    gyro << radioMsg.gyro[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
                    pitch << radioMsg.pitch[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
                    throttle << radioMsg.throttle[i];

                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron,
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
            break;

646
#endif
pixhawk's avatar
pixhawk committed
647
        default:
lm's avatar
lm committed
648 649 650 651
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
652 653
                    //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
654 655 656
                    //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
657 658 659 660 661
            break;
        }
    }
}

662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691
void UAS::setLocalOriginAtCurrentGPSPosition()
{

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

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


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

pixhawk's avatar
pixhawk committed
692 693
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
694
    #ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
695
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
696 697
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
698
#endif
pixhawk's avatar
pixhawk committed
699 700
}

pixhawk's avatar
pixhawk committed
701 702
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
703
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
704 705 706 707 708 709 710 711 712 713 714 715 716
  mavlink_message_t msg;
  mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
  sendMessage(msg);
#endif
}

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

lm's avatar
lm committed
717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737
void UAS::startDataRecording()
{
  mavlink_message_t msg;
  mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
  sendMessage(msg);
}

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

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

pixhawk's avatar
pixhawk committed
738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758
void UAS::startMagnetometerCalibration()
{
    mavlink_message_t msg;
    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_MAG);
    sendMessage(msg);
}

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

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

759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780
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
781
#ifndef _MSVC_VER
782
    else if (time < 1261440000000000LLU)
783
#else
784
    else if (time < 1261440000000000)
785
#endif
786 787 788
    {
        if (onboardTimeOffset == 0)
        {
789
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
790
        }
791
        return time/1000 + onboardTimeOffset;
792 793 794 795 796
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
797
        return time/1000;
798 799 800
    }
}

pixhawk's avatar
pixhawk committed
801
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
802
{
lm's avatar
lm committed
803
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
pixhawk's avatar
pixhawk committed
804 805
    {
        mavlink_message_t msg;
lm's avatar
lm committed
806
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
807
        sendMessage(msg);
lm's avatar
lm committed
808
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
809
    }
pixhawk's avatar
pixhawk committed
810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826
}

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
827
    int len = mavlink_msg_to_send_buffer(buffer, &message);
828
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
829 830 831 832 833 834 835 836 837 838 839
    // 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
 */
840
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
841
{
842
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
843 844 845 846 847 848
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
849
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
850 851 852
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
853
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
854 855 856
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
857
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
858 859 860
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
861
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
862 863 864
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
865 866 867 868 869
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
870 871 872
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
873
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
874 875 876
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
877
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
878 879 880
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
881
    default:
pixhawk's avatar
pixhawk committed
882 883 884 885 886 887 888 889 890 891 892 893 894 895 896
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
897
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
898 899 900 901 902 903 904 905
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

906
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
907 908 909 910
{
    return commStatus;
}

911 912 913
void UAS::requestParameters()
{
    mavlink_message_t msg;
914
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
915 916
    // Send message twice to increase chance of reception
    sendMessage(msg);
917 918
}

919
void UAS::writeParametersToStorage()
920
{
921 922 923
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE);
unknown's avatar
unknown committed
924
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
925 926 927 928 929 930 931 932 933
    sendMessage(msg);
}

void UAS::readParametersFromStorage()
{
    mavlink_message_t msg;
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(uint8_t)MAV_ACTION_STORAGE_READ);
    sendMessage(msg);
lm's avatar
lm committed
934 935
}

936
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
937 938
{
    // Buffers to write data to
939
    mavlink_message_t msg;
940
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
941 942
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
943
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
944 945
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
946 947
    // TODO: use 0 to turn off and get rid of enable/disable? will require
    //  a different magic flag for turning on defaults, possibly something really high like 1111 ?
lm's avatar
lm committed
948 949
    stream.req_message_rate = 0;
    // Start / stop the message
950
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
951 952 953 954 955
    // 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
956
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
957 958
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
959 960 961
    sendMessage(msg);
}

962
void UAS::enableRawSensorDataTransmission(int rate)
lm's avatar
lm committed
963 964 965
{
    // Buffers to write data to
    mavlink_message_t msg;
966
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
967
    // Select the message to request from now on
968
    stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
lm's avatar
lm committed
969
    // Select the update rate in Hz the message should be send
970
    stream.req_message_rate = rate;
lm's avatar
lm committed
971
    // Start / stop the message
972
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
973 974 975 976 977
    // 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
978
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
979 980
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
981 982 983
    sendMessage(msg);
}

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

1006
void UAS::enableRCChannelDataTransmission(int rate)
lm's avatar
lm committed
1007
{
1008 1009 1010 1011 1012
#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
    mavlink_message_t msg;
    mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
    sendMessage(msg);
#else
1013 1014 1015
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1016
    stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
1017
    // Select the update rate in Hz the message should be send
1018
    stream.req_message_rate = rate;
1019
    // Start / stop the message
1020
    stream.start_stop = (rate) ? 1 : 0;
1021 1022 1023 1024 1025 1026
    // 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);
1027 1028
    // Send message twice to increase chance of reception
    sendMessage(msg);
1029
    sendMessage(msg);
1030
#endif
lm's avatar
lm committed
1031 1032
}

1033
void UAS::enableRawControllerDataTransmission(int rate)
lm's avatar
lm committed
1034
{
1035 1036 1037 1038
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1039
    stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
1040
    // Select the update rate in Hz the message should be send
1041
    stream.req_message_rate = rate;
1042
    // Start / stop the message
1043
    stream.start_stop = (rate) ? 1 : 0;
1044 1045 1046 1047 1048 1049
    // 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);
1050 1051
    // Send message twice to increase chance of reception
    sendMessage(msg);
1052
    sendMessage(msg);
lm's avatar
lm committed
1053 1054
}

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

1077
void UAS::enablePositionTransmission(int rate)
pixhawk's avatar
pixhawk committed
1078 1079 1080 1081 1082
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1083
    stream.req_stream_id = MAV_DATA_STREAM_POSITION;
pixhawk's avatar
pixhawk committed
1084
    // Select the update rate in Hz the message should be send
1085
    stream.req_message_rate = rate;
pixhawk's avatar
pixhawk committed
1086
    // Start / stop the message
1087
    stream.start_stop = (rate) ? 1 : 0;
pixhawk's avatar
pixhawk committed
1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098
    // 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);
}

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

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

1143
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1144 1145 1146 1147 1148
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1149
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1150
    // Select the update rate in Hz the message should be send
1151
    stream.req_message_rate = rate;
1152
    // Start / stop the message
1153
    stream.start_stop = (rate) ? 1 : 0;
1154 1155 1156 1157 1158 1159
    // 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);
1160 1161
    // Send message twice to increase chance of reception
    sendMessage(msg);
1162
    sendMessage(msg);
1163 1164
}

lm's avatar
lm committed
1165 1166 1167 1168 1169 1170 1171
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1172
void UAS::setParameter(int component, QString id, float value)
1173
{    
1174 1175 1176
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1177 1178
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1179

1180
    // Copy string into buffer, ensuring not to exceed the buffer size    
1181
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1182
    {
lm's avatar
lm committed
1183
        // String characters
1184
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1185
        {
1186
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1187 1188
        }
        // Null termination at end of string or end of buffer
1189
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1190 1191 1192 1193 1194 1195 1196 1197
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1198
    }    
1199
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1200
    sendMessage(msg);
1201 1202
}

pixhawk's avatar
pixhawk committed
1203
/**
lm's avatar
lm committed
1204
 * Launches the system
pixhawk's avatar
pixhawk committed
1205 1206 1207 1208
 *
 **/
void UAS::launch()
{
1209
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1210
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1211
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1212 1213 1214
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1215 1216 1217 1218 1219 1220 1221 1222
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1223
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1224
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1225
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1226 1227 1228
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1229 1230 1231 1232 1233 1234 1235 1236
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1237
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1238
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1239
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1240 1241 1242
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256
}

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
1257 1258
//    if(mode == (int)MAV_MODE_MANUAL)
//    {
pixhawk's avatar
pixhawk committed
1259
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
1260
        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
1261 1262 1263 1264
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;

        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
lm's avatar
lm committed
1265
//    }
pixhawk's avatar
pixhawk committed
1266 1267
}

1268 1269 1270 1271 1272
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1273 1274 1275 1276 1277
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1278

pixhawk's avatar
pixhawk committed
1279 1280
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1281

pixhawk's avatar
pixhawk committed
1282 1283 1284 1285 1286
        break;
    default:

        break;
    }
1287
//    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1288 1289 1290

}

1291

1292
/*void UAS::requestWaypoints()
1293 1294 1295 1296 1297
{
//    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
1298 1299
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1300 1301
}

pixhawk's avatar
pixhawk committed
1302 1303
void UAS::setWaypoint(Waypoint* wp)
{
1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321
//    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
1322 1323 1324 1325
}

void UAS::setWaypointActive(int id)
{
1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348
//    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!";
1349
}*/
pixhawk's avatar
pixhawk committed
1350 1351 1352 1353


void UAS::halt()
{
1354
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1355
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1356
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1357 1358 1359
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1360 1361 1362 1363
}

void UAS::go()
{
1364
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1365
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1366
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1367 1368 1369
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1370 1371 1372 1373 1374
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1375
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1376
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1377
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1378 1379 1380
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1381 1382 1383 1384 1385 1386 1387 1388
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1389
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1390
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1391
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1392 1393 1394
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419
}

/**
 * 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)
    {
1420
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1421
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1422
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1423 1424 1425
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448
        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
1449
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1450
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1451
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1452 1453 1454
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1455 1456 1457 1458
        result = true;
    }
}

1459 1460
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1461 1462 1463 1464 1465 1466
    mavlink_message_t msg;
    mavlink_msg_position_target_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, x, y, z, yaw);

    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
1467 1468
}

pixhawk's avatar
pixhawk committed
1469 1470 1471
/**
 * @return The name of this system as string in human-readable form
 */
1472
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512
{
    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
1513
    case NICD:
pixhawk's avatar
pixhawk committed
1514
        break;
lm's avatar
lm committed
1515
    case NIMH:
pixhawk's avatar
pixhawk committed
1516
        break;
lm's avatar
lm committed
1517
    case LIION:
pixhawk's avatar
pixhawk committed
1518
        break;
lm's avatar
lm committed
1519
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1520 1521 1522
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1523
    case LIFE:
pixhawk's avatar
pixhawk committed
1524
        break;
lm's avatar
lm committed
1525
    case AGZN:
pixhawk's avatar
pixhawk committed
1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542
        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
1543 1544 1545
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1546 1547
double UAS::getChargeLevel()
{
1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561
    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
1562 1563
}

lm's avatar
lm committed
1564 1565 1566 1567
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1568 1569
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581
        lowBattAlarm = true;
    }
}

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