UAS.cc 60.5 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"
46 47
#include "LinkManager.h"
#include "SerialLink.h"
pixhawk's avatar
pixhawk committed
48

49

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

UAS::~UAS()
{
    delete links;
100
    links=NULL;
pixhawk's avatar
pixhawk committed
101 102
}

103
int UAS::getUASID() const
pixhawk's avatar
pixhawk committed
104 105 106 107
{
    return uasId;
}

108 109 110 111 112 113 114 115 116 117
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
118
        if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
119 120 121 122 123 124
        {
            GAudioOutput::instance()->notifyNegative();
        }
    }
}

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

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

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

pixhawk's avatar
pixhawk committed
145 146 147 148 149 150 151 152 153 154
    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
155
            if (this->type != mavlink_msg_heartbeat_get_type(&message))
pixhawk's avatar
pixhawk committed
156
            {
pixhawk's avatar
pixhawk committed
157
                this->type = mavlink_msg_heartbeat_get_type(&message);
158
                this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
pixhawk's avatar
pixhawk committed
159 160
                emit systemTypeSet(this, type);
            }
161

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

pixhawk's avatar
pixhawk committed
173
                // FIXME
174
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
175

pixhawk's avatar
pixhawk committed
176 177 178 179 180
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
181

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

lm's avatar
lm committed
194
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
195 196
                {
                    modechanged = true;
lm's avatar
lm committed
197
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
198 199
                    QString mode;

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

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

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

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

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

pixhawk's avatar
pixhawk committed
288 289 290 291 292 293 294 295 296
                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
297 298 299 300
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
301
            //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
302
            {
pixhawk's avatar
pixhawk committed
303 304
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
305
                quint64 time = getUnixTime(attitude.usec);
lm's avatar
lm committed
306 307 308
                roll = attitude.roll;
                pitch = attitude.pitch;
                yaw = attitude.yaw;
pixhawk's avatar
pixhawk committed
309 310 311 312 313 314
                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
315 316 317
                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
318
                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
319 320
            }
            break;
321
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
322
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
323
            //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
324
            {
325 326
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
327
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
328 329 330
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
lm's avatar
lm committed
331 332 333
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
334 335 336
                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
337
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
338
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
339 340 341 342

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

343
                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
pixhawk's avatar
pixhawk committed
344 345 346 347 348 349 350
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
351 352
            }
            break;
353 354 355 356 357 358 359
        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);
360 361 362
                latitude = pos.lat;
                longitude = pos.lon;
                altitude = pos.alt;
363 364 365 366 367 368 369
                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
370 371 372 373 374 375 376 377
                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;
378 379
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
380 381 382 383 384 385 386 387
            }
            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);
388 389 390

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

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

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

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

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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
715 716
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
lm's avatar
lm committed
717
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
718 719 720
  mavlink_message_t msg;
  mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
  sendMessage(msg);
lm's avatar
lm committed
721 722 723 724 725
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
pixhawk's avatar
pixhawk committed
726 727 728 729 730 731 732 733 734 735
#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
736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756
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
757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777
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);
}

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

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

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

841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862
void UAS::forwardMessage(mavlink_message_t message)
{
    // Emit message on all links that are currently connected
    QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
    foreach(LinkInterface* link, link_list)
    {
        SerialLink* serial = dynamic_cast<SerialLink*>(link);
        if(serial != 0)
        {

            for(int i=0;i<links->size();i++)
            {
                if(serial != links->at(i))
                {
                    qDebug()<<"Forwarding Over link: "<<serial->getName()<<" "<<serial;
                    sendMessage(serial, message);
                }
            }
        }
    }
}

pixhawk's avatar
pixhawk committed
863 864
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
865
    if(!link) return;
pixhawk's avatar
pixhawk committed
866 867 868
    // Create buffer
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
869
    int len = mavlink_msg_to_send_buffer(buffer, &message);
870
    mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
871 872 873 874 875 876 877 878 879 880 881
    // 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
 */
882
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
883
{
884
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
885 886 887 888 889 890
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
891
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
892 893 894
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
895
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
896 897 898
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
899
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
900 901 902
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
903
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
904 905 906
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
907 908 909 910 911
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
912 913 914
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
915
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
916 917 918
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
919
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
920 921 922
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
923
    default:
pixhawk's avatar
pixhawk committed
924 925 926 927 928 929 930 931 932 933 934 935 936 937 938
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
939
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
940 941 942 943 944 945 946 947
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

948
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
949 950 951 952
{
    return commStatus;
}

953 954 955
void UAS::requestParameters()
{
    mavlink_message_t msg;
956
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
957 958
    // Send message twice to increase chance of reception
    sendMessage(msg);
959 960
}

961
void UAS::writeParametersToStorage()
962
{
963 964 965
    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
966
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
967 968 969 970 971 972 973 974 975
    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
976 977
}

978
void UAS::enableAllDataTransmission(int rate)
lm's avatar
lm committed
979 980
{
    // Buffers to write data to
981
    mavlink_message_t msg;
982
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
983 984
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
985
    stream.req_stream_id = MAV_DATA_STREAM_ALL;
lm's avatar
lm committed
986 987
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
988 989
    // 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
990 991
    stream.req_message_rate = 0;
    // Start / stop the message
992
    stream.start_stop = (rate) ? 1 : 0;
lm's avatar
lm committed
993 994 995 996 997
    // 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
998
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
999 1000
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
1001 1002 1003
    sendMessage(msg);
}

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

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

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

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

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

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

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

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

1185
void UAS::enableExtra3Transmission(int rate)
pixhawk's avatar
pixhawk committed
1186 1187 1188 1189 1190
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
1191
    stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
pixhawk's avatar
pixhawk committed
1192
    // Select the update rate in Hz the message should be send
1193
    stream.req_message_rate = rate;
1194
    // Start / stop the message
1195
    stream.start_stop = (rate) ? 1 : 0;
1196 1197 1198 1199 1200 1201
    // 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);
1202 1203
    // Send message twice to increase chance of reception
    sendMessage(msg);
1204
    sendMessage(msg);
1205 1206
}

lm's avatar
lm committed
1207 1208 1209 1210 1211 1212 1213
/**
 * Set a parameter value onboard
 *
 * @param component The component to set the parameter
 * @param id Name of the parameter
 * @param value Parameter value
 */
1214
void UAS::setParameter(int component, QString id, float value)
1215
{    
1216 1217 1218
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
1219 1220
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
1221

1222
    // Copy string into buffer, ensuring not to exceed the buffer size    
1223
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
1224
    {
lm's avatar
lm committed
1225
        // String characters
1226
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1227
        {
1228
            p.param_id[i] = id.toAscii()[i];
lm's avatar
lm committed
1229 1230
        }
        // Null termination at end of string or end of buffer
1231
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
1232 1233 1234 1235 1236 1237 1238 1239
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
1240
    }    
1241
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
1242
    sendMessage(msg);
1243 1244
}

pixhawk's avatar
pixhawk committed
1245
/**
lm's avatar
lm committed
1246
 * Launches the system
pixhawk's avatar
pixhawk committed
1247 1248 1249 1250
 *
 **/
void UAS::launch()
{
1251
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1252
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1253
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
1254 1255 1256
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1257 1258 1259 1260 1261 1262 1263 1264
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
1265
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1266
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1267
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
1268 1269 1270
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1271 1272 1273 1274 1275 1276 1277 1278
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1279
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1280
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1281
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1282 1283 1284
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298
}

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
1299 1300
//    if(mode == (int)MAV_MODE_MANUAL)
//    {
pixhawk's avatar
pixhawk committed
1301
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
1302
        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
1303 1304 1305 1306
        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
1307
//    }
pixhawk's avatar
pixhawk committed
1308 1309
}

1310 1311 1312 1313 1314
int UAS::getSystemType()
{
    return this->type;
}

pixhawk's avatar
pixhawk committed
1315 1316 1317 1318 1319
void UAS::receiveButton(int buttonIndex)
{
    switch (buttonIndex)
    {
    case 0:
pixhawk's avatar
pixhawk committed
1320

pixhawk's avatar
pixhawk committed
1321 1322
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1323

pixhawk's avatar
pixhawk committed
1324 1325 1326 1327 1328
        break;
    default:

        break;
    }
1329
//    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
pixhawk's avatar
pixhawk committed
1330 1331 1332

}

1333

1334
/*void UAS::requestWaypoints()
1335 1336 1337 1338 1339
{
//    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
1340 1341
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1342 1343
}

pixhawk's avatar
pixhawk committed
1344 1345
void UAS::setWaypoint(Waypoint* wp)
{
1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363
//    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
1364 1365 1366 1367
}

void UAS::setWaypointActive(int id)
{
1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390
//    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!";
1391
}*/
pixhawk's avatar
pixhawk committed
1392 1393 1394 1395


void UAS::halt()
{
1396
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1397
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1398
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1399 1400 1401
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1402 1403 1404 1405
}

void UAS::go()
{
1406
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1407
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1408
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1409 1410 1411
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1412 1413 1414 1415 1416
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1417
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1418
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1419
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1420 1421 1422
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1423 1424 1425 1426 1427 1428 1429 1430
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1431
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1432
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1433
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1434 1435 1436
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461
}

/**
 * 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)
    {
1462
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1463
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1464
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1465 1466 1467
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490
        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
1491
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1492
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1493
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1494 1495 1496
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1497 1498 1499 1500
        result = true;
    }
}

1501 1502
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
1503 1504 1505 1506 1507 1508
    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);
1509 1510
}

pixhawk's avatar
pixhawk committed
1511 1512 1513
/**
 * @return The name of this system as string in human-readable form
 */
1514
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534
{
    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);
1535
    //qDebug() << link<<" ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
pixhawk's avatar
pixhawk committed
1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554
}

/**
 * @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
1555
    case NICD:
pixhawk's avatar
pixhawk committed
1556
        break;
lm's avatar
lm committed
1557
    case NIMH:
pixhawk's avatar
pixhawk committed
1558
        break;
lm's avatar
lm committed
1559
    case LIION:
pixhawk's avatar
pixhawk committed
1560
        break;
lm's avatar
lm committed
1561
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1562 1563 1564
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1565
    case LIFE:
pixhawk's avatar
pixhawk committed
1566
        break;
lm's avatar
lm committed
1567
    case AGZN:
pixhawk's avatar
pixhawk committed
1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584
        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
1585 1586 1587
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1588 1589
double UAS::getChargeLevel()
{
1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603
    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
1604 1605
}

lm's avatar
lm committed
1606 1607 1608 1609
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1610 1611
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623
        lowBattAlarm = true;
    }
}

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