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 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
    status.voltage_battery = 0;
113
    status.errors_comm = 0;
114

115 116
    system.base_mode = MAV_MODE_PREFLIGHT;
    system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED;
117
    system.system_status = MAV_STATE_UNINIT;
118

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

        static quint64 last = 0;

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

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

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

    }
}

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

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

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

    // Test for encoding / decoding packets

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

    // Fake system values

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

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

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

    // Vary values

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

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

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


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

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

246
                if (lastTime > time) {
pixhawk's avatar
pixhawk committed
247 248 249 250 251 252 253 254 255
                    // 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
256
                for (int i = 1; i < (parts.size() - 1); ++i) {
pixhawk's avatar
pixhawk committed
257 258 259 260 261 262 263 264
                    // 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());

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

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

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

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

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

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

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

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

                // IMU
328
                rawImuValues.time_usec = time;
pixhawk's avatar
pixhawk committed
329 330 331 332
                rawImuValues.xmag = 0;
                rawImuValues.ymag = 0;
                rawImuValues.zmag = 0;
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
333
                mavlink_msg_raw_imu_encode(systemId, componentId, &msg, &rawImuValues);
pixhawk's avatar
pixhawk committed
334
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
335
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
336 337 338 339 340 341 342 343 344 345
                //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
346
        }
pixhawk's avatar
pixhawk committed
347 348 349 350 351 352

        rate50hzCounter = 1;
    }


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

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

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

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

370 371


372 373
        circleCounter++;

374

375 376 377
//        x = (x > 5.0f) ? 5.0f : x;
//        y = (y > 5.0f) ? 5.0f : y;
//        z = (z > 3.0f) ? 3.0f : z;
378

379 380 381
//        x = (x < -5.0f) ? -5.0f : x;
//        y = (y < -5.0f) ? -5.0f : y;
//        z = (z < -3.0f) ? -3.0f : z;
382

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

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

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

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

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

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


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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
538 539
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
540
        static int typeCounter = 0;
541
        uint8_t mavType;
lm's avatar
lm committed
542 543
        if (typeCounter < 10)
        {
lm's avatar
lm committed
544
            mavType = MAV_TYPE_QUADROTOR;
lm's avatar
lm committed
545 546 547 548
        }
        else
        {
            mavType = typeCounter % (MAV_TYPE_GCS);
549
        }
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, system.base_mode, system.custom_mode, system.system_status);
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);
lm's avatar
lm committed
556
        //qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
pixhawk's avatar
pixhawk committed
557 558 559 560
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
561

pixhawk's avatar
pixhawk committed
562 563 564 565 566 567 568
        // Send controller states

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


569

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

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

580
//        // HEARTBEAT VEHICLE 3
581

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

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

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

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

    // FULL RATE TASKS
    // Default is 50 Hz

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

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

        // Attitude

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

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

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

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

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

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

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

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

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

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

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


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

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

pixhawk's avatar
pixhawk committed
846
    // Update comm status
847
    status.errors_comm = comm.packet_rx_drop_count;
pixhawk's avatar
pixhawk committed
848

pixhawk's avatar
pixhawk committed
849 850 851
}


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

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

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

    readyBufferMutex.unlock();

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

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

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

        _isConnected = false;

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

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

    return true;
}

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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