MAVLinkSimulationLink.cc 35.9 KB
Newer Older
pixhawk's avatar
pixhawk committed
1
/*=====================================================================
pixhawk's avatar
pixhawk committed
2

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

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

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

lm's avatar
lm committed
9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12
    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's avatar
pixhawk committed
13

lm's avatar
lm committed
14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17
    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.
pixhawk's avatar
pixhawk committed
18

pixhawk's avatar
pixhawk committed
19
    You should have received a copy of the GNU General Public License
lm's avatar
lm committed
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21

pixhawk's avatar
pixhawk committed
22
======================================================================*/
pixhawk's avatar
pixhawk committed
23

pixhawk's avatar
pixhawk committed
24 25 26 27 28 29 30 31 32 33 34 35 36 37 38
/**
 * @file
 *   @brief Implementation of simulated system link
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <cstdlib>
#include <cstdio>
#include <iostream>
#include <cmath>
#include <QTime>
#include <QImage>
#include <QDebug>
39
#include <QFileInfo>
pixhawk's avatar
pixhawk committed
40
#include "LinkManager.h"
41
#include "MAVLinkProtocol.h"
pixhawk's avatar
pixhawk committed
42
#include "MAVLinkSimulationLink.h"
43
#include "QGCMAVLink.h"
pixhawk's avatar
pixhawk committed
44
#include "QGC.h"
45
#include "MAVLinkSimulationMAV.h"
pixhawk's avatar
pixhawk committed
46 47 48 49 50 51 52 53 54 55 56 57

/**
 * Create a simulated link. This link is connected to an input and output file.
 * The link sends one line at a time at the specified sendrate. The timing of
 * the sendrate is free of drift, which means it is stable on the long run.
 * However, small deviations are mixed in to vary the sendrate slightly
 * in order to simulate disturbances on a real communication link.
 *
 * @param readFile The file with the messages to read (must be in ASCII format, line breaks can be Unix or Windows style)
 * @param writeFile The received messages are written to that file
 * @param rate The rate at which the messages are sent (in intervals of milliseconds)
 **/
pixhawk's avatar
pixhawk committed
58
MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate, QObject* parent) : LinkInterface(parent),
59 60
    readyBytes(0),
    timeOffset(0)
pixhawk's avatar
pixhawk committed
61 62 63 64
{
    this->rate = rate;
    _isConnected = false;

lm's avatar
lm committed
65
    onboardParams = QMap<QString, float>();
pixhawk's avatar
pixhawk committed
66 67 68 69 70 71 72
    onboardParams.insert("PID_ROLL_K_P", 0.5f);
    onboardParams.insert("PID_PITCH_K_P", 0.5f);
    onboardParams.insert("PID_YAW_K_P", 0.5f);
    onboardParams.insert("PID_XY_K_P", 0.5f);
    onboardParams.insert("PID_ALT_K_P", 0.5f);
    onboardParams.insert("SYS_TYPE", 1);
    onboardParams.insert("SYS_ID", systemId);
lm's avatar
lm committed
73

pixhawk's avatar
pixhawk committed
74 75
    // Comments on the variables can be found in the header file

pixhawk's avatar
pixhawk committed
76
    simulationFile = new QFile(readFile, this);
77
    if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text)) {
pixhawk's avatar
pixhawk committed
78 79 80
        simulationHeader = simulationFile->readLine();
    }
    receiveFile = new QFile(writeFile, this);
81
    lastSent = QGC::groundTimeMilliseconds();
pixhawk's avatar
pixhawk committed
82

83
    if (simulationFile->exists()) {
pixhawk's avatar
pixhawk committed
84
        this->name = "Simulation: " + QFileInfo(simulationFile->fileName()).fileName();
85
    } else {
pixhawk's avatar
pixhawk committed
86 87 88
        this->name = "MAVLink simulation link";
    }

89 90


pixhawk's avatar
pixhawk committed
91 92 93
    // Initialize the pseudo-random number generator
    srand(QTime::currentTime().msec());
    maxTimeNoise = 0;
pixhawk's avatar
pixhawk committed
94 95
    this->id = getNextLinkId();
    LinkManager::instance()->add(this);
96
    QObject::connect(this, SIGNAL(destroyed(QObject*)), LinkManager::instance(), SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
97 98 99 100 101 102 103
}

MAVLinkSimulationLink::~MAVLinkSimulationLink()
{
    //TODO Check destructor
    //    fileStream->flush();
    //    outStream->flush();
lm's avatar
lm committed
104
    delete simulationFile;
pixhawk's avatar
pixhawk committed
105 106 107 108
}

void MAVLinkSimulationLink::run()
{
pixhawk's avatar
pixhawk committed
109 110 111 112 113 114

    status.mode = MAV_MODE_UNINIT;
    status.status = MAV_STATE_UNINIT;
    status.vbat = 0;
    status.packet_drop = 0;

115 116


117
    forever {
pixhawk's avatar
pixhawk committed
118 119 120

        static quint64 last = 0;

121
        if (QGC::groundTimeMilliseconds() - last >= rate) {
122
            if (_isConnected) {
pixhawk's avatar
pixhawk committed
123
                mainloop();
124 125 126 127 128 129 130 131 132

                // FIXME Hacky code to read from packet log file
//                readyBufferMutex.lock();
//                for (int i = 0; i < streampointer; i++)
//                {
//                    readyBuffer.enqueue(*(stream + i));
//                }
//                readyBufferMutex.unlock();

133
                readBytes();
pixhawk's avatar
pixhawk committed
134
            }
135
            last = QGC::groundTimeMilliseconds();
pixhawk's avatar
pixhawk committed
136
        }
137
        QGC::SLEEP::msleep(3);
pixhawk's avatar
pixhawk committed
138 139 140 141

    }
}

142 143 144 145 146 147 148
void MAVLinkSimulationLink::sendMAVLinkMessage(const mavlink_message_t* msg)
{
    // Allocate buffer with packet data
    uint8_t buf[MAVLINK_MAX_PACKET_LEN];
    unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);

    // Pack to link buffer
pixhawk's avatar
pixhawk committed
149
    readyBufferMutex.lock();
150
    for (unsigned int i = 0; i < bufferlength; i++) {
151 152
        readyBuffer.enqueue(*(buf + i));
    }
pixhawk's avatar
pixhawk committed
153
    readyBufferMutex.unlock();
154 155
}

pixhawk's avatar
pixhawk committed
156 157 158 159
void MAVLinkSimulationLink::enqueue(uint8_t* stream, uint8_t* index, mavlink_message_t* msg)
{
    // Allocate buffer with packet data
    uint8_t buf[MAVLINK_MAX_PACKET_LEN];
pixhawk's avatar
pixhawk committed
160
    unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);
pixhawk's avatar
pixhawk committed
161 162 163 164 165
    //add data into datastream
    memcpy(stream+(*index),buf, bufferlength);
    (*index) += bufferlength;
}

pixhawk's avatar
pixhawk committed
166 167 168 169 170 171
void MAVLinkSimulationLink::mainloop()
{

    // Test for encoding / decoding packets

    // Test data stream
172
    streampointer = 0;
pixhawk's avatar
pixhawk committed
173 174 175

    // Fake system values

176 177
    static float fullVoltage = 4.2f * 3.0f;
    static float emptyVoltage = 3.35f * 3.0f;
pixhawk's avatar
pixhawk committed
178
    static float voltage = fullVoltage;
179
    static float drainRate = 0.025f; // x.xx% of the capacity is linearly drained per second
pixhawk's avatar
pixhawk committed
180

pixhawk's avatar
pixhawk committed
181
    mavlink_attitude_t attitude;
182
    memset(&attitude, 0, sizeof(mavlink_attitude_t));
183 184 185 186
#ifdef MAVLINK_ENABLED_PIXHAWK
    mavlink_raw_aux_t rawAuxValues;
    memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif
pixhawk's avatar
pixhawk committed
187
    mavlink_raw_imu_t rawImuValues;
188
    memset(&rawImuValues, 0, sizeof(mavlink_raw_imu_t));
pixhawk's avatar
pixhawk committed
189 190 191 192 193 194 195 196 197 198

    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength;
    int messageSize;
    mavlink_message_t msg;

    // Timers
    static unsigned int rate1hzCounter = 1;
    static unsigned int rate10hzCounter = 1;
    static unsigned int rate50hzCounter = 1;
199
    static unsigned int circleCounter = 0;
pixhawk's avatar
pixhawk committed
200 201 202 203 204 205

    // Vary values

    // VOLTAGE
    // The battery is drained constantly
    voltage = voltage - ((fullVoltage - emptyVoltage) * drainRate / rate);
206
    if (voltage < 3.550f * 3.0f) voltage = 3.550f * 3.0f;
pixhawk's avatar
pixhawk committed
207

pixhawk's avatar
pixhawk committed
208
    static int state = 0;
pixhawk's avatar
pixhawk committed
209

210
    if (state == 0) {
pixhawk's avatar
pixhawk committed
211 212
        // BOOT
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
213
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
214
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
215
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
216 217 218 219 220 221 222 223
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
        state++;
    }


    // 50 HZ TASKS
224 225 226
    if (rate50hzCounter == 1000 / rate / 40) {
        if (simulationFile->isOpen()) {
            if (simulationFile->atEnd()) {
pixhawk's avatar
pixhawk committed
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242
                // We reached the end of the file, start from scratch
                simulationFile->reset();
                simulationHeader = simulationFile->readLine();
            }

            // Data was made available, read one line
            // first entry is the timestamp
            QString values = QString(simulationFile->readLine());
            QStringList parts = values.split("\t");
            QStringList keys = simulationHeader.split("\t");
            //qDebug() << simulationHeader;
            //qDebug() << values;
            bool ok;
            static quint64 lastTime = 0;
            static quint64 baseTime = 0;
            quint64 time = QString(parts.first()).toLongLong(&ok, 10);
243 244
            // FIXME Remove multiplicaton by 1000
            time *= 1000;
pixhawk's avatar
pixhawk committed
245

246 247
            if (ok) {
                if (timeOffset == 0) {
pixhawk's avatar
pixhawk committed
248 249 250 251
                    timeOffset = time;
                    baseTime = time;
                }

252
                if (lastTime > time) {
pixhawk's avatar
pixhawk committed
253 254 255 256 257 258 259 260 261
                    // We have wrapped around in the logfile
                    // Add the measurement time interval to the base time
                    baseTime += lastTime - timeOffset;
                }
                lastTime = time;

                time = time - timeOffset + baseTime;

                // Gather individual measurement values
262
                for (int i = 1; i < (parts.size() - 1); ++i) {
pixhawk's avatar
pixhawk committed
263 264 265 266 267
                    // Get one data field
                    bool res;
                    double d = QString(parts.at(i)).toDouble(&res);
                    if (!res) d = 0;

268
                    if (keys.value(i, "") == "Accel._X") {
pixhawk's avatar
pixhawk committed
269 270 271
                        rawImuValues.xacc = d;
                    }

272
                    if (keys.value(i, "") == "Accel._Y") {
pixhawk's avatar
pixhawk committed
273 274 275
                        rawImuValues.yacc = d;
                    }

276
                    if (keys.value(i, "") == "Accel._Z") {
pixhawk's avatar
pixhawk committed
277 278
                        rawImuValues.zacc = d;
                    }
279
                    if (keys.value(i, "") == "Gyro_Phi") {
pixhawk's avatar
pixhawk committed
280
                        rawImuValues.xgyro = d;
281
                        attitude.rollspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
282 283
                    }

284
                    if (keys.value(i, "") == "Gyro_Theta") {
pixhawk's avatar
pixhawk committed
285
                        rawImuValues.ygyro = d;
286
                        attitude.pitchspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
287 288
                    }

289
                    if (keys.value(i, "") == "Gyro_Psi") {
pixhawk's avatar
pixhawk committed
290
                        rawImuValues.zgyro = d;
291
                        attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
292
                    }
lm's avatar
lm committed
293
#ifdef MAVLINK_ENABLED_PIXHAWK
294
                    if (keys.value(i, "") == "Pressure") {
pixhawk's avatar
pixhawk committed
295 296 297
                        rawAuxValues.baro = d;
                    }

298
                    if (keys.value(i, "") == "Battery") {
pixhawk's avatar
pixhawk committed
299 300
                        rawAuxValues.vbat = d;
                    }
301
#endif
302
                    if (keys.value(i, "") == "roll_IMU") {
pixhawk's avatar
pixhawk committed
303 304 305
                        attitude.roll = d;
                    }

306
                    if (keys.value(i, "") == "pitch_IMU") {
pixhawk's avatar
pixhawk committed
307 308 309
                        attitude.pitch = d;
                    }

310
                    if (keys.value(i, "") == "yaw_IMU") {
pixhawk's avatar
pixhawk committed
311 312 313 314 315 316 317 318 319 320
                        attitude.yaw = d;
                    }

                    //Accel._X	Accel._Y	Accel._Z	Battery	Bottom_Rotor	CPU_Load	Ground_Dist.	Gyro_Phi	Gyro_Psi	Gyro_Theta	Left_Servo	Mag._X	Mag._Y	Mag._Z	Pressure	Right_Servo	Temperature	Top_Rotor	pitch_IMU	roll_IMU	yaw_IMU

                }
                // Send out packets


                // ATTITUDE
321
                attitude.usec = time;
pixhawk's avatar
pixhawk committed
322
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
323
                mavlink_msg_attitude_encode(systemId, componentId, &msg, &attitude);
pixhawk's avatar
pixhawk committed
324
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
325
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
326 327 328 329 330
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

                // IMU
331
                rawImuValues.usec = time;
pixhawk's avatar
pixhawk committed
332 333 334 335
                rawImuValues.xmag = 0;
                rawImuValues.ymag = 0;
                rawImuValues.zmag = 0;
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
336
                mavlink_msg_raw_imu_encode(systemId, componentId, &msg, &rawImuValues);
pixhawk's avatar
pixhawk committed
337
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
338
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
339 340 341 342 343 344
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

                //qDebug() << "ATTITUDE" << "BUF LEN" << bufferlength << "POINTER" << streampointer;

345
                //qDebug() << "REALTIME" << QGC::groundTimeMilliseconds() << "ONBOARDTIME" << attitude.msec << "ROLL" << attitude.roll;
pixhawk's avatar
pixhawk committed
346 347 348

            }

pixhawk's avatar
pixhawk committed
349
        }
pixhawk's avatar
pixhawk committed
350 351 352 353 354 355

        rate50hzCounter = 1;
    }


    // 10 HZ TASKS
356
    if (rate10hzCounter == 1000 / rate / 9) {
pixhawk's avatar
pixhawk committed
357
        rate10hzCounter = 1;
pixhawk's avatar
pixhawk committed
358

359 360 361 362
        float lastX = x;
        float lastY = y;
        float lastZ = z;
        float hackDt = 0.1f; // 100 ms
363

pixhawk's avatar
pixhawk committed
364
        // Move X Position
365 366 367
        x = 12.0*sin(((double)circleCounter)/200.0);
        y = 5.0*cos(((double)circleCounter)/200.0);
        z = 1.8 + 1.2*sin(((double)circleCounter)/200.0);
368

369 370 371 372
        float xSpeed = (x - lastX)/hackDt;
        float ySpeed = (y - lastY)/hackDt;
        float zSpeed = (z - lastZ)/hackDt;

373 374


375 376
        circleCounter++;

377

378 379 380
//        x = (x > 5.0f) ? 5.0f : x;
//        y = (y > 5.0f) ? 5.0f : y;
//        z = (z > 3.0f) ? 3.0f : z;
381

382 383 384
//        x = (x < -5.0f) ? -5.0f : x;
//        y = (y < -5.0f) ? -5.0f : y;
//        z = (z < -3.0f) ? -3.0f : z;
385

pixhawk's avatar
pixhawk committed
386 387 388
        // Send back new setpoint
        mavlink_message_t ret;
        mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ, spYaw);
389 390 391 392 393 394
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        // Send back new position
395
        mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
396
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
pixhawk's avatar
pixhawk committed
397 398 399
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
400

401 402 403 404 405 406
//        // GPS RAW
//        mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.00001), 8.548103+(y*0.00001), z, 0, 0, 2.5f, 0.1f);
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
407

pixhawk's avatar
pixhawk committed
408
        // GLOBAL POSITION
409
        mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed, ySpeed, zSpeed);
pixhawk's avatar
pixhawk committed
410 411 412 413 414
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

415 416 417 418 419 420
//        // GLOBAL POSITION VEHICLE 2
//        mavlink_msg_global_position_int_pack(54, componentId, &ret, (473780.28137103+(x+0.002))*1E3, (85489.9892510421+((y/2)+0.3))*1E3, (z+570.0)*1000.0, xSpeed, ySpeed, zSpeed);
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
421

422 423 424
//        // ATTITUDE VEHICLE 2
//        mavlink_msg_attitude_pack(54, MAV_COMP_ID_IMU, &ret, 0, 0, 0, atan2((y/2)+0.3, (x+0.002)), 0, 0, 0);
//        sendMAVLinkMessage(&ret);
pixhawk's avatar
pixhawk committed
425 426


427 428 429 430 431 432
//        // GLOBAL POSITION VEHICLE 3
//        mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
433

434
        static int rcCounter = 0;
435
        if (rcCounter == 2) {
436
            mavlink_rc_channels_raw_t chan;
437 438 439 440 441 442 443
            chan.chan1_raw = 1000 + ((int)(fabs(x) * 1000) % 2000);
            chan.chan2_raw = 1000 + ((int)(fabs(y) * 1000) % 2000);
            chan.chan3_raw = 1000 + ((int)(fabs(z) * 1000) % 2000);
            chan.chan4_raw = (chan.chan1_raw + chan.chan2_raw) / 2.0f;
            chan.chan5_raw = (chan.chan3_raw + chan.chan4_raw) / 2.0f;
            chan.chan6_raw = (chan.chan3_raw + chan.chan2_raw) / 2.0f;
            chan.chan7_raw = (chan.chan4_raw + chan.chan2_raw) / 2.0f;
444
            chan.chan8_raw = 0;
pixhawk's avatar
pixhawk committed
445
            chan.rssi = 100;
446
            messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
447 448 449 450 451 452 453 454 455
            // Allocate buffer with packet data
            bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
            //add data into datastream
            memcpy(stream+streampointer,buffer, bufferlength);
            streampointer += bufferlength;
            rcCounter = 0;
        }
        rcCounter++;

pixhawk's avatar
pixhawk committed
456 457 458
    }

    // 1 HZ TASKS
459
    if (rate1hzCounter == 1000 / rate / 1) {
pixhawk's avatar
pixhawk committed
460 461
        // STATE
        static int statusCounter = 0;
462
        if (statusCounter == 100) {
pixhawk's avatar
pixhawk committed
463 464 465 466 467
            status.mode = (status.mode + 1) % MAV_MODE_TEST3;
            statusCounter = 0;
        }
        statusCounter++;

468
        static int detectionCounter = 6;
469
        if (detectionCounter % 10 == 0) {
lm's avatar
lm committed
470
#ifdef MAVLINK_ENABLED_PIXHAWK
471 472 473
            mavlink_pattern_detected_t detected;
            detected.confidence = 5.0f;

474
            if (detectionCounter == 10) {
475 476 477
                char fileName[] = "patterns/face5.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
478
            } else if (detectionCounter == 20) {
479 480 481
                char fileName[] = "7";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
482
            } else if (detectionCounter == 30) {
483 484 485
                char fileName[] = "patterns/einstein.bmp";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
486
            } else if (detectionCounter == 40) {
487 488 489
                char fileName[] = "F";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
490
            } else if (detectionCounter == 50) {
491 492 493
                char fileName[] = "patterns/face2.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
494
            } else if (detectionCounter == 60) {
495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511
                char fileName[] = "H";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
                detectionCounter = 0;
            }
            detected.detected = 1;
            messageSize = mavlink_msg_pattern_detected_encode(systemId, componentId, &msg, &detected);
            // Allocate buffer with packet data
            bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
            //add data into datastream
            memcpy(stream+streampointer,buffer, bufferlength);
            streampointer += bufferlength;
            //detectionCounter = 0;
#endif
        }
        detectionCounter++;

512
        status.vbat = voltage * 1000; // millivolts
513
        status.load = 33 * detectionCounter % 1000;
pixhawk's avatar
pixhawk committed
514 515

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
516
        messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
517
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
518
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
519 520 521 522
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

523
        // Pack debug text message
pixhawk's avatar
pixhawk committed
524
        mavlink_statustext_t text;
525
        text.severity = 0;
526
        strcpy((char*)(text.text), "Text message from system 32");
pixhawk's avatar
pixhawk committed
527 528
        mavlink_msg_statustext_encode(systemId, componentId, &msg, &text);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
529 530 531
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
532 533
        /*
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
534
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
535
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
536
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
537 538 539 540
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;*/

pixhawk's avatar
pixhawk committed
541 542
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
543
        static int typeCounter = 0;
544
        uint8_t mavType;
545
        if (typeCounter < 10) {
546
            mavType = MAV_QUADROTOR;
547
        } else {
548 549
            mavType = typeCounter % (OCU);
        }
pixhawk's avatar
pixhawk committed
550 551
        typeCounter++;

pixhawk's avatar
pixhawk committed
552
        // Pack message and get size of encoded byte string
553
        messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK);
pixhawk's avatar
pixhawk committed
554
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
555
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
556 557 558 559
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
560

pixhawk's avatar
pixhawk committed
561 562 563
        // Send controller states


lm's avatar
lm committed
564 565 566 567 568 569 570 571 572 573
#ifdef MAVLINK_ENABLED_PIXHAWK
        uint8_t attControl = 1;
        uint8_t posXYControl = 1;
        uint8_t posZControl = 0;
        uint8_t posYawControl = 1;

        uint8_t gpsLock = 2;
        uint8_t visLock = 3;
        uint8_t ahrsHealth = 200;
        uint8_t posLock = qMax(gpsLock, visLock);
574
        messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, ahrsHealth, attControl, posXYControl, posZControl, posYawControl);
lm's avatar
lm committed
575
#endif
576

pixhawk's avatar
pixhawk committed
577 578 579 580 581
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;


582

583
//        // HEARTBEAT VEHICLE 2
pixhawk's avatar
pixhawk committed
584

585 586 587 588 589 590 591
//        // Pack message and get size of encoded byte string
//        messageSize = mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA);
//        // Allocate buffer with packet data
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
pixhawk's avatar
pixhawk committed
592

593
//        // HEARTBEAT VEHICLE 3
594

595 596 597 598 599 600 601
//        // Pack message and get size of encoded byte string
//        messageSize = mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
//        // Allocate buffer with packet data
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
602

pixhawk's avatar
pixhawk committed
603
        // STATUS VEHICLE 2
604
        mavlink_sys_status_t status2;
pixhawk's avatar
pixhawk committed
605 606
        status2.mode = MAV_MODE_LOCKED;
        status2.vbat = voltage;
607
        status2.load = 120;
pixhawk's avatar
pixhawk committed
608 609 610
        status2.status = MAV_STATE_STANDBY;

        // Pack message and get size of encoded byte string
611
        messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
612
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
613
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
614 615 616
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
pixhawk's avatar
pixhawk committed
617

pixhawk's avatar
pixhawk committed
618
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
619 620 621 622 623
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
624
    /*
pixhawk's avatar
pixhawk committed
625 626 627 628
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
629
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
630 631 632 633

        // Attitude

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
634
        messageSize = mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
pixhawk's avatar
pixhawk committed
635
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
636
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
637 638 639 640 641
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
642
    }*/
pixhawk's avatar
pixhawk committed
643 644

    readyBufferMutex.lock();
645
    for (unsigned int i = 0; i < streampointer; i++) {
pixhawk's avatar
pixhawk committed
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

    // Increment counters after full main loop
    rate1hzCounter++;
    rate10hzCounter++;
    rate50hzCounter++;
}


qint64 MAVLinkSimulationLink::bytesAvailable()
{
    readyBufferMutex.lock();
    qint64 size = readyBuffer.size();
    readyBufferMutex.unlock();
    return size;
}

void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
pixhawk's avatar
pixhawk committed
667 668
    // Parse bytes
    mavlink_message_t msg;
lm's avatar
lm committed
669
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
670

671 672 673 674 675
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;

pixhawk's avatar
pixhawk committed
676 677
    // Output all bytes as hex digits
    int i;
678 679
    for (i=0; i<size; i++) {
        if (mavlink_parse_char(this->id, data[i], &msg, &comm)) {
pixhawk's avatar
pixhawk committed
680
            // MESSAGE RECEIVED!
681 682
            qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
            emit messageReceived(msg);
pixhawk's avatar
pixhawk committed
683

684
            switch (msg.msgid) {
pixhawk's avatar
pixhawk committed
685
                // SET THE SYSTEM MODE
686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740
            case MAVLINK_MSG_ID_SET_MODE: {
                mavlink_set_mode_t mode;
                mavlink_msg_set_mode_decode(&msg, &mode);
                // Set mode indepent of mode.target
                status.mode = mode.mode;
            }
            break;
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET: {
                mavlink_local_position_setpoint_set_t set;
                mavlink_msg_local_position_setpoint_set_decode(&msg, &set);
                spX = set.x;
                spY = set.y;
                spZ = set.z;
                spYaw = set.yaw;

                // Send back new setpoint
                mavlink_message_t ret;
                mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ, spYaw);
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;
            }
            break;
            // EXECUTE OPERATOR ACTIONS
            case MAVLINK_MSG_ID_ACTION: {
                mavlink_action_t action;
                mavlink_msg_action_decode(&msg, &action);

                qDebug() << "SIM" << "received action" << action.action << "for system" << action.target;

                switch (action.action) {
                case MAV_ACTION_LAUNCH:
                    status.status = MAV_STATE_ACTIVE;
                    status.mode = MAV_MODE_AUTO;
                    break;
                case MAV_ACTION_RETURN:
                    status.status = MAV_STATE_ACTIVE;
                    break;
                case MAV_ACTION_MOTORS_START:
                    status.status = MAV_STATE_ACTIVE;
                    status.mode = MAV_MODE_LOCKED;
                    break;
                case MAV_ACTION_MOTORS_STOP:
                    status.status = MAV_STATE_STANDBY;
                    status.mode = MAV_MODE_LOCKED;
                    break;
                case MAV_ACTION_EMCY_KILL:
                    status.status = MAV_STATE_EMERGENCY;
                    status.mode = MAV_MODE_MANUAL;
                    break;
                case MAV_ACTION_SHUTDOWN:
                    status.status = MAV_STATE_POWEROFF;
                    status.mode = MAV_MODE_LOCKED;
                    break;
pixhawk's avatar
pixhawk committed
741
                }
742 743
            }
            break;
lm's avatar
lm committed
744
#ifdef MAVLINK_ENABLED_PIXHAWK
745 746 747 748 749 750
            case MAVLINK_MSG_ID_MANUAL_CONTROL: {
                mavlink_manual_control_t control;
                mavlink_msg_manual_control_decode(&msg, &control);
                qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch;
            }
            break;
751
#endif
752 753 754 755
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
                qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
                mavlink_param_request_list_t read;
                mavlink_msg_param_request_list_decode(&msg, &read);
756 757
//                    if (read.target_system == systemId)
//                    {
758 759 760 761 762 763 764
                // Output all params
                // Iterate through all components, through all parameters and emit them
                QMap<QString, float>::iterator i;
                // Iterate through all components / subsystems
                int j = 0;
                for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
                    if (j != 5) {
765
                        // Pack message and get size of encoded byte string
766
                        mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)i.key().toStdString().c_str(), i.value(), onboardParams.size(), j);
767 768 769 770 771 772
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791
                    j++;
                }

                qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
//                    }
            }
            break;
            case MAVLINK_MSG_ID_PARAM_SET: {
                // Drop on even milliseconds
                if (QGC::groundTimeMilliseconds() % 2 == 0) {
                    qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER";
                    mavlink_param_set_t set;
                    mavlink_msg_param_set_decode(&msg, &set);
                    //                    if (set.target_system == systemId)
                    //                    {
                    QString key = QString((char*)set.param_id);
                    if (onboardParams.contains(key)) {
                        onboardParams.remove(key);
                        onboardParams.insert(key, set.param_value);
792 793

                        // Pack message and get size of encoded byte string
794
                        mavlink_msg_param_value_pack(set.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value, onboardParams.size(), onboardParams.keys().indexOf(key));
795 796 797 798 799 800
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
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
                    //                    }
                }
            }
            break;
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
                qDebug() << "SIMULATION RECEIVED COMMAND TO SEND PARAMETER";
                mavlink_param_request_read_t read;
                mavlink_msg_param_request_read_decode(&msg, &read);
                QByteArray bytes((char*)read.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
                QString key = QString(bytes);
                if (onboardParams.contains(key)) {
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
                    // Allocate buffer with packet data
                    bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                    //add data into datastream
                    memcpy(stream+streampointer,buffer, bufferlength);
                    streampointer+=bufferlength;
                    //qDebug() << "Sending PARAM" << key;
                } else if (read.param_index < onboardParams.size()) {
                    key = onboardParams.keys().at(read.param_index);
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
                    // Allocate buffer with packet data
                    bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                    //add data into datastream
                    memcpy(stream+streampointer,buffer, bufferlength);
                    streampointer+=bufferlength;
                    //qDebug() << "Sending PARAM #ID" << (read.param_index) << "KEY:" << key;
834
                }
835 836
            }
            break;
pixhawk's avatar
pixhawk committed
837 838 839 840
            }


        }
841 842
        unsigned char v=data[i];
        fprintf(stderr,"%02x ", v);
pixhawk's avatar
pixhawk committed
843
    }
844
    fprintf(stderr,"\n");
pixhawk's avatar
pixhawk committed
845

846
    readyBufferMutex.lock();
847
    for (int i = 0; i < streampointer; i++) {
848 849 850 851
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
852 853 854
    // Update comm status
    status.packet_drop = comm.packet_rx_drop_count;

pixhawk's avatar
pixhawk committed
855 856 857
}


858 859
void MAVLinkSimulationLink::readBytes()
{
pixhawk's avatar
pixhawk committed
860 861
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
862 863
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
864
    qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
pixhawk's avatar
pixhawk committed
865

866
    for (unsigned int i = 0; i < len; i++) {
pixhawk's avatar
pixhawk committed
867 868 869 870 871 872 873 874
        *(data + i) = readyBuffer.takeFirst();
    }

    QByteArray b(data, len);
    emit bytesReceived(this, b);

    readyBufferMutex.unlock();

875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890
//    if (len > 0)
//    {
//        qDebug() << "Simulation sent " << len << " bytes to groundstation: ";

//        /* Increase write counter */
//        //bitsSentTotal += size * 8;

//        //Output all bytes as hex digits
//        int i;
//        for (i=0; i<len; i++)
//        {
//            unsigned int v=data[i];
//            fprintf(stderr,"%02x ", v);
//        }
//        fprintf(stderr,"\n");
//    }
pixhawk's avatar
pixhawk committed
891 892 893 894 895 896 897 898
}

/**
 * Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection
 * couldn't be disconnected.
 **/
899 900
bool MAVLinkSimulationLink::disconnect()
{
pixhawk's avatar
pixhawk committed
901 902 903 904 905 906 907

    if(isConnected()) {
        //        timer->stop();

        _isConnected = false;

        emit disconnected();
908
        emit connected(false);
pixhawk's avatar
pixhawk committed
909

910
        //exit();
pixhawk's avatar
pixhawk committed
911 912 913 914 915 916 917 918 919 920 921 922 923 924
    }

    return true;
}

/**
 * Connect the link.
 *
 * @return True if connection has been established, false if connection
 * couldn't be established.
 **/
bool MAVLinkSimulationLink::connect()
{
    _isConnected = true;
925 926
    emit connected();
    emit connected(true);
pixhawk's avatar
pixhawk committed
927 928

    start(LowPriority);
LM's avatar
LM committed
929
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 37.480391, -122.282883);
930
    Q_UNUSED(mav1);
931 932
//    MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
//    Q_UNUSED(mav2);
pixhawk's avatar
pixhawk committed
933 934 935 936
    //    timer->start(rate);
    return true;
}

937 938 939 940 941 942 943 944 945 946 947 948
/**
 * Connect the link.
 *
 * @param connect true connects the link, false disconnects it
 * @return True if connection has been established, false if connection
 * couldn't be established.
 **/
void MAVLinkSimulationLink::connectLink()
{
    this->connect();
}

949 950 951 952 953 954 955 956 957 958 959
/**
 * Connect the link.
 *
 * @param connect true connects the link, false disconnects it
 * @return True if connection has been established, false if connection
 * couldn't be established.
 **/
bool MAVLinkSimulationLink::connectLink(bool connect)
{
    _isConnected = connect;

960
    if(connect) {
961 962 963 964 965 966
        this->connect();
    }

    return true;
}

pixhawk's avatar
pixhawk committed
967 968 969 970 971
/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
972 973
bool MAVLinkSimulationLink::isConnected()
{
pixhawk's avatar
pixhawk committed
974 975 976 977 978 979 980 981 982 983 984 985 986
    return _isConnected;
}

int MAVLinkSimulationLink::getId()
{
    return id;
}

QString MAVLinkSimulationLink::getName()
{
    return name;
}

987 988
qint64 MAVLinkSimulationLink::getNominalDataRate()
{
pixhawk's avatar
pixhawk committed
989 990 991 992
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
}

993 994
qint64 MAVLinkSimulationLink::getTotalUpstream()
{
pixhawk's avatar
pixhawk committed
995 996 997 998 999
    return 0;
    //TODO Add functionality here
    // @todo Add functionality here
}

1000 1001
qint64 MAVLinkSimulationLink::getShortTermUpstream()
{
pixhawk's avatar
pixhawk committed
1002 1003 1004
    return 0;
}

1005 1006
qint64 MAVLinkSimulationLink::getCurrentUpstream()
{
pixhawk's avatar
pixhawk committed
1007 1008 1009
    return 0;
}

1010 1011
qint64 MAVLinkSimulationLink::getMaxUpstream()
{
pixhawk's avatar
pixhawk committed
1012 1013 1014
    return 0;
}

1015 1016
qint64 MAVLinkSimulationLink::getBitsSent()
{
pixhawk's avatar
pixhawk committed
1017 1018 1019
    return 0;
}

1020 1021
qint64 MAVLinkSimulationLink::getBitsReceived()
{
pixhawk's avatar
pixhawk committed
1022 1023 1024
    return 0;
}

1025 1026
qint64 MAVLinkSimulationLink::getTotalDownstream()
{
pixhawk's avatar
pixhawk committed
1027 1028 1029
    return 0;
}

1030 1031
qint64 MAVLinkSimulationLink::getShortTermDownstream()
{
pixhawk's avatar
pixhawk committed
1032 1033 1034
    return 0;
}

1035 1036
qint64 MAVLinkSimulationLink::getCurrentDownstream()
{
pixhawk's avatar
pixhawk committed
1037 1038 1039
    return 0;
}

1040 1041
qint64 MAVLinkSimulationLink::getMaxDownstream()
{
pixhawk's avatar
pixhawk committed
1042 1043 1044
    return 0;
}

1045 1046
bool MAVLinkSimulationLink::isFullDuplex()
{
pixhawk's avatar
pixhawk committed
1047 1048 1049 1050
    /* Full duplex is no problem when running in pure software, but this is a serial simulation */
    return false;
}

1051 1052
int MAVLinkSimulationLink::getLinkQuality()
{
pixhawk's avatar
pixhawk committed
1053 1054 1055
    /* The Link quality is always perfect when running in software */
    return 100;
}