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

PIXHAWK Micro Air Vehicle Flying Robotics Toolkit

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

This file is part of the PIXHAWK project

    PIXHAWK is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    PIXHAWK is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.

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

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

#include <QList>
#include <QMessageBox>
#include <QTimer>
#include <iostream>
#include <QDebug>
#include <cmath>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "MG.h"
42
#include "QGC.h"
pixhawk's avatar
pixhawk committed
43
#include "GAudioOutput.h"
44 45
#include "MAVLinkProtocol.h"
#include <mavlink.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 76
        lowBattAlarm(false),
        positionLock(false),
        statusTimeout(new QTimer(this))
pixhawk's avatar
pixhawk committed
77
{
78
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
79
    setBattery(LIPOLY, 3);
80 81
    statusTimeout->setInterval(500);
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
pixhawk's avatar
pixhawk committed
82 83 84 85 86 87 88
}

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

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

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

pixhawk's avatar
pixhawk committed
111 112 113 114 115 116 117 118 119 120
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
    if (!links->contains(link))
    {
        addLink(link);
121
//        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
pixhawk's avatar
pixhawk committed
122
    }
123 124 125 126
//    else
//    {
//        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
//    }
pixhawk's avatar
pixhawk committed
127

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

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

pixhawk's avatar
pixhawk committed
156
                // FIXME
157
                //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
pixhawk's avatar
pixhawk committed
158

pixhawk's avatar
pixhawk committed
159 160 161 162 163
                QString audiostring = "System " + QString::number(this->getUASID());
                QString stateAudio = "";
                QString modeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
pixhawk's avatar
pixhawk committed
164

pixhawk's avatar
pixhawk committed
165
                if (state.status != this->status)
pixhawk's avatar
pixhawk committed
166
                {
pixhawk's avatar
pixhawk committed
167
                    statechanged = true;
lm's avatar
lm committed
168
                    this->status = (int)state.status;
pixhawk's avatar
pixhawk committed
169 170
                    getStatusForCode((int)state.status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
171
                    emit statusChanged(this->status);
172
                    stateAudio = " changed status to " + uasState;
pixhawk's avatar
pixhawk committed
173 174
                }

lm's avatar
lm committed
175
                if (this->mode != static_cast<unsigned int>(state.mode))
pixhawk's avatar
pixhawk committed
176 177
                {
                    modechanged = true;
lm's avatar
lm committed
178
                    this->mode = static_cast<unsigned int>(state.mode);
pixhawk's avatar
pixhawk committed
179 180
                    QString mode;

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

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

lm's avatar
lm committed
223 224 225 226 227 228 229 230 231 232 233
                // LOW BATTERY ALARM
                float chargeLevel = getChargeLevel();
                if (chargeLevel <= 10.0f)
                {
                    startLowBattAlarm();
                }
                else
                {
                    stopLowBattAlarm();
                }

lm's avatar
lm committed
234
                // COMMUNICATIONS DROP RATE
235
                emit dropRateChanged(this->getUASID(), state.packet_drop);
236
                //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
lm's avatar
lm committed
237 238

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

pixhawk's avatar
pixhawk committed
266 267 268 269 270 271 272 273 274
                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
275 276 277 278
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
279
            //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
280
            {
pixhawk's avatar
pixhawk committed
281 282
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
283
                quint64 time = getUnixTime(attitude.usec);
pixhawk's avatar
pixhawk committed
284 285 286 287 288 289
                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
290 291 292
                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
293
                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
294 295
            }
            break;
296
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
297
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
298
            //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
299
            {
300 301
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
302
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
303 304 305
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
306 307 308
                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
309
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
310 311
                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
312 313 314 315 316 317 318
                // Set internal state
                if (!positionLock)
                {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
319 320
            }
            break;
321 322 323 324 325 326 327 328 329 330 331 332 333 334
        case MAVLINK_MSG_ID_GLOBAL_POSITION:
            //std::cerr << std::endl;
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
            {
                mavlink_global_position_t pos;
                mavlink_msg_global_position_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
                emit valueChanged(uasId, "alt", pos.alt, time);
                emit valueChanged(uasId, "g-vx", pos.vx, time);
                emit valueChanged(uasId, "g-vy", pos.vy, time);
                emit valueChanged(uasId, "g-vz", pos.vz, time);
                emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
pixhawk's avatar
pixhawk committed
335 336 337 338 339 340 341 342
                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;
343 344 345 346 347 348 349 350
            }
            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);
351 352 353

                // SANITY CHECK
                // only accept values in a realistic range
pixhawk's avatar
pixhawk committed
354 355
               // quint64 time = getUnixTime(pos.usec);
                quint64 time = MG::TIME::getGroundTimeNow();
356 357
                emit valueChanged(uasId, "lat", pos.lat, time);
                emit valueChanged(uasId, "lon", pos.lon, time);
358 359 360 361 362
                // Check for NaN
                int alt = pos.alt;
                if (alt != alt)
                {
                    alt = 0;
363
                    emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
364
                }
365
                emit valueChanged(uasId, "alt", pos.alt, time);
366 367 368 369 370 371 372 373 374
                // 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
                {
375
                     emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
376 377
                }
                emit globalPositionChanged(this, pos.lon, pos.lat, alt, time);
378 379
            }
            break;
lm's avatar
lm committed
380 381 382 383
        case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
lm's avatar
lm committed
384
                for(int i = 0; i < (int)pos.satellites_visible; i++)
lm's avatar
lm committed
385
                {
lm's avatar
lm committed
386
                    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
387 388 389
                }
            }
            break;
390 391 392 393 394 395 396
        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
397
        case MAVLINK_MSG_ID_DEBUG:
pixhawk's avatar
pixhawk committed
398
            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
399
            break;
400 401 402 403 404
        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
405
                emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
406 407 408 409 410 411 412 413 414
                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);
415
                quint64 time = MG::TIME::getGroundTimeNow();
416
                //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
417 418 419
                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);
420 421
            }
            break;
pixhawk's avatar
pixhawk committed
422 423 424 425
        case MAVLINK_MSG_ID_WAYPOINT_COUNT:
            {
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
pixhawk's avatar
pixhawk committed
426 427 428 429
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
pixhawk's avatar
pixhawk committed
430 431 432
            }
            break;

433
        case MAVLINK_MSG_ID_WAYPOINT:
434
            {
435 436
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
437
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
pixhawk's avatar
pixhawk committed
438 439 440 441
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
442
            }
pixhawk's avatar
pixhawk committed
443
            break;
pixhawk's avatar
pixhawk committed
444

445 446 447 448 449 450 451 452 453 454 455
        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
456 457 458 459
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
460 461 462 463
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
464 465 466
            }
            break;

467
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
468
            {
pixhawk's avatar
pixhawk committed
469 470 471
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
472
            }
pixhawk's avatar
pixhawk committed
473
            break;
pixhawk's avatar
pixhawk committed
474

475
        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
pixhawk's avatar
pixhawk committed
476
            {
477 478 479
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
480
            }
pixhawk's avatar
pixhawk committed
481
            break;
pixhawk's avatar
pixhawk committed
482

483 484 485 486 487 488 489
        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
490

491
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
492 493 494
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
495
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
496 497
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
498
                int severity = mavlink_msg_statustext_get_severity(&message);
499
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
500
                //emit statusTextReceived(severity, text);
501
                emit textMessageReceived(uasId, message.compid, severity, text);
lm's avatar
lm committed
502 503
            }
            break;
pixhawk's avatar
pixhawk committed
504
        default:
lm's avatar
lm committed
505 506 507 508
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
509 510
                    //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
511 512 513
                    //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
514 515 516 517 518
            break;
        }
    }
}

pixhawk's avatar
pixhawk committed
519 520
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
521
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
522
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
523 524
    mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
    sendMessage(msg);
525
  #endif
pixhawk's avatar
pixhawk committed
526 527
}

528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549
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
550
    else if (time < 1261440000000000LLU)
551 552 553
    {
        if (onboardTimeOffset == 0)
        {
554
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
555
        }
556
        return time/1000 + onboardTimeOffset;
557 558 559 560 561
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
562
        return time/1000;
563 564 565
    }
}

pixhawk's avatar
pixhawk committed
566
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
567
{
lm's avatar
lm committed
568
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_TEST3)
pixhawk's avatar
pixhawk committed
569 570
    {
        mavlink_message_t msg;
lm's avatar
lm committed
571
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
572
        sendMessage(msg);
lm's avatar
lm committed
573
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
574
    }
pixhawk's avatar
pixhawk committed
575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591
}

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
592
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
593 594 595 596 597 598 599 600 601 602 603
    // 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
 */
604
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
605
{
606
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
607 608 609 610 611 612
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
613
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
614 615 616
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
617
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
618 619 620
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
621
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
622 623 624
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
625
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
626 627 628
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
629 630 631 632 633
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
634 635 636
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
637
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
638 639 640
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
641
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
642 643 644
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
645
    default:
pixhawk's avatar
pixhawk committed
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
661
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
662 663 664 665 666 667 668 669
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

670
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
671 672 673 674
{
    return commStatus;
}

675 676 677
void UAS::requestParameters()
{
    mavlink_message_t msg;
678
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
679 680
    // Send message twice to increase chance of reception
    sendMessage(msg);
681 682
}

683
void UAS::writeParametersToStorage()
684
{
685 686 687
    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
688
    //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
689 690 691 692 693 694 695 696 697
    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
698 699 700 701
}

void UAS::enableAllDataTransmission(bool enabled)
{
702
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
lm's avatar
lm committed
703
    // Buffers to write data to
704
    mavlink_message_t msg;
705
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
706 707
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
708
    stream.req_stream_id = 0;
lm's avatar
lm committed
709 710 711 712 713 714 715 716 717 718
    // Select the update rate in Hz the message should be send
    // All messages will be send with their default rate
    stream.req_message_rate = 0;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
719
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
720 721
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
722
    sendMessage(msg);
723
#endif
lm's avatar
lm committed
724 725 726 727
}

void UAS::enableRawSensorDataTransmission(bool enabled)
{
728
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
lm's avatar
lm committed
729 730
    // Buffers to write data to
    mavlink_message_t msg;
731
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
732
    // Select the message to request from now on
733
    stream.req_stream_id = 1;
lm's avatar
lm committed
734 735 736 737 738 739 740 741 742
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
743
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
744 745
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
746
    sendMessage(msg);
747
#endif
lm's avatar
lm committed
748 749 750 751
}

void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
752
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
753 754 755 756 757 758 759 760 761 762 763 764 765 766 767
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 2;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 10;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
768 769
    // Send message twice to increase chance of reception
    sendMessage(msg);
770
    sendMessage(msg);
771
#endif
lm's avatar
lm committed
772
}
773

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

void UAS::enableRawControllerDataTransmission(bool enabled)
{
800
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
801 802 803 804 805 806 807 808 809 810 811 812 813 814 815
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 4;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
816 817
    // Send message twice to increase chance of reception
    sendMessage(msg);
818
    sendMessage(msg);
819
#endif
lm's avatar
lm committed
820 821 822 823
}

void UAS::enableRawSensorFusionTransmission(bool enabled)
{
824
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
825 826 827 828 829 830 831 832 833 834 835 836 837 838 839
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 5;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
840 841
    // Send message twice to increase chance of reception
    sendMessage(msg);
842
    sendMessage(msg);
843
#endif
844 845
}

pixhawk's avatar
pixhawk committed
846 847
void UAS::enablePositionTransmission(bool enabled)
{
848
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 6;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
867
#endif
pixhawk's avatar
pixhawk committed
868 869 870 871
}

void UAS::enableExtra1Transmission(bool enabled)
{
872
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 7;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
891
#endif
pixhawk's avatar
pixhawk committed
892 893 894 895
}

void UAS::enableExtra2Transmission(bool enabled)
{
896
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 8;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
915
#endif
pixhawk's avatar
pixhawk committed
916 917 918 919
}

void UAS::enableExtra3Transmission(bool enabled)
{
920
  #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
921 922 923 924 925 926 927
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 9;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
928 929 930 931 932 933 934 935
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
936 937
    // Send message twice to increase chance of reception
    sendMessage(msg);
938
    sendMessage(msg);
939
#endif
940 941 942 943 944 945 946
}

void UAS::setParameter(int component, QString id, float value)
{
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
947 948
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
949 950 951

    // Copy string into buffer, ensuring not to exceed the buffer size
    char* s = (char*)id.toStdString().c_str();
952
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
953
    {
lm's avatar
lm committed
954
        // String characters
955
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
956 957 958 959
        {
            p.param_id[i] = s[i];
        }
        // Null termination at end of string or end of buffer
960
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
961 962 963 964 965 966 967 968
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
969 970
    }
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
971
    sendMessage(msg);
972 973
}

pixhawk's avatar
pixhawk committed
974 975 976 977 978 979
/**
 * @brief Launches the system
 *
 **/
void UAS::launch()
{
980
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
981
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
982
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH);
983 984 985
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
986 987 988 989 990 991 992 993
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
994
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
995
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
996
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START);
997 998 999
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1000 1001 1002 1003 1004 1005 1006 1007
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
1008
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1009
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1010
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP);
1011 1012 1013
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027
}

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
1028
    if(mode == (int)MAV_MODE_MANUAL)
pixhawk's avatar
pixhawk committed
1029
    {
1030
      #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
pixhawk's avatar
pixhawk committed
1031
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
1032
        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
1033 1034 1035 1036
        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());
1037
      #endif
pixhawk's avatar
pixhawk committed
1038 1039 1040 1041 1042 1043 1044 1045
    }
}

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

pixhawk's avatar
pixhawk committed
1047 1048
        break;
    case 1:
pixhawk's avatar
pixhawk committed
1049

pixhawk's avatar
pixhawk committed
1050 1051 1052 1053 1054 1055 1056 1057 1058
        break;
    default:

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

}

1059

1060
/*void UAS::requestWaypoints()
1061 1062 1063 1064 1065
{
//    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
1066 1067
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1068 1069
}

pixhawk's avatar
pixhawk committed
1070 1071
void UAS::setWaypoint(Waypoint* wp)
{
1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089
//    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
1090 1091 1092 1093
}

void UAS::setWaypointActive(int id)
{
1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116
//    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!";
1117
}*/
pixhawk's avatar
pixhawk committed
1118 1119 1120 1121


void UAS::halt()
{
1122
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1123
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1124
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
1125 1126 1127
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1128 1129 1130 1131
}

void UAS::go()
{
1132
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1133
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1134
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_CONTINUE);
1135 1136 1137
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1138 1139 1140 1141 1142
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1143
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1144
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1145
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,  (int)MAV_ACTION_RETURN);
1146 1147 1148
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1149 1150 1151 1152 1153 1154 1155 1156
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1157
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1158
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1159
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
1160 1161 1162
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187
}

/**
 * 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)
    {
1188
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1189
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1190
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
1191 1192 1193
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216
        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
1217
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1218
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1219
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
1220 1221 1222
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1223 1224 1225 1226 1227 1228 1229
        result = true;
    }
}

/**
 * @return The name of this system as string in human-readable form
 */
1230
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270
{
    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
1271
    case NICD:
pixhawk's avatar
pixhawk committed
1272
        break;
lm's avatar
lm committed
1273
    case NIMH:
pixhawk's avatar
pixhawk committed
1274
        break;
lm's avatar
lm committed
1275
    case LIION:
pixhawk's avatar
pixhawk committed
1276
        break;
lm's avatar
lm committed
1277
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1278 1279 1280
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1281
    case LIFE:
pixhawk's avatar
pixhawk committed
1282
        break;
lm's avatar
lm committed
1283
    case AGZN:
pixhawk's avatar
pixhawk committed
1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300
        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
1301 1302 1303
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1304 1305
double UAS::getChargeLevel()
{
1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319
    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
1320 1321
}

lm's avatar
lm committed
1322 1323 1324 1325
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1326 1327
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339
        lowBattAlarm = true;
    }
}

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