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

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

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

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

lm's avatar
lm committed
9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.
pixhawk's avatar
pixhawk committed
13

lm's avatar
lm committed
14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.
pixhawk's avatar
pixhawk committed
18

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

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

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

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

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

lm's avatar
lm committed
65
    onboardParams = QMap<QString, float>();
pixhawk's avatar
pixhawk committed
66 67 68
    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 76 77 78 79 80 81 82
    onboardParams.insert("HDNG2RLL_P", 0.7f);
    onboardParams.insert("HDNG2RLL_I", 0.01f);
    onboardParams.insert("HDNG2RLL_D", 0.02f);
    onboardParams.insert("HDNG2RLL_IMAX", 500.0f);
    onboardParams.insert("RLL2SRV_P", 0.4f);
    onboardParams.insert("RLL2SRV_I", 0.0f);
    onboardParams.insert("RLL2SRV_D", 0.0f);
    onboardParams.insert("RLL2SRV_IMAX", 500.0f);
lm's avatar
lm committed
83

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

pixhawk's avatar
pixhawk committed
86
    simulationFile = new QFile(readFile, this);
87
    if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text)) {
pixhawk's avatar
pixhawk committed
88 89 90
        simulationHeader = simulationFile->readLine();
    }
    receiveFile = new QFile(writeFile, this);
91
    lastSent = QGC::groundTimeMilliseconds();
pixhawk's avatar
pixhawk committed
92

93
    if (simulationFile->exists()) {
pixhawk's avatar
pixhawk committed
94
        this->name = "Simulation: " + QFileInfo(simulationFile->fileName()).fileName();
95
    } else {
pixhawk's avatar
pixhawk committed
96 97 98
        this->name = "MAVLink simulation link";
    }

99 100


pixhawk's avatar
pixhawk committed
101 102 103
    // Initialize the pseudo-random number generator
    srand(QTime::currentTime().msec());
    maxTimeNoise = 0;
pixhawk's avatar
pixhawk committed
104 105
    this->id = getNextLinkId();
    LinkManager::instance()->add(this);
106
    QObject::connect(this, SIGNAL(destroyed(QObject*)), LinkManager::instance(), SLOT(removeLink(QObject*)));
pixhawk's avatar
pixhawk committed
107 108 109 110 111 112 113
}

MAVLinkSimulationLink::~MAVLinkSimulationLink()
{
    //TODO Check destructor
    //    fileStream->flush();
    //    outStream->flush();
lm's avatar
lm committed
114
    delete simulationFile;
pixhawk's avatar
pixhawk committed
115 116 117 118
}

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

120
    status.voltage_battery = 0;
121
    status.errors_comm = 0;
122

123 124
    system.base_mode = MAV_MODE_PREFLIGHT;
    system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED;
125
    system.system_status = MAV_STATE_UNINIT;
126

127
    forever {
pixhawk's avatar
pixhawk committed
128 129 130

        static quint64 last = 0;

131
        if (QGC::groundTimeMilliseconds() - last >= rate) {
132
            if (_isConnected) {
pixhawk's avatar
pixhawk committed
133
                mainloop();
134 135 136 137 138 139 140 141 142

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

143
                readBytes();
pixhawk's avatar
pixhawk committed
144
            }
145
            last = QGC::groundTimeMilliseconds();
pixhawk's avatar
pixhawk committed
146
        }
147
        QGC::SLEEP::msleep(3);
pixhawk's avatar
pixhawk committed
148 149 150 151

    }
}

152 153 154 155 156 157 158
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
159
    readyBufferMutex.lock();
160
    for (unsigned int i = 0; i < bufferlength; i++) {
161 162
        readyBuffer.enqueue(*(buf + i));
    }
pixhawk's avatar
pixhawk committed
163
    readyBufferMutex.unlock();
164 165
}

pixhawk's avatar
pixhawk committed
166 167 168 169
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
170
    unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);
pixhawk's avatar
pixhawk committed
171 172 173 174 175
    //add data into datastream
    memcpy(stream+(*index),buf, bufferlength);
    (*index) += bufferlength;
}

pixhawk's avatar
pixhawk committed
176 177 178 179 180 181
void MAVLinkSimulationLink::mainloop()
{

    // Test for encoding / decoding packets

    // Test data stream
182
    streampointer = 0;
pixhawk's avatar
pixhawk committed
183 184 185

    // Fake system values

186 187
    static float fullVoltage = 4.2f * 3.0f;
    static float emptyVoltage = 3.35f * 3.0f;
pixhawk's avatar
pixhawk committed
188
    static float voltage = fullVoltage;
189
    static float drainRate = 0.025f; // x.xx% of the capacity is linearly drained per second
pixhawk's avatar
pixhawk committed
190

pixhawk's avatar
pixhawk committed
191
    mavlink_attitude_t attitude;
192
    memset(&attitude, 0, sizeof(mavlink_attitude_t));
193 194 195 196
#ifdef MAVLINK_ENABLED_PIXHAWK
    mavlink_raw_aux_t rawAuxValues;
    memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif
pixhawk's avatar
pixhawk committed
197
    mavlink_raw_imu_t rawImuValues;
198
    memset(&rawImuValues, 0, sizeof(mavlink_raw_imu_t));
pixhawk's avatar
pixhawk committed
199 200 201 202 203 204 205 206 207 208

    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;
209
    static unsigned int circleCounter = 0;
pixhawk's avatar
pixhawk committed
210 211 212 213 214 215

    // Vary values

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

pixhawk's avatar
pixhawk committed
218
    static int state = 0;
pixhawk's avatar
pixhawk committed
219

220
    if (state == 0) {
pixhawk's avatar
pixhawk committed
221 222 223 224 225
        state++;
    }


    // 50 HZ TASKS
226 227 228
    if (rate50hzCounter == 1000 / rate / 40) {
        if (simulationFile->isOpen()) {
            if (simulationFile->atEnd()) {
pixhawk's avatar
pixhawk committed
229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244
                // 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);
245 246
            // FIXME Remove multiplicaton by 1000
            time *= 1000;
pixhawk's avatar
pixhawk committed
247

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

254
                if (lastTime > time) {
pixhawk's avatar
pixhawk committed
255 256 257 258 259 260 261 262 263
                    // 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
264
                for (int i = 1; i < (parts.size() - 1); ++i) {
pixhawk's avatar
pixhawk committed
265 266 267 268 269
                    // Get one data field
                    bool res;
                    double d = QString(parts.at(i)).toDouble(&res);
                    if (!res) d = 0;

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

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

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

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

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

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

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

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

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

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

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

            }

pixhawk's avatar
pixhawk committed
351
        }
pixhawk's avatar
pixhawk committed
352 353 354 355 356 357

        rate50hzCounter = 1;
    }


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

361 362 363 364
        double lastX = x;
        double lastY = y;
        double lastZ = z;
        double hackDt = 0.1f; // 100 ms
365

pixhawk's avatar
pixhawk committed
366
        // Move X Position
367 368 369
        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);
370

371 372 373
        double xSpeed = (x - lastX)/hackDt;
        double ySpeed = (y - lastY)/hackDt;
        double zSpeed = (z - lastZ)/hackDt;
374

375 376


377 378
        circleCounter++;

379

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

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

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

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

403 404 405 406 407 408
//        // 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;
409

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

417 418 419 420 421 422
        // GLOBAL POSITION VEHICLE 2
        mavlink_msg_global_position_int_pack(systemId+1, componentId+1, &ret, 0, (473780.28137103+(x+0.00001))*1E3, (85489.9892510421+((y/2)+0.00001))*1E3, (z+550.0)*1000.0, (z+550.0)*1000.0-1, xSpeed, ySpeed, zSpeed, yaw);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
423

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


429
//        // GLOBAL POSITION VEHICLE 3
430
//        mavlink_msg_global_position_int_pack(60, componentId, &ret, 0, (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);
431 432 433 434
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
435

436
        static int rcCounter = 0;
437
        if (rcCounter == 2) {
438
            mavlink_rc_channels_raw_t chan;
lm's avatar
lm committed
439
            chan.time_boot_ms = 0;
lm's avatar
lm committed
440
            chan.port = 0;
441 442 443 444 445 446 447
            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;
448
            chan.chan8_raw = 0;
pixhawk's avatar
pixhawk committed
449
            chan.rssi = 100;
450
            messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
451 452 453 454 455 456 457 458 459
            // 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
460 461 462
    }

    // 1 HZ TASKS
463
    if (rate1hzCounter == 1000 / rate / 1) {
pixhawk's avatar
pixhawk committed
464 465
        // STATE
        static int statusCounter = 0;
466
        if (statusCounter == 100) {
467
            system.base_mode = (system.base_mode + 1) % MAV_MODE_ENUM_END;
pixhawk's avatar
pixhawk committed
468 469 470 471
            statusCounter = 0;
        }
        statusCounter++;

472
        static int detectionCounter = 6;
473
        if (detectionCounter % 10 == 0) {
lm's avatar
lm committed
474
#ifdef MAVLINK_ENABLED_PIXHAWK
475 476 477
            mavlink_pattern_detected_t detected;
            detected.confidence = 5.0f;

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

516
        status.voltage_battery = voltage * 1000; // millivolts
517
        status.load = 33 * detectionCounter % 1000;
pixhawk's avatar
pixhawk committed
518 519

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

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

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

pixhawk's avatar
pixhawk committed
545 546
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
547
        static int typeCounter = 0;
548
        uint8_t mavType;
lm's avatar
lm committed
549 550
        if (typeCounter < 10)
        {
lm's avatar
lm committed
551
            mavType = MAV_TYPE_QUADROTOR;
lm's avatar
lm committed
552 553 554 555
        }
        else
        {
            mavType = typeCounter % (MAV_TYPE_GCS);
556
        }
pixhawk's avatar
pixhawk committed
557 558
        typeCounter++;

pixhawk's avatar
pixhawk committed
559
        // Pack message and get size of encoded byte string
560
        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
561
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
562
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
lm's avatar
lm committed
563
        //qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
pixhawk's avatar
pixhawk committed
564 565 566 567
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

568 569 570 571 572 573 574 575 576
        // Pack message and get size of encoded byte string
        messageSize = mavlink_msg_heartbeat_pack(systemId+1, componentId+1, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status);
        // Allocate buffer with packet data
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
        //qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
577

pixhawk's avatar
pixhawk committed
578 579 580 581 582 583 584
        // Send controller states

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


585

586
//        // HEARTBEAT VEHICLE 2
pixhawk's avatar
pixhawk committed
587

588 589 590 591 592 593 594
//        // 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
595

596
//        // HEARTBEAT VEHICLE 3
597

598 599 600 601 602 603 604
//        // 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;
605

pixhawk's avatar
pixhawk committed
606
        // STATUS VEHICLE 2
607
        mavlink_sys_status_t status2;
608
        mavlink_heartbeat_t system2;
609
        system2.base_mode = MAV_MODE_PREFLIGHT;
610
        status2.voltage_battery = voltage;
611
        status2.load = 120;
612
        system2.system_status = MAV_STATE_STANDBY;
pixhawk's avatar
pixhawk committed
613 614

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

pixhawk's avatar
pixhawk committed
622
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
623 624 625 626 627
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
628
    /*
pixhawk's avatar
pixhawk committed
629 630 631 632
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
633
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
634 635 636 637

        // Attitude

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

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
646
    }*/
pixhawk's avatar
pixhawk committed
647 648

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

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


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

void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
pixhawk's avatar
pixhawk committed
671 672
    // Parse bytes
    mavlink_message_t msg;
lm's avatar
lm committed
673
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
674

675 676 677 678 679
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;

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

690
            switch (msg.msgid) {
pixhawk's avatar
pixhawk committed
691
                // SET THE SYSTEM MODE
692 693 694 695
            case MAVLINK_MSG_ID_SET_MODE: {
                mavlink_set_mode_t mode;
                mavlink_msg_set_mode_decode(&msg, &mode);
                // Set mode indepent of mode.target
696
                system.base_mode = mode.base_mode;
697 698
            }
            break;
699 700 701
            case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT: {
                mavlink_set_local_position_setpoint_t set;
                mavlink_msg_set_local_position_setpoint_decode(&msg, &set);
702 703 704 705 706 707 708
                spX = set.x;
                spY = set.y;
                spZ = set.z;
                spYaw = set.yaw;

                // Send back new setpoint
                mavlink_message_t ret;
lm's avatar
lm committed
709
                mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw);
710 711 712 713 714 715 716
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;
            }
            break;
            // EXECUTE OPERATOR ACTIONS
pixhawk's avatar
pixhawk committed
717 718 719
            case MAVLINK_MSG_ID_COMMAND_LONG: {
                mavlink_command_long_t action;
                mavlink_msg_command_long_decode(&msg, &action);
720

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

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

                        // Pack message and get size of encoded byte string
LM's avatar
LM committed
801
                        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));
802 803 804 805 806 807
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
808 809 810 811 812 813 814 815 816 817 818 819 820 821
                    //                    }
                }
            }
            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
822
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
823 824 825 826 827 828 829 830 831 832 833
                    // 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
834
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
835 836 837 838 839 840
                    // 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;
841
                }
842 843
            }
            break;
pixhawk's avatar
pixhawk committed
844 845 846 847
            }


        }
848 849
        unsigned char v=data[i];
        fprintf(stderr,"%02x ", v);
pixhawk's avatar
pixhawk committed
850
    }
851
    fprintf(stderr,"\n");
pixhawk's avatar
pixhawk committed
852

853
    readyBufferMutex.lock();
854
    for (int i = 0; i < streampointer; i++) {
855 856 857 858
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
859
    // Update comm status
860
    status.errors_comm = comm.packet_rx_drop_count;
pixhawk's avatar
pixhawk committed
861

pixhawk's avatar
pixhawk committed
862 863 864
}


865 866
void MAVLinkSimulationLink::readBytes()
{
pixhawk's avatar
pixhawk committed
867 868
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
869 870
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
871
    qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
pixhawk's avatar
pixhawk committed
872

873
    for (unsigned int i = 0; i < len; i++) {
pixhawk's avatar
pixhawk committed
874 875 876 877 878 879 880 881
        *(data + i) = readyBuffer.takeFirst();
    }

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

    readyBufferMutex.unlock();

882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897
//    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
898 899 900 901 902 903 904 905
}

/**
 * Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection
 * couldn't be disconnected.
 **/
906 907
bool MAVLinkSimulationLink::disconnect()
{
pixhawk's avatar
pixhawk committed
908 909 910 911 912 913 914

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

        _isConnected = false;

        emit disconnected();
915
        emit connected(false);
pixhawk's avatar
pixhawk committed
916

917
        //exit();
pixhawk's avatar
pixhawk committed
918 919 920 921 922 923 924 925 926 927 928 929 930 931
    }

    return true;
}

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

    start(LowPriority);
LM's avatar
LM committed
936
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 37.480391, -122.282883);
937
    Q_UNUSED(mav1);
938 939
//    MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
//    Q_UNUSED(mav2);
pixhawk's avatar
pixhawk committed
940 941 942 943
    //    timer->start(rate);
    return true;
}

944 945 946 947 948 949 950 951 952 953 954 955
/**
 * 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();
}

956 957 958 959 960 961 962 963 964 965 966
/**
 * 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;

967
    if(connect) {
968 969 970 971 972 973
        this->connect();
    }

    return true;
}

pixhawk's avatar
pixhawk committed
974 975 976 977 978
/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
979 980
bool MAVLinkSimulationLink::isConnected()
{
pixhawk's avatar
pixhawk committed
981 982 983 984 985 986 987 988 989 990 991 992 993
    return _isConnected;
}

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

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

994 995
qint64 MAVLinkSimulationLink::getNominalDataRate()
{
pixhawk's avatar
pixhawk committed
996 997 998 999
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
}

1000 1001
qint64 MAVLinkSimulationLink::getTotalUpstream()
{
pixhawk's avatar
pixhawk committed
1002 1003 1004 1005 1006
    return 0;
    //TODO Add functionality here
    // @todo Add functionality here
}

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

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

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

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

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

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

1037 1038
qint64 MAVLinkSimulationLink::getShortTermDownstream()
{
pixhawk's avatar
pixhawk committed
1039 1040 1041
    return 0;
}

1042 1043
qint64 MAVLinkSimulationLink::getCurrentDownstream()
{
pixhawk's avatar
pixhawk committed
1044 1045 1046
    return 0;
}

1047 1048
qint64 MAVLinkSimulationLink::getMaxDownstream()
{
pixhawk's avatar
pixhawk committed
1049 1050 1051
    return 0;
}

1052 1053
bool MAVLinkSimulationLink::isFullDuplex()
{
pixhawk's avatar
pixhawk committed
1054 1055 1056 1057
    /* Full duplex is no problem when running in pure software, but this is a serial simulation */
    return false;
}

1058 1059
int MAVLinkSimulationLink::getLinkQuality()
{
pixhawk's avatar
pixhawk committed
1060 1061 1062
    /* The Link quality is always perfect when running in software */
    return 100;
}