MAVLinkSimulationLink.cc 35.8 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 39 40
/**
 * @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>
#include "MG.h"
#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
    onboardParams.insert("PID_ROLL_K_P", 0.5f);
    onboardParams.insert("PID_PITCH_K_P", 0.5f);
    onboardParams.insert("PID_YAW_K_P", 0.5f);
69
    onboardParams.insert("PID_XY_K_P", 100.0f);
pixhawk's avatar
pixhawk committed
70 71 72
    onboardParams.insert("PID_ALT_K_P", 0.5f);
    onboardParams.insert("SYS_TYPE", 1);
    onboardParams.insert("SYS_ID", systemId);
73 74
    onboardParams.insert("RC4_REV", 0);
    onboardParams.insert("RC5_REV", 1);
lm's avatar
lm committed
75

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

pixhawk's avatar
pixhawk committed
78
    simulationFile = new QFile(readFile, this);
79
    if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text)) {
pixhawk's avatar
pixhawk committed
80 81 82
        simulationHeader = simulationFile->readLine();
    }
    receiveFile = new QFile(writeFile, this);
83
    lastSent = MG::TIME::getGroundTimeNow() * 1000;
pixhawk's avatar
pixhawk committed
84

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

91 92


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

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

void MAVLinkSimulationLink::run()
{
pixhawk's avatar
pixhawk committed
111

112 113
    status.voltage_battery = 0;
    status.errors_uart = 0;
114

115 116
    system.system_mode = MAV_MODE_PREFLIGHT;
    system.system_status = MAV_STATE_UNINIT;
117

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

        static quint64 last = 0;

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

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

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

    }
}

143 144 145 146 147 148 149
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
150
    readyBufferMutex.lock();
151
    for (unsigned int i = 0; i < bufferlength; i++) {
152 153
        readyBuffer.enqueue(*(buf + i));
    }
pixhawk's avatar
pixhawk committed
154
    readyBufferMutex.unlock();
155 156
}

pixhawk's avatar
pixhawk committed
157 158 159 160
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
161
    unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);
pixhawk's avatar
pixhawk committed
162 163 164 165 166
    //add data into datastream
    memcpy(stream+(*index),buf, bufferlength);
    (*index) += bufferlength;
}

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

    // Test for encoding / decoding packets

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

    // Fake system values

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

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

    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;
200
    static unsigned int circleCounter = 0;
pixhawk's avatar
pixhawk committed
201 202 203 204 205 206

    // Vary values

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

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

211
    if (state == 0) {
pixhawk's avatar
pixhawk committed
212 213 214 215 216
        state++;
    }


    // 50 HZ TASKS
217 218 219
    if (rate50hzCounter == 1000 / rate / 40) {
        if (simulationFile->isOpen()) {
            if (simulationFile->atEnd()) {
pixhawk's avatar
pixhawk committed
220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235
                // 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);
236 237
            // FIXME Remove multiplicaton by 1000
            time *= 1000;
pixhawk's avatar
pixhawk committed
238

239 240
            if (ok) {
                if (timeOffset == 0) {
pixhawk's avatar
pixhawk committed
241 242 243 244
                    timeOffset = time;
                    baseTime = time;
                }

245
                if (lastTime > time) {
pixhawk's avatar
pixhawk committed
246 247 248 249 250 251 252 253 254
                    // 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
255
                for (int i = 1; i < (parts.size() - 1); ++i) {
pixhawk's avatar
pixhawk committed
256 257 258 259 260 261 262 263
                    // Get one data field
                    bool res;
                    double d = QString(parts.at(i)).toDouble(&res);
                    if (!res) d = 0;

                    //qDebug() << "TIME" << time << "VALUE" << d;
                    //emit valueChanged(220, keys.at(i), d, MG::TIME::getGroundTimeNow());

264
                    if (keys.value(i, "") == "Accel._X") {
pixhawk's avatar
pixhawk committed
265 266 267
                        rawImuValues.xacc = d;
                    }

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

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

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

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

294
                    if (keys.value(i, "") == "Battery") {
pixhawk's avatar
pixhawk committed
295 296
                        rawAuxValues.vbat = d;
                    }
297
#endif
298
                    if (keys.value(i, "") == "roll_IMU") {
pixhawk's avatar
pixhawk committed
299 300 301
                        attitude.roll = d;
                    }

302
                    if (keys.value(i, "") == "pitch_IMU") {
pixhawk's avatar
pixhawk committed
303 304 305
                        attitude.pitch = d;
                    }

306
                    if (keys.value(i, "") == "yaw_IMU") {
pixhawk's avatar
pixhawk committed
307 308 309 310 311 312 313 314 315 316
                        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
317
                attitude.usec = time;
pixhawk's avatar
pixhawk committed
318
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
319
                mavlink_msg_attitude_encode(systemId, componentId, &msg, &attitude);
pixhawk's avatar
pixhawk committed
320
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
321
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
322 323 324 325 326
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

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

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

                //qDebug() << "REALTIME" << MG::TIME::getGroundTimeNow() << "ONBOARDTIME" << attitude.msec << "ROLL" << attitude.roll;

            }

pixhawk's avatar
pixhawk committed
345
        }
pixhawk's avatar
pixhawk committed
346 347 348 349 350 351

        rate50hzCounter = 1;
    }


    // 10 HZ TASKS
352
    if (rate10hzCounter == 1000 / rate / 9) {
pixhawk's avatar
pixhawk committed
353
        rate10hzCounter = 1;
pixhawk's avatar
pixhawk committed
354

355 356 357 358
        float lastX = x;
        float lastY = y;
        float lastZ = z;
        float hackDt = 0.1f; // 100 ms
359

pixhawk's avatar
pixhawk committed
360
        // Move X Position
361 362 363
        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);
364

365 366 367 368
        float xSpeed = (x - lastX)/hackDt;
        float ySpeed = (y - lastY)/hackDt;
        float zSpeed = (z - lastZ)/hackDt;

369 370


371 372
        circleCounter++;

373

374 375 376
//        x = (x > 5.0f) ? 5.0f : x;
//        y = (y > 5.0f) ? 5.0f : y;
//        z = (z > 3.0f) ? 3.0f : z;
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

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

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

397 398 399 400 401 402
//        // 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;
403

pixhawk's avatar
pixhawk committed
404
        // GLOBAL POSITION
LM's avatar
LM committed
405
        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, yaw);
pixhawk's avatar
pixhawk committed
406 407 408 409 410
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

411 412 413 414 415 416
//        // 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;
417

418 419 420
//        // 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
421 422


423 424 425 426 427 428
//        // 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;
429

430
        static int rcCounter = 0;
431
        if (rcCounter == 2) {
432
            mavlink_rc_channels_raw_t chan;
433 434 435 436 437 438 439
            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;
440
            chan.chan8_raw = 0;
pixhawk's avatar
pixhawk committed
441
            chan.rssi = 100;
442
            messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
443 444 445 446 447 448 449 450 451
            // 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
452 453 454
    }

    // 1 HZ TASKS
455
    if (rate1hzCounter == 1000 / rate / 1) {
pixhawk's avatar
pixhawk committed
456 457
        // STATE
        static int statusCounter = 0;
458
        if (statusCounter == 100) {
459
            system.system_mode = (system.system_mode + 1) % MAV_MODE_ENUM_END;
pixhawk's avatar
pixhawk committed
460 461 462 463
            statusCounter = 0;
        }
        statusCounter++;

464
        static int detectionCounter = 6;
465
        if (detectionCounter % 10 == 0) {
lm's avatar
lm committed
466
#ifdef MAVLINK_ENABLED_PIXHAWK
467 468 469
            mavlink_pattern_detected_t detected;
            detected.confidence = 5.0f;

470
            if (detectionCounter == 10) {
471 472 473
                char fileName[] = "patterns/face5.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
474
            } else if (detectionCounter == 20) {
475 476 477
                char fileName[] = "7";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
478
            } else if (detectionCounter == 30) {
479 480 481
                char fileName[] = "patterns/einstein.bmp";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
482
            } else if (detectionCounter == 40) {
483 484 485
                char fileName[] = "F";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
486
            } else if (detectionCounter == 50) {
487 488 489
                char fileName[] = "patterns/face2.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
490
            } else if (detectionCounter == 60) {
491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507
                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++;

508
        status.voltage_battery = voltage * 1000; // millivolts
509
        status.load = 33 * detectionCounter % 1000;
pixhawk's avatar
pixhawk committed
510 511

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

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

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

pixhawk's avatar
pixhawk committed
537 538
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
539
        static int typeCounter = 0;
540
        uint8_t mavType;
lm's avatar
lm committed
541 542
        if (typeCounter < 10)
        {
lm's avatar
lm committed
543
            mavType = MAV_TYPE_QUADROTOR;
lm's avatar
lm committed
544 545 546 547
        }
        else
        {
            mavType = typeCounter % (MAV_TYPE_GCS);
548
        }
pixhawk's avatar
pixhawk committed
549 550
        typeCounter++;

pixhawk's avatar
pixhawk committed
551
        // Pack message and get size of encoded byte string
552
        messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.system_mode, system.flight_mode, system.system_status, system.safety_status, system.link_status);
pixhawk's avatar
pixhawk committed
553
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
554
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
lm's avatar
lm committed
555
        //qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
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 564 565 566 567
        // Send controller states

        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;


568

569
//        // HEARTBEAT VEHICLE 2
pixhawk's avatar
pixhawk committed
570

571 572 573 574 575 576 577
//        // 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
578

579
//        // HEARTBEAT VEHICLE 3
580

581 582 583 584 585 586 587
//        // 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;
588

pixhawk's avatar
pixhawk committed
589
        // STATUS VEHICLE 2
590
        mavlink_sys_status_t status2;
591 592 593
        mavlink_heartbeat_t system2;
        system2.system_mode = MAV_MODE_PREFLIGHT;
        status2.voltage_battery = voltage;
594
        status2.load = 120;
595
        system2.system_status = MAV_STATE_STANDBY;
pixhawk's avatar
pixhawk committed
596 597

        // Pack message and get size of encoded byte string
598
        messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
599
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
600
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
601 602 603
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
pixhawk's avatar
pixhawk committed
604

pixhawk's avatar
pixhawk committed
605
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
606 607 608 609 610
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
611
    /*
pixhawk's avatar
pixhawk committed
612 613 614 615
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
616
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
617 618 619 620

        // Attitude

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
621
        messageSize = mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
pixhawk's avatar
pixhawk committed
622
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
623
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
624 625 626 627 628
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
629
    }*/
pixhawk's avatar
pixhawk committed
630 631

    readyBufferMutex.lock();
632
    for (unsigned int i = 0; i < streampointer; i++) {
pixhawk's avatar
pixhawk committed
633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653
        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)
{
654
    //qDebug() << "Simulation received " << size << " bytes from groundstation: ";
pixhawk's avatar
pixhawk committed
655 656 657 658

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

pixhawk's avatar
pixhawk committed
659 660
    // Parse bytes
    mavlink_message_t msg;
lm's avatar
lm committed
661
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
662

663 664 665 666 667
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;

pixhawk's avatar
pixhawk committed
668 669
    // Output all bytes as hex digits
    int i;
670 671
    for (i=0; i<size; i++) {
        if (mavlink_parse_char(this->id, data[i], &msg, &comm)) {
pixhawk's avatar
pixhawk committed
672
            // MESSAGE RECEIVED!
673 674
            qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
            emit messageReceived(msg);
pixhawk's avatar
pixhawk committed
675

676
            switch (msg.msgid) {
pixhawk's avatar
pixhawk committed
677
                // SET THE SYSTEM MODE
678 679 680 681
            case MAVLINK_MSG_ID_SET_MODE: {
                mavlink_set_mode_t mode;
                mavlink_msg_set_mode_decode(&msg, &mode);
                // Set mode indepent of mode.target
682
                system.system_mode = mode.mode;
683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702
            }
            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
703 704 705
            case MAVLINK_MSG_ID_COMMAND_SHORT: {
                mavlink_command_short_t action;
                mavlink_msg_command_short_decode(&msg, &action);
706

LM's avatar
LM committed
707
                qDebug() << "SIM" << "received action" << action.command << "for system" << action.target_system;
708

lm's avatar
lm committed
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
                // FIXME MAVLINKV10PORTINGNEEDED
//                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;
//                }
735 736
            }
            break;
lm's avatar
lm committed
737
#ifdef MAVLINK_ENABLED_PIXHAWK
738 739 740 741 742 743
            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;
744
#endif
745 746 747 748
            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);
749 750
//                    if (read.target_system == systemId)
//                    {
751 752 753 754 755 756 757
                // 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) {
758
                        // Pack message and get size of encoded byte string
759
                        mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), 0, onboardParams.size(), j);
760 761 762 763 764 765
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784
                    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);
785 786

                        // Pack message and get size of encoded byte string
787
                        mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, 0, onboardParams.size(), onboardParams.keys().indexOf(key));
788 789 790 791 792 793
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
794 795 796 797 798 799 800 801 802 803 804 805 806 807
                    //                    }
                }
            }
            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
808
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key));
809 810 811 812 813 814 815 816 817 818 819
                    // 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
820
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key));
821 822 823 824 825 826
                    // 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;
827
                }
828 829
            }
            break;
pixhawk's avatar
pixhawk committed
830 831 832 833
            }


        }
834 835
        unsigned char v=data[i];
        fprintf(stderr,"%02x ", v);
pixhawk's avatar
pixhawk committed
836
    }
837
    fprintf(stderr,"\n");
pixhawk's avatar
pixhawk committed
838

839
    readyBufferMutex.lock();
840
    for (int i = 0; i < streampointer; i++) {
841 842 843 844
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
845
    // Update comm status
846
    status.errors_uart = comm.packet_rx_drop_count;
pixhawk's avatar
pixhawk committed
847

pixhawk's avatar
pixhawk committed
848 849 850
}


851 852
void MAVLinkSimulationLink::readBytes()
{
pixhawk's avatar
pixhawk committed
853 854
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
855 856
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
857
    qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
pixhawk's avatar
pixhawk committed
858

859
    for (unsigned int i = 0; i < len; i++) {
pixhawk's avatar
pixhawk committed
860 861 862 863 864 865 866 867
        *(data + i) = readyBuffer.takeFirst();
    }

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

    readyBufferMutex.unlock();

868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883
//    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
884 885 886 887 888 889 890 891
}

/**
 * Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection
 * couldn't be disconnected.
 **/
892 893
bool MAVLinkSimulationLink::disconnect()
{
pixhawk's avatar
pixhawk committed
894 895 896 897 898 899 900

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

        _isConnected = false;

        emit disconnected();
901
        emit connected(false);
pixhawk's avatar
pixhawk committed
902

903
        //exit();
pixhawk's avatar
pixhawk committed
904 905 906 907 908 909 910 911 912 913 914 915 916 917
    }

    return true;
}

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

    start(LowPriority);
LM's avatar
LM committed
922
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 37.480391, -122.282883);
923
    Q_UNUSED(mav1);
924 925
//    MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
//    Q_UNUSED(mav2);
pixhawk's avatar
pixhawk committed
926 927 928 929
    //    timer->start(rate);
    return true;
}

930 931 932 933 934 935 936 937 938 939 940 941
/**
 * 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();
}

942 943 944 945 946 947 948 949 950 951 952
/**
 * 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;

953
    if(connect) {
954 955 956 957 958 959
        this->connect();
    }

    return true;
}

pixhawk's avatar
pixhawk committed
960 961 962 963 964
/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
965 966
bool MAVLinkSimulationLink::isConnected()
{
pixhawk's avatar
pixhawk committed
967 968 969 970 971 972 973 974 975 976 977 978 979
    return _isConnected;
}

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

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

980 981
qint64 MAVLinkSimulationLink::getNominalDataRate()
{
pixhawk's avatar
pixhawk committed
982 983 984 985
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
}

986 987
qint64 MAVLinkSimulationLink::getTotalUpstream()
{
pixhawk's avatar
pixhawk committed
988 989 990 991 992
    return 0;
    //TODO Add functionality here
    // @todo Add functionality here
}

993 994
qint64 MAVLinkSimulationLink::getShortTermUpstream()
{
pixhawk's avatar
pixhawk committed
995 996 997
    return 0;
}

998 999
qint64 MAVLinkSimulationLink::getCurrentUpstream()
{
pixhawk's avatar
pixhawk committed
1000 1001 1002
    return 0;
}

1003 1004
qint64 MAVLinkSimulationLink::getMaxUpstream()
{
pixhawk's avatar
pixhawk committed
1005 1006 1007
    return 0;
}

1008 1009
qint64 MAVLinkSimulationLink::getBitsSent()
{
pixhawk's avatar
pixhawk committed
1010 1011 1012
    return 0;
}

1013 1014
qint64 MAVLinkSimulationLink::getBitsReceived()
{
pixhawk's avatar
pixhawk committed
1015 1016 1017
    return 0;
}

1018 1019
qint64 MAVLinkSimulationLink::getTotalDownstream()
{
pixhawk's avatar
pixhawk committed
1020 1021 1022
    return 0;
}

1023 1024
qint64 MAVLinkSimulationLink::getShortTermDownstream()
{
pixhawk's avatar
pixhawk committed
1025 1026 1027
    return 0;
}

1028 1029
qint64 MAVLinkSimulationLink::getCurrentDownstream()
{
pixhawk's avatar
pixhawk committed
1030 1031 1032
    return 0;
}

1033 1034
qint64 MAVLinkSimulationLink::getMaxDownstream()
{
pixhawk's avatar
pixhawk committed
1035 1036 1037
    return 0;
}

1038 1039
bool MAVLinkSimulationLink::isFullDuplex()
{
pixhawk's avatar
pixhawk committed
1040 1041 1042 1043
    /* Full duplex is no problem when running in pure software, but this is a serial simulation */
    return false;
}

1044 1045
int MAVLinkSimulationLink::getLinkQuality()
{
pixhawk's avatar
pixhawk committed
1046 1047 1048
    /* The Link quality is always perfect when running in software */
    return 100;
}