MAVLinkSimulationLink.cc 37 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);
Lorenz Meier's avatar
Lorenz Meier committed
87 88
    if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text))
    {
pixhawk's avatar
pixhawk committed
89 90 91
        simulationHeader = simulationFile->readLine();
    }
    receiveFile = new QFile(writeFile, this);
92
    lastSent = QGC::groundTimeMilliseconds();
pixhawk's avatar
pixhawk committed
93

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

103 104


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

MAVLinkSimulationLink::~MAVLinkSimulationLink()
{
    //TODO Check destructor
    //    fileStream->flush();
    //    outStream->flush();
Lorenz Meier's avatar
Lorenz Meier committed
118 119 120 121 122
    // Force termination, there is no
    // need for cleanup since
    // this thread is not manipulating
    // any relevant data
    terminate();
lm's avatar
lm committed
123
    delete simulationFile;
pixhawk's avatar
pixhawk committed
124 125 126 127
}

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

129
    status.voltage_battery = 0;
130
    status.errors_comm = 0;
131

132 133
    system.base_mode = MAV_MODE_PREFLIGHT;
    system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED;
134
    system.system_status = MAV_STATE_UNINIT;
135

Lorenz Meier's avatar
Lorenz Meier committed
136 137
    forever
    {
pixhawk's avatar
pixhawk committed
138 139
        static quint64 last = 0;

Lorenz Meier's avatar
Lorenz Meier committed
140 141 142 143
        if (QGC::groundTimeMilliseconds() - last >= rate)
        {
            if (_isConnected)
            {
pixhawk's avatar
pixhawk committed
144
                mainloop();
145
                readBytes();
pixhawk's avatar
pixhawk committed
146
            }
Lorenz Meier's avatar
Lorenz Meier committed
147 148 149 150 151 152
            else
            {
                // Sleep for substantially longer
                // if not connected
                QGC::SLEEP::msleep(500);
            }
153
            last = QGC::groundTimeMilliseconds();
pixhawk's avatar
pixhawk committed
154
        }
155
        QGC::SLEEP::msleep(3);
pixhawk's avatar
pixhawk committed
156 157 158
    }
}

159 160 161 162 163 164 165
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
166
    readyBufferMutex.lock();
Lorenz Meier's avatar
Lorenz Meier committed
167 168
    for (unsigned int i = 0; i < bufferlength; i++)
    {
169 170
        readyBuffer.enqueue(*(buf + i));
    }
pixhawk's avatar
pixhawk committed
171
    readyBufferMutex.unlock();
172 173
}

pixhawk's avatar
pixhawk committed
174 175 176 177
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
178
    unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);
pixhawk's avatar
pixhawk committed
179 180 181 182 183
    //add data into datastream
    memcpy(stream+(*index),buf, bufferlength);
    (*index) += bufferlength;
}

pixhawk's avatar
pixhawk committed
184 185 186 187 188 189
void MAVLinkSimulationLink::mainloop()
{

    // Test for encoding / decoding packets

    // Test data stream
190
    streampointer = 0;
pixhawk's avatar
pixhawk committed
191 192 193

    // Fake system values

194 195
    static float fullVoltage = 4.2f * 3.0f;
    static float emptyVoltage = 3.35f * 3.0f;
pixhawk's avatar
pixhawk committed
196
    static float voltage = fullVoltage;
197
    static float drainRate = 0.025f; // x.xx% of the capacity is linearly drained per second
pixhawk's avatar
pixhawk committed
198

pixhawk's avatar
pixhawk committed
199
    mavlink_attitude_t attitude;
200
    memset(&attitude, 0, sizeof(mavlink_attitude_t));
201 202 203 204
#ifdef MAVLINK_ENABLED_PIXHAWK
    mavlink_raw_aux_t rawAuxValues;
    memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif
pixhawk's avatar
pixhawk committed
205
    mavlink_raw_imu_t rawImuValues;
206
    memset(&rawImuValues, 0, sizeof(mavlink_raw_imu_t));
pixhawk's avatar
pixhawk committed
207 208 209 210 211 212 213 214 215 216

    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;
217
    static unsigned int circleCounter = 0;
pixhawk's avatar
pixhawk committed
218 219 220 221 222 223

    // Vary values

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

pixhawk's avatar
pixhawk committed
226
    static int state = 0;
pixhawk's avatar
pixhawk committed
227

Lorenz Meier's avatar
Lorenz Meier committed
228 229
    if (state == 0)
    {
pixhawk's avatar
pixhawk committed
230 231 232 233 234
        state++;
    }


    // 50 HZ TASKS
Lorenz Meier's avatar
Lorenz Meier committed
235 236 237 238
    if (rate50hzCounter == 1000 / rate / 40)
    {
        if (simulationFile->isOpen())
        {
239
            if (simulationFile->atEnd()) {
pixhawk's avatar
pixhawk committed
240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255
                // 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);
256 257
            // FIXME Remove multiplicaton by 1000
            time *= 1000;
pixhawk's avatar
pixhawk committed
258

259 260
            if (ok) {
                if (timeOffset == 0) {
pixhawk's avatar
pixhawk committed
261 262 263 264
                    timeOffset = time;
                    baseTime = time;
                }

265
                if (lastTime > time) {
pixhawk's avatar
pixhawk committed
266 267 268 269 270 271 272 273 274
                    // 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
275
                for (int i = 1; i < (parts.size() - 1); ++i) {
pixhawk's avatar
pixhawk committed
276 277 278 279 280
                    // Get one data field
                    bool res;
                    double d = QString(parts.at(i)).toDouble(&res);
                    if (!res) d = 0;

281
                    if (keys.value(i, "") == "Accel._X") {
pixhawk's avatar
pixhawk committed
282 283 284
                        rawImuValues.xacc = d;
                    }

285
                    if (keys.value(i, "") == "Accel._Y") {
pixhawk's avatar
pixhawk committed
286 287 288
                        rawImuValues.yacc = d;
                    }

289
                    if (keys.value(i, "") == "Accel._Z") {
pixhawk's avatar
pixhawk committed
290 291
                        rawImuValues.zacc = d;
                    }
292
                    if (keys.value(i, "") == "Gyro_Phi") {
pixhawk's avatar
pixhawk committed
293
                        rawImuValues.xgyro = d;
294
                        attitude.rollspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
295 296
                    }

297
                    if (keys.value(i, "") == "Gyro_Theta") {
pixhawk's avatar
pixhawk committed
298
                        rawImuValues.ygyro = d;
299
                        attitude.pitchspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
300 301
                    }

302
                    if (keys.value(i, "") == "Gyro_Psi") {
pixhawk's avatar
pixhawk committed
303
                        rawImuValues.zgyro = d;
304
                        attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
305
                    }
lm's avatar
lm committed
306
#ifdef MAVLINK_ENABLED_PIXHAWK
307
                    if (keys.value(i, "") == "Pressure") {
pixhawk's avatar
pixhawk committed
308 309 310
                        rawAuxValues.baro = d;
                    }

311
                    if (keys.value(i, "") == "Battery") {
pixhawk's avatar
pixhawk committed
312 313
                        rawAuxValues.vbat = d;
                    }
314
#endif
315
                    if (keys.value(i, "") == "roll_IMU") {
pixhawk's avatar
pixhawk committed
316 317 318
                        attitude.roll = d;
                    }

319
                    if (keys.value(i, "") == "pitch_IMU") {
pixhawk's avatar
pixhawk committed
320 321 322
                        attitude.pitch = d;
                    }

323
                    if (keys.value(i, "") == "yaw_IMU") {
pixhawk's avatar
pixhawk committed
324 325 326 327 328 329 330 331 332 333
                        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
334
                attitude.time_boot_ms = time/1000;
pixhawk's avatar
pixhawk committed
335
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
336
                mavlink_msg_attitude_encode(systemId, componentId, &msg, &attitude);
pixhawk's avatar
pixhawk committed
337
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
338
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
339 340 341 342 343
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

                // IMU
344
                rawImuValues.time_usec = time;
pixhawk's avatar
pixhawk committed
345 346 347 348
                rawImuValues.xmag = 0;
                rawImuValues.ymag = 0;
                rawImuValues.zmag = 0;
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
349
                mavlink_msg_raw_imu_encode(systemId, componentId, &msg, &rawImuValues);
pixhawk's avatar
pixhawk committed
350
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
351
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
352 353 354 355 356 357
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

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

358
                //qDebug() << "REALTIME" << QGC::groundTimeMilliseconds() << "ONBOARDTIME" << attitude.msec << "ROLL" << attitude.roll;
pixhawk's avatar
pixhawk committed
359 360 361

            }

pixhawk's avatar
pixhawk committed
362
        }
pixhawk's avatar
pixhawk committed
363 364 365 366 367 368

        rate50hzCounter = 1;
    }


    // 10 HZ TASKS
369
    if (rate10hzCounter == 1000 / rate / 9) {
pixhawk's avatar
pixhawk committed
370
        rate10hzCounter = 1;
pixhawk's avatar
pixhawk committed
371

372 373 374 375
        double lastX = x;
        double lastY = y;
        double lastZ = z;
        double hackDt = 0.1f; // 100 ms
376

pixhawk's avatar
pixhawk committed
377
        // Move X Position
378 379 380
        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);
381

382 383 384
        double xSpeed = (x - lastX)/hackDt;
        double ySpeed = (y - lastY)/hackDt;
        double zSpeed = (z - lastZ)/hackDt;
385

386 387


388 389
        circleCounter++;

390

391 392 393
//        x = (x > 5.0f) ? 5.0f : x;
//        y = (y > 5.0f) ? 5.0f : y;
//        z = (z > 3.0f) ? 3.0f : z;
394

395 396 397
//        x = (x < -5.0f) ? -5.0f : x;
//        y = (y < -5.0f) ? -5.0f : y;
//        z = (z < -3.0f) ? -3.0f : z;
398

pixhawk's avatar
pixhawk committed
399 400
        // Send back new setpoint
        mavlink_message_t ret;
LM's avatar
LM committed
401
        mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw); // spYaw/180.0*M_PI);
402 403 404 405 406 407
        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
408
        mavlink_msg_local_position_ned_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
409
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
pixhawk's avatar
pixhawk committed
410 411 412
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
413

414 415 416 417 418 419
//        // 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;
420

pixhawk's avatar
pixhawk committed
421
        // GLOBAL POSITION
lm's avatar
lm committed
422
        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
423 424 425 426 427
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

428 429 430 431 432 433
        // 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;
434

435 436 437
//        // 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
438 439


440
//        // GLOBAL POSITION VEHICLE 3
441
//        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);
442 443 444 445
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
446

447
        static int rcCounter = 0;
448
        if (rcCounter == 2) {
449
            mavlink_rc_channels_raw_t chan;
lm's avatar
lm committed
450
            chan.time_boot_ms = 0;
lm's avatar
lm committed
451
            chan.port = 0;
452 453 454 455 456 457 458
            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;
459
            chan.chan8_raw = 0;
pixhawk's avatar
pixhawk committed
460
            chan.rssi = 100;
461
            messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
462 463 464 465 466 467 468 469 470
            // 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
471 472 473
    }

    // 1 HZ TASKS
474
    if (rate1hzCounter == 1000 / rate / 1) {
pixhawk's avatar
pixhawk committed
475 476
        // STATE
        static int statusCounter = 0;
477
        if (statusCounter == 100) {
478
            system.base_mode = (system.base_mode + 1) % MAV_MODE_ENUM_END;
pixhawk's avatar
pixhawk committed
479 480 481 482
            statusCounter = 0;
        }
        statusCounter++;

483
        static int detectionCounter = 6;
484
        if (detectionCounter % 10 == 0) {
lm's avatar
lm committed
485
#ifdef MAVLINK_ENABLED_PIXHAWK
486 487 488
            mavlink_pattern_detected_t detected;
            detected.confidence = 5.0f;

489
            if (detectionCounter == 10) {
490 491 492
                char fileName[] = "patterns/face5.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
493
            } else if (detectionCounter == 20) {
494 495 496
                char fileName[] = "7";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
497
            } else if (detectionCounter == 30) {
498 499 500
                char fileName[] = "patterns/einstein.bmp";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
501
            } else if (detectionCounter == 40) {
502 503 504
                char fileName[] = "F";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
505
            } else if (detectionCounter == 50) {
506 507 508
                char fileName[] = "patterns/face2.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
509
            } else if (detectionCounter == 60) {
510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526
                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++;

527
        status.voltage_battery = voltage * 1000; // millivolts
528
        status.load = 33 * detectionCounter % 1000;
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_sys_status_encode(systemId, componentId, &msg, &status);
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;

538
        // Pack debug text message
pixhawk's avatar
pixhawk committed
539
        mavlink_statustext_t text;
540
        text.severity = 0;
541
        strcpy((char*)(text.text), "Text message from system 32");
pixhawk's avatar
pixhawk committed
542 543
        mavlink_msg_statustext_encode(systemId, componentId, &msg, &text);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
544 545 546
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
547 548
        /*
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
549
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
550
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
551
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
552 553 554 555
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;*/

pixhawk's avatar
pixhawk committed
556 557
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
558
        static int typeCounter = 0;
559
        uint8_t mavType;
lm's avatar
lm committed
560 561
        if (typeCounter < 10)
        {
lm's avatar
lm committed
562
            mavType = MAV_TYPE_QUADROTOR;
lm's avatar
lm committed
563 564 565 566
        }
        else
        {
            mavType = typeCounter % (MAV_TYPE_GCS);
567
        }
pixhawk's avatar
pixhawk committed
568 569
        typeCounter++;

pixhawk's avatar
pixhawk committed
570
        // Pack message and get size of encoded byte string
571
        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
572
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
573
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
lm's avatar
lm committed
574
        //qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
pixhawk's avatar
pixhawk committed
575 576 577 578
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

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

pixhawk's avatar
pixhawk committed
589 590 591 592 593 594 595
        // Send controller states

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


596

597
//        // HEARTBEAT VEHICLE 2
pixhawk's avatar
pixhawk committed
598

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

607
//        // HEARTBEAT VEHICLE 3
608

609 610 611 612 613 614 615
//        // 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;
616

pixhawk's avatar
pixhawk committed
617
        // STATUS VEHICLE 2
618
        mavlink_sys_status_t status2;
619
        mavlink_heartbeat_t system2;
620
        system2.base_mode = MAV_MODE_PREFLIGHT;
621
        status2.voltage_battery = voltage;
622
        status2.load = 120;
623
        system2.system_status = MAV_STATE_STANDBY;
pixhawk's avatar
pixhawk committed
624 625

        // Pack message and get size of encoded byte string
626
        messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
627
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
628
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
629 630 631
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
pixhawk's avatar
pixhawk committed
632

pixhawk's avatar
pixhawk committed
633
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
634 635 636 637 638
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
639
    /*
pixhawk's avatar
pixhawk committed
640 641 642 643
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
644
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
645 646 647 648

        // Attitude

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
649
        messageSize = mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
pixhawk's avatar
pixhawk committed
650
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
651
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
652 653 654 655 656
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
657
    }*/
pixhawk's avatar
pixhawk committed
658 659

    readyBufferMutex.lock();
660
    for (unsigned int i = 0; i < streampointer; i++) {
pixhawk's avatar
pixhawk committed
661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681
        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
682 683
    // Parse bytes
    mavlink_message_t msg;
lm's avatar
lm committed
684
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
685

686 687 688 689 690
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;

pixhawk's avatar
pixhawk committed
691
    // Output all bytes as hex digits
LM's avatar
LM committed
692
    for (int i=0; i<size; i++)
lm's avatar
lm committed
693 694 695
    {
        if (mavlink_parse_char(this->id, data[i], &msg, &comm))
        {
pixhawk's avatar
pixhawk committed
696
            // MESSAGE RECEIVED!
697 698
            qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
            emit messageReceived(msg);
pixhawk's avatar
pixhawk committed
699

LM's avatar
LM committed
700 701
            switch (msg.msgid)
            {
pixhawk's avatar
pixhawk committed
702
                // SET THE SYSTEM MODE
LM's avatar
LM committed
703 704
            case MAVLINK_MSG_ID_SET_MODE:
            {
705 706 707
                mavlink_set_mode_t mode;
                mavlink_msg_set_mode_decode(&msg, &mode);
                // Set mode indepent of mode.target
708
                system.base_mode = mode.base_mode;
709 710
            }
            break;
LM's avatar
LM committed
711 712
            case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
            {
713 714
                mavlink_set_local_position_setpoint_t set;
                mavlink_msg_set_local_position_setpoint_decode(&msg, &set);
715 716 717 718 719 720 721
                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
722
                mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw);
723 724 725 726 727 728 729
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;
            }
            break;
            // EXECUTE OPERATOR ACTIONS
LM's avatar
LM committed
730 731
            case MAVLINK_MSG_ID_COMMAND_LONG:
            {
pixhawk's avatar
pixhawk committed
732 733
                mavlink_command_long_t action;
                mavlink_msg_command_long_decode(&msg, &action);
734

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

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

LM's avatar
LM committed
798 799
                    qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
                }
800
            }
LM's avatar
LM committed
801 802 803
                break;
            case MAVLINK_MSG_ID_PARAM_SET:
            {
804
                // Drop on even milliseconds
LM's avatar
LM committed
805 806
                if (QGC::groundTimeMilliseconds() % 2 == 0)
                {
807 808 809 810 811 812
                    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);
LM's avatar
LM committed
813 814
                    if (onboardParams.contains(key))
                    {
815 816
                        onboardParams.remove(key);
                        onboardParams.insert(key, set.param_value);
817 818

                        // Pack message and get size of encoded byte string
LM's avatar
LM committed
819
                        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));
820 821 822 823 824 825
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
826 827 828 829
                    //                    }
                }
            }
            break;
LM's avatar
LM committed
830 831
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            {
832 833 834 835 836
                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);
LM's avatar
LM committed
837 838
                if (onboardParams.contains(key))
                {
839 840 841
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
LM's avatar
LM committed
842
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
843 844 845 846 847 848
                    // 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;
LM's avatar
LM committed
849
                }
850
                else if (read.param_index >= 0 && read.param_index < onboardParams.keys().size())
LM's avatar
LM committed
851
                {
852 853 854 855
                    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
856
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
857 858 859 860 861 862
                    // 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;
863
                }
864 865
            }
            break;
pixhawk's avatar
pixhawk committed
866 867
            }
        }
868 869
        unsigned char v=data[i];
        fprintf(stderr,"%02x ", v);
pixhawk's avatar
pixhawk committed
870
    }
871
    fprintf(stderr,"\n");
pixhawk's avatar
pixhawk committed
872

873
    readyBufferMutex.lock();
LM's avatar
LM committed
874 875
    for (int i = 0; i < streampointer; i++)
    {
876 877 878 879
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
880
    // Update comm status
881
    status.errors_comm = comm.packet_rx_drop_count;
pixhawk's avatar
pixhawk committed
882

pixhawk's avatar
pixhawk committed
883 884 885
}


886 887
void MAVLinkSimulationLink::readBytes()
{
pixhawk's avatar
pixhawk committed
888 889
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
890 891
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
892
    qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
pixhawk's avatar
pixhawk committed
893

894
    for (unsigned int i = 0; i < len; i++) {
pixhawk's avatar
pixhawk committed
895 896 897 898 899 900 901 902
        *(data + i) = readyBuffer.takeFirst();
    }

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

    readyBufferMutex.unlock();

903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918
//    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
919 920 921 922 923 924 925 926
}

/**
 * Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection
 * couldn't be disconnected.
 **/
927 928
bool MAVLinkSimulationLink::disconnect()
{
pixhawk's avatar
pixhawk committed
929

Lorenz Meier's avatar
Lorenz Meier committed
930 931
    if(isConnected())
    {
pixhawk's avatar
pixhawk committed
932 933 934 935 936
        //        timer->stop();

        _isConnected = false;

        emit disconnected();
937
        emit connected(false);
pixhawk's avatar
pixhawk committed
938

939
        //exit();
pixhawk's avatar
pixhawk committed
940 941 942 943 944 945 946 947 948 949 950 951 952 953
    }

    return true;
}

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

    start(LowPriority);
LM's avatar
LM committed
958
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 37.480391, -122.282883);
959
    Q_UNUSED(mav1);
960 961
//    MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
//    Q_UNUSED(mav2);
pixhawk's avatar
pixhawk committed
962 963 964 965
    //    timer->start(rate);
    return true;
}

966 967 968 969 970 971 972 973 974 975 976 977
/**
 * 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();
}

978 979 980 981 982 983 984 985 986 987 988
/**
 * 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;

989
    if(connect) {
990 991 992 993 994 995
        this->connect();
    }

    return true;
}

pixhawk's avatar
pixhawk committed
996 997 998 999 1000
/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
1001 1002
bool MAVLinkSimulationLink::isConnected()
{
pixhawk's avatar
pixhawk committed
1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015
    return _isConnected;
}

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

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

1016 1017
qint64 MAVLinkSimulationLink::getNominalDataRate()
{
pixhawk's avatar
pixhawk committed
1018 1019 1020 1021
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
}

1022 1023
qint64 MAVLinkSimulationLink::getTotalUpstream()
{
pixhawk's avatar
pixhawk committed
1024 1025 1026 1027 1028
    return 0;
    //TODO Add functionality here
    // @todo Add functionality here
}

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

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

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

1044 1045
qint64 MAVLinkSimulationLink::getBitsSent()
{
pixhawk's avatar
pixhawk committed
1046 1047 1048
    return 0;
}

1049 1050
qint64 MAVLinkSimulationLink::getBitsReceived()
{
pixhawk's avatar
pixhawk committed
1051 1052 1053
    return 0;
}

1054 1055
qint64 MAVLinkSimulationLink::getTotalDownstream()
{
pixhawk's avatar
pixhawk committed
1056 1057 1058
    return 0;
}

1059 1060
qint64 MAVLinkSimulationLink::getShortTermDownstream()
{
pixhawk's avatar
pixhawk committed
1061 1062 1063
    return 0;
}

1064 1065
qint64 MAVLinkSimulationLink::getCurrentDownstream()
{
pixhawk's avatar
pixhawk committed
1066 1067 1068
    return 0;
}

1069 1070
qint64 MAVLinkSimulationLink::getMaxDownstream()
{
pixhawk's avatar
pixhawk committed
1071 1072 1073
    return 0;
}

1074 1075
bool MAVLinkSimulationLink::isFullDuplex()
{
pixhawk's avatar
pixhawk committed
1076 1077 1078 1079
    /* Full duplex is no problem when running in pure software, but this is a serial simulation */
    return false;
}

1080 1081
int MAVLinkSimulationLink::getLinkQuality()
{
pixhawk's avatar
pixhawk committed
1082 1083 1084
    /* The Link quality is always perfect when running in software */
    return 100;
}