UAS.cc 46.2 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 121 122
void UAS::setSelected()
{
    UASManager::instance()->setActiveUAS(this);
}

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

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

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

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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
261 262 263 264 265 266 267 268 269
                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
270 271 272 273
            }
            break;
        case MAVLINK_MSG_ID_ATTITUDE:
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
274
            //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
275
            {
pixhawk's avatar
pixhawk committed
276 277
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
278
                quint64 time = getUnixTime(attitude.usec);
pixhawk's avatar
pixhawk committed
279 280 281 282 283 284
                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
285 286 287
                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
288
                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
289 290
            }
            break;
291
        case MAVLINK_MSG_ID_LOCAL_POSITION:
lm's avatar
lm committed
292
            //std::cerr << std::endl;
pixhawk's avatar
pixhawk committed
293
            //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
lm's avatar
lm committed
294
            {
295 296
                mavlink_local_position_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
297
                quint64 time = getUnixTime(pos.usec);
lm's avatar
lm committed
298 299 300 301 302 303 304
                emit valueChanged(uasId, "x", pos.x, time);
                emit valueChanged(uasId, "y", pos.y, time);
                emit valueChanged(uasId, "z", pos.z, time);
                emit valueChanged(uasId, "vx", pos.vx, time);
                emit valueChanged(uasId, "vy", pos.vy, time);
                emit valueChanged(uasId, "vz", pos.vz, time);
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
pixhawk's avatar
pixhawk committed
305 306 307 308 309 310 311 312
                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;
lm's avatar
lm committed
313 314
            }
            break;
315 316 317 318 319 320 321 322 323 324 325 326 327 328
        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
329 330 331 332 333 334 335 336
                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;
337 338 339 340 341 342 343 344
            }
            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);
345 346 347

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

427
        case MAVLINK_MSG_ID_WAYPOINT:
428
            {
429 430
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_decode(&message, &wp);
pixhawk's avatar
pixhawk committed
431 432 433 434
                if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
435
            }
pixhawk's avatar
pixhawk committed
436
            break;
pixhawk's avatar
pixhawk committed
437 438 439 440 441

        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
pixhawk's avatar
pixhawk committed
442 443 444 445
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
pixhawk's avatar
pixhawk committed
446 447 448
            }
            break;

449
        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
450
            {
451 452 453
//                mavlink_waypoint_reached_t wp;
//                mavlink_msg_waypoint_reached_decode(&message, &wp);
//                emit waypointReached(this, wp.id);
454
            }
pixhawk's avatar
pixhawk committed
455
            break;
456 457 458 459 460 461 462
        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;
463
        case MAVLINK_MSG_ID_STATUSTEXT:
lm's avatar
lm committed
464 465 466
            {
                QByteArray b;
                b.resize(256);
pixhawk's avatar
pixhawk committed
467
                mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
lm's avatar
lm committed
468 469
                //b.append('\0');
                QString text = QString(b);
pixhawk's avatar
pixhawk committed
470
                int severity = mavlink_msg_statustext_get_severity(&message);
471
                //qDebug() << "RECEIVED STATUS:" << text;false
lm's avatar
lm committed
472
                //emit statusTextReceived(severity, text);
473
                emit textMessageReceived(uasId, severity, text);
lm's avatar
lm committed
474 475
            }
            break;
pixhawk's avatar
pixhawk committed
476
        default:
lm's avatar
lm committed
477 478 479 480
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
481 482
                    //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
483 484 485
                    //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
486 487 488 489 490
            break;
        }
    }
}

pixhawk's avatar
pixhawk committed
491 492 493 494 495 496
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
    mavlink_message_t msg;

}

497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518
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
519
    else if (time < 1261440000000000LLU)
520 521 522
    {
        if (onboardTimeOffset == 0)
        {
523
            onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000;
524
        }
525
        return time/1000 + onboardTimeOffset;
526 527 528 529 530
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
531
        return time/1000;
532 533 534
    }
}

pixhawk's avatar
pixhawk committed
535
void UAS::setMode(int mode)
pixhawk's avatar
pixhawk committed
536
{
lm's avatar
lm committed
537
    if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_TEST3)
pixhawk's avatar
pixhawk committed
538 539
    {
        mavlink_message_t msg;
lm's avatar
lm committed
540
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
pixhawk's avatar
pixhawk committed
541
        sendMessage(msg);
lm's avatar
lm committed
542
        qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
pixhawk's avatar
pixhawk committed
543
    }
pixhawk's avatar
pixhawk committed
544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560
}

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
561
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
562 563 564 565 566 567 568 569 570 571 572
    // 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
 */
573
float UAS::filterVoltage(float value) const
pixhawk's avatar
pixhawk committed
574
{
575
    return lpVoltage * 0.7f + value * 0.3f;
pixhawk's avatar
pixhawk committed
576 577 578 579 580 581
}

void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
    switch (statusCode)
    {
lm's avatar
lm committed
582
    case MAV_STATE_UNINIT:
pixhawk's avatar
pixhawk committed
583 584 585
        uasState = tr("UNINIT");
        stateDescription = tr("Not initialized");
        break;
lm's avatar
lm committed
586
    case MAV_STATE_BOOT:
pixhawk's avatar
pixhawk committed
587 588 589
        uasState = tr("BOOT");
        stateDescription = tr("Booting system, please wait..");
        break;
lm's avatar
lm committed
590
    case MAV_STATE_CALIBRATING:
pixhawk's avatar
pixhawk committed
591 592 593
        uasState = tr("CALIBRATING");
        stateDescription = tr("Calibrating sensors..");
        break;
lm's avatar
lm committed
594
    case MAV_STATE_ACTIVE:
pixhawk's avatar
pixhawk committed
595 596 597
        uasState = tr("ACTIVE");
        stateDescription = tr("Normal operation mode");
        break;
lm's avatar
lm committed
598 599 600 601 602
    case MAV_STATE_STANDBY:
        uasState = tr("STANDBY");
        stateDescription = tr("Standby, operational");
        break;
    case MAV_STATE_CRITICAL:
pixhawk's avatar
pixhawk committed
603 604 605
        uasState = tr("CRITICAL");
        stateDescription = tr("Failure occured!");
        break;
lm's avatar
lm committed
606
    case MAV_STATE_EMERGENCY:
pixhawk's avatar
pixhawk committed
607 608 609
        uasState = tr("EMERGENCY");
        stateDescription = tr("EMERGENCY: Please land");
        break;
lm's avatar
lm committed
610
    case MAV_STATE_POWEROFF:
pixhawk's avatar
pixhawk committed
611 612 613
        uasState = tr("SHUTDOWN");
        stateDescription = tr("Powering off system");
        break;
lm's avatar
lm committed
614
    default:
pixhawk's avatar
pixhawk committed
615 616 617 618 619 620 621 622 623 624 625 626 627 628 629
        uasState = tr("UNKNOWN");
        stateDescription = tr("FAILURE: Unknown system state");
        break;
    }
}



/* MANAGEMENT */

/*
 *
 * @return The uptime in milliseconds
 *
 **/
630
quint64 UAS::getUptime() const
pixhawk's avatar
pixhawk committed
631 632 633 634 635 636 637 638
{
    if(startTime == 0) {
        return 0;
    } else {
        return MG::TIME::getGroundTimeNow() - startTime;
    }
}

639
int UAS::getCommunicationStatus() const
pixhawk's avatar
pixhawk committed
640 641 642 643
{
    return commStatus;
}

644 645 646
void UAS::requestParameters()
{
    mavlink_message_t msg;
647
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
648 649
    // Send message twice to increase chance of reception
    sendMessage(msg);
650 651 652 653
}

void UAS::writeParameters()
{
lm's avatar
lm committed
654 655 656 657 658 659 660
    //mavlink_message_t msg;
    qDebug() << __FILE__ << __LINE__ << __func__ << "IS NOT IMPLEMENTED!";
}

void UAS::enableAllDataTransmission(bool enabled)
{
    // Buffers to write data to
661
    mavlink_message_t msg;
662
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
663 664
    // Select the message to request from now on
    // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
665
    stream.req_stream_id = 0;
lm's avatar
lm committed
666 667 668 669 670 671 672 673 674 675
    // 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
676
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
677 678
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
679 680 681 682 683 684 685
    sendMessage(msg);
}

void UAS::enableRawSensorDataTransmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
686
    mavlink_request_data_stream_t stream;
lm's avatar
lm committed
687
    // Select the message to request from now on
688
    stream.req_stream_id = 1;
lm's avatar
lm committed
689 690 691 692 693 694 695 696 697
    // 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
698
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
699 700
    // Send message twice to increase chance of reception
    sendMessage(msg);
lm's avatar
lm committed
701 702 703 704 705
    sendMessage(msg);
}

void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
706 707 708 709 710 711 712 713 714 715 716 717 718 719 720
    // 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);
721 722
    // Send message twice to increase chance of reception
    sendMessage(msg);
723
    sendMessage(msg);
lm's avatar
lm committed
724
}
725

lm's avatar
lm committed
726 727
void UAS::enableRCChannelDataTransmission(bool enabled)
{
728 729 730 731 732 733 734 735 736 737 738 739 740 741 742
    // 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);
743 744
    // Send message twice to increase chance of reception
    sendMessage(msg);
745
    sendMessage(msg);
lm's avatar
lm committed
746 747 748 749
}

void UAS::enableRawControllerDataTransmission(bool enabled)
{
750 751 752 753 754 755 756 757 758 759 760 761 762 763 764
    // 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);
765 766
    // Send message twice to increase chance of reception
    sendMessage(msg);
767
    sendMessage(msg);
lm's avatar
lm committed
768 769 770 771
}

void UAS::enableRawSensorFusionTransmission(bool enabled)
{
772 773 774 775 776 777 778 779 780 781 782 783 784 785 786
    // 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);
787 788
    // Send message twice to increase chance of reception
    sendMessage(msg);
789
    sendMessage(msg);
790 791
}

pixhawk's avatar
pixhawk committed
792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866
void UAS::enablePositionTransmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 6;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

void UAS::enableExtra1Transmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 7;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

void UAS::enableExtra2Transmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 8;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
    // Start / stop the message
    stream.start_stop = (enabled) ? 1 : 0;
    // The system which should take this command
    stream.target_system = uasId;
    // The component / subsystem which should take this command
    stream.target_component = 0;
    // Encode and send the message
    mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
}

void UAS::enableExtra3Transmission(bool enabled)
{
    // Buffers to write data to
    mavlink_message_t msg;
    mavlink_request_data_stream_t stream;
    // Select the message to request from now on
    stream.req_stream_id = 9;
    // Select the update rate in Hz the message should be send
    stream.req_message_rate = 200;
867 868 869 870 871 872 873 874
    // 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);
875 876
    // Send message twice to increase chance of reception
    sendMessage(msg);
877
    sendMessage(msg);
878 879 880 881 882 883 884
}

void UAS::setParameter(int component, QString id, float value)
{
    mavlink_message_t msg;
    mavlink_param_set_t p;
    p.param_value = value;
885 886
    p.target_system = (uint8_t)uasId;
    p.target_component = (uint8_t)component;
887 888 889

    // Copy string into buffer, ensuring not to exceed the buffer size
    char* s = (char*)id.toStdString().c_str();
890
    for (unsigned int i = 0; i < sizeof(p.param_id); i++)
891
    {
lm's avatar
lm committed
892
        // String characters
893
        if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
lm's avatar
lm committed
894 895 896 897
        {
            p.param_id[i] = s[i];
        }
        // Null termination at end of string or end of buffer
898
        else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
lm's avatar
lm committed
899 900 901 902 903 904 905 906
        {
            p.param_id[i] = '\0';
        }
        // Zero fill
        else
        {
            p.param_id[i] = 0;
        }
907 908
    }
    mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
909
    sendMessage(msg);
910 911
}

pixhawk's avatar
pixhawk committed
912 913 914 915 916 917
/**
 * @brief Launches the system
 *
 **/
void UAS::launch()
{
918
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
919
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
lm's avatar
lm committed
920
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_LAUNCH);
921 922 923
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
924 925 926 927 928 929 930 931
}

/**
 * Depending on the UAS, this might make the rotors of a helicopter spinning
 *
 **/
void UAS::enable_motors()
{
932
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
933
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
lm's avatar
lm committed
934
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_MOTORS_START);
935 936 937
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
938 939 940 941 942 943 944 945
}

/**
 * @warning Depending on the UAS, this might completely stop all motors.
 *
 **/
void UAS::disable_motors()
{
946
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
947
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
lm's avatar
lm committed
948
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_MOTORS_STOP);
949 950 951
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
952 953 954 955 956 957 958 959 960 961 962 963 964 965
}

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
966
    if(mode == (int)MAV_MODE_MANUAL)
pixhawk's avatar
pixhawk committed
967 968
    {
        mavlink_message_t message;
pixhawk's avatar
pixhawk committed
969
        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
970 971 972 973 974 975 976 977 978 979 980 981
        sendMessage(message);
        qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;

        emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    }
}

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

pixhawk's avatar
pixhawk committed
983 984
        break;
    case 1:
pixhawk's avatar
pixhawk committed
985

pixhawk's avatar
pixhawk committed
986 987 988 989 990 991 992 993 994
        break;
    default:

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

}

995

996
/*void UAS::requestWaypoints()
997 998 999 1000 1001
{
//    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
1002 1003
    waypointManager.requestWaypoints();
    qDebug() << "UAS Request WPs";
1004 1005
}

pixhawk's avatar
pixhawk committed
1006 1007
void UAS::setWaypoint(Waypoint* wp)
{
1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025
//    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
1026 1027 1028 1029
}

void UAS::setWaypointActive(int id)
{
1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052
//    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!";
1053
}*/
pixhawk's avatar
pixhawk committed
1054 1055 1056 1057


void UAS::halt()
{
1058
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1059
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1060 1061 1062 1063
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_HALT);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1064 1065 1066 1067
}

void UAS::go()
{
1068
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1069
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1070 1071 1072 1073
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_CONTINUE);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1074 1075 1076 1077 1078
}

/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
1079
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1080
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1081 1082 1083 1084
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_RETURN);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1085 1086 1087 1088 1089 1090 1091 1092
}

/**
 * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
 * and might differ between systems.
 */
void UAS::emergencySTOP()
{
1093
    mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1094
    // TODO Replace MG System ID with static function call and allow to change ID in GUI
1095 1096 1097 1098
    mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_EMCY_LAND);
    // Send message twice to increase chance of reception
    sendMessage(msg);
    sendMessage(msg);
pixhawk's avatar
pixhawk committed
1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123
}

/**
 * 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)
    {
1124
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1125
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1126 1127 1128 1129
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_EMCY_KILL);
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152
        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
1153
        mavlink_message_t msg;
pixhawk's avatar
pixhawk committed
1154
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
1155 1156 1157 1158
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), (int)MAV_ACTION_SHUTDOWN);
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
pixhawk's avatar
pixhawk committed
1159 1160 1161 1162 1163 1164 1165
        result = true;
    }
}

/**
 * @return The name of this system as string in human-readable form
 */
1166
QString UAS::getUASName(void) const
pixhawk's avatar
pixhawk committed
1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206
{
    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
1207
    case NICD:
pixhawk's avatar
pixhawk committed
1208
        break;
lm's avatar
lm committed
1209
    case NIMH:
pixhawk's avatar
pixhawk committed
1210
        break;
lm's avatar
lm committed
1211
    case LIION:
pixhawk's avatar
pixhawk committed
1212
        break;
lm's avatar
lm committed
1213
    case LIPOLY:
pixhawk's avatar
pixhawk committed
1214 1215 1216
        fullVoltage = this->cells * UAS::lipoFull;
        emptyVoltage = this->cells * UAS::lipoEmpty;
        break;
lm's avatar
lm committed
1217
    case LIFE:
pixhawk's avatar
pixhawk committed
1218
        break;
lm's avatar
lm committed
1219
    case AGZN:
pixhawk's avatar
pixhawk committed
1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236
        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
1237 1238 1239
/**
 * @return charge level in percent - 0 - 100
 */
pixhawk's avatar
pixhawk committed
1240 1241
double UAS::getChargeLevel()
{
1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255
    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
1256 1257
}

lm's avatar
lm committed
1258 1259 1260 1261
void UAS::startLowBattAlarm()
{
    if (!lowBattAlarm)
    {
1262 1263
        GAudioOutput::instance()->alert("LOW BATTERY");
        QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lm's avatar
lm committed
1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275
        lowBattAlarm = true;
    }
}

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