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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

93 94


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

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

void MAVLinkSimulationLink::run()
{
pixhawk's avatar
pixhawk committed
112 113 114 115 116 117 118

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

119 120


pixhawk's avatar
pixhawk committed
121 122 123 124 125 126 127 128 129 130
    forever
    {

        static quint64 last = 0;

        if (MG::TIME::getGroundTimeNow() - last >= rate)
        {
            if (_isConnected)
            {
                mainloop();
131 132 133 134 135 136 137 138 139

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

140
                readBytes();
pixhawk's avatar
pixhawk committed
141 142 143
            }
            last = MG::TIME::getGroundTimeNow();
        }
144
        QGC::SLEEP::msleep(3);
pixhawk's avatar
pixhawk committed
145 146 147 148

    }
}

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

    //qDebug() << "SENT MAVLINK MESSAGE FROM SYSTEM" << msg->sysid << "COMP" << msg->compid;
}

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 186 187 188

    // Fake system values

    static float fullVoltage = 4.2 * 3;
    static float emptyVoltage = 3.35 * 3;
    static float voltage = fullVoltage;
189
    static float drainRate = 0.025; // 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));
lm's avatar
lm committed
193
    #ifdef MAVLINK_ENABLED_PIXHAWK
194
      mavlink_raw_aux_t rawAuxValues;
195
      memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
196
    #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 216 217

    // Vary values

    // VOLTAGE
    // The battery is drained constantly
    voltage = voltage - ((fullVoltage - emptyVoltage) * drainRate / rate);
    if (voltage < 3.550 * 3) voltage = 3.550 * 3;

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

pixhawk's avatar
pixhawk committed
220
    if (state == 0)
pixhawk's avatar
pixhawk committed
221
    {
pixhawk's avatar
pixhawk committed
222 223
        // BOOT
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
224
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
225
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
226
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
227 228 229 230 231 232 233 234 235 236 237
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
        state++;
    }


    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 40)
    {
        if (simulationFile->isOpen())
pixhawk's avatar
pixhawk committed
238
        {
pixhawk's avatar
pixhawk committed
239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256
            if (simulationFile->atEnd())
            {
                // 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);
257 258
	    // FIXME Remove multiplicaton by 1000
	    time *= 1000;
pixhawk's avatar
pixhawk committed
259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305

            if (ok)
            {
                if (timeOffset == 0)
                {
                    timeOffset = time;
                    baseTime = time;
                }

                if (lastTime > time)
                {
                    // 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
                for (int i = 1; i < (parts.size() - 1); ++i)
                {
                    // Get one data field
                    bool res;
                    double d = QString(parts.at(i)).toDouble(&res);
                    if (!res) d = 0;

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

                    if (keys.value(i, "") == "Accel._X")
                    {
                        rawImuValues.xacc = d;
                    }

                    if (keys.value(i, "") == "Accel._Y")
                    {
                        rawImuValues.yacc = d;
                    }

                    if (keys.value(i, "") == "Accel._Z")
                    {
                        rawImuValues.zacc = d;
                    }
                    if (keys.value(i, "") == "Gyro_Phi")
                    {
                        rawImuValues.xgyro = d;
306
                        attitude.rollspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
307 308 309 310 311
                    }

                    if (keys.value(i, "") == "Gyro_Theta")
                    {
                        rawImuValues.ygyro = d;
312
                        attitude.pitchspeed = ((d-29.000)/15000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
313 314 315 316 317
                    }

                    if (keys.value(i, "") == "Gyro_Psi")
                    {
                        rawImuValues.zgyro = d;
318
                        attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
319
                    }
lm's avatar
lm committed
320
#ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
321 322 323 324 325 326 327 328 329
                    if (keys.value(i, "") == "Pressure")
                    {
                        rawAuxValues.baro = d;
                    }

                    if (keys.value(i, "") == "Battery")
                    {
                        rawAuxValues.vbat = d;
                    }
330
#endif
pixhawk's avatar
pixhawk committed
331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352
                    if (keys.value(i, "") == "roll_IMU")
                    {
                        attitude.roll = d;
                    }

                    if (keys.value(i, "") == "pitch_IMU")
                    {
                        attitude.pitch = d;
                    }

                    if (keys.value(i, "") == "yaw_IMU")
                    {
                        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
353
                attitude.usec = time;
pixhawk's avatar
pixhawk committed
354
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
355
                mavlink_msg_attitude_encode(systemId, componentId, &msg, &attitude);
pixhawk's avatar
pixhawk committed
356
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
357
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
358 359 360 361 362
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

                // IMU
363
                rawImuValues.usec = time;
pixhawk's avatar
pixhawk committed
364 365 366 367
                rawImuValues.xmag = 0;
                rawImuValues.ymag = 0;
                rawImuValues.zmag = 0;
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
368
                mavlink_msg_raw_imu_encode(systemId, componentId, &msg, &rawImuValues);
pixhawk's avatar
pixhawk committed
369
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
370
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
371 372 373 374 375 376 377 378 379 380
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

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

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

            }

pixhawk's avatar
pixhawk committed
381
        }
pixhawk's avatar
pixhawk committed
382 383 384 385 386 387 388 389 390

        rate50hzCounter = 1;
    }


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

392 393 394 395
        float lastX = x;
        float lastY = y;
        float lastZ = z;
        float hackDt = 0.1f; // 100 ms
396

pixhawk's avatar
pixhawk committed
397
        // Move X Position
398 399 400
        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);
401

402 403 404 405
        float xSpeed = (x - lastX)/hackDt;
        float ySpeed = (y - lastY)/hackDt;
        float zSpeed = (z - lastZ)/hackDt;

406 407


408 409
        circleCounter++;

410

411 412 413
//        x = (x > 5.0f) ? 5.0f : x;
//        y = (y > 5.0f) ? 5.0f : y;
//        z = (z > 3.0f) ? 3.0f : z;
414

415 416 417
//        x = (x < -5.0f) ? -5.0f : x;
//        y = (y < -5.0f) ? -5.0f : y;
//        z = (z < -3.0f) ? -3.0f : z;
418

pixhawk's avatar
pixhawk committed
419 420 421
        // Send back new setpoint
        mavlink_message_t ret;
        mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ, spYaw);
422 423 424 425 426 427
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        // Send back new position
428
        mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
429
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
pixhawk's avatar
pixhawk committed
430 431 432
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
433

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

pixhawk's avatar
pixhawk committed
441
        // GLOBAL POSITION
442
        mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed, ySpeed, zSpeed);
pixhawk's avatar
pixhawk committed
443 444 445 446 447
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

448
        // GLOBAL POSITION VEHICLE 2
449
        mavlink_msg_global_position_int_pack(54, componentId, &ret, (473780.28137103+(x+0.002))*1E3, (85489.9892510421+((y/2)+0.3))*1E3, (z+570.0)*1000.0, xSpeed, ySpeed, zSpeed);
450 451 452 453 454
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

455 456 457 458 459 460
//        // GLOBAL POSITION VEHICLE 3
//        mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
461

462 463 464
        static int rcCounter = 0;
        if (rcCounter == 2)
        {
465
            mavlink_rc_channels_raw_t chan;
466 467 468 469 470 471 472
            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;
473
            chan.chan8_raw = 0;
pixhawk's avatar
pixhawk committed
474
            chan.rssi = 100;
475
            messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
476 477 478 479 480 481 482 483 484
            // 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
485 486 487 488 489
    }

    // 1 HZ TASKS
    if (rate1hzCounter == 1000 / rate / 1)
    {
pixhawk's avatar
pixhawk committed
490 491 492 493 494 495 496 497 498
        // STATE
        static int statusCounter = 0;
        if (statusCounter == 100)
        {
            status.mode = (status.mode + 1) % MAV_MODE_TEST3;
            statusCounter = 0;
        }
        statusCounter++;

499 500 501
        static int detectionCounter = 6;
        if (detectionCounter % 10 == 0)
        {
lm's avatar
lm committed
502
#ifdef MAVLINK_ENABLED_PIXHAWK
503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554
            mavlink_pattern_detected_t detected;
            detected.confidence = 5.0f;

            if (detectionCounter == 10)
            {
                char fileName[] = "patterns/face5.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
            }
            else if (detectionCounter == 20)
            {
                char fileName[] = "7";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
            }
            else if (detectionCounter == 30)
            {
                char fileName[] = "patterns/einstein.bmp";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
            }
            else if (detectionCounter == 40)
            {
                char fileName[] = "F";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 1; // 0: Pattern, 1: Letter
            }
            else if (detectionCounter == 50)
            {
                char fileName[] = "patterns/face2.png";
                memcpy(detected.file, fileName, sizeof(fileName));
                detected.type = 0; // 0: Pattern, 1: Letter
            }
            else if (detectionCounter == 60)
            {
                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++;

555
        status.vbat = voltage * 1000; // millivolts
556
        status.load = 33 * detectionCounter % 1000;
pixhawk's avatar
pixhawk committed
557 558

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
559
        messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
560
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
561
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
562 563 564 565
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

566
        // Pack debug text message
pixhawk's avatar
pixhawk committed
567
        mavlink_statustext_t text;
568
        text.severity = 0;
569
        strcpy((char*)(text.text), "Text message from system 32");
pixhawk's avatar
pixhawk committed
570 571
        mavlink_msg_statustext_encode(systemId, componentId, &msg, &text);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
572 573 574
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
575 576
        /*
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
577
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
578
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
579
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
580 581 582 583
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;*/

pixhawk's avatar
pixhawk committed
584 585
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
586
        static int typeCounter = 0;
587 588 589 590 591 592 593 594 595
        uint8_t mavType;
        if (typeCounter < 10)
        {
            mavType = MAV_QUADROTOR;
        }
        else
        {
            mavType = typeCounter % (OCU);
        }
pixhawk's avatar
pixhawk committed
596 597
        typeCounter++;

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

pixhawk's avatar
pixhawk committed
606

pixhawk's avatar
pixhawk committed
607 608 609
        // Send controller states


lm's avatar
lm committed
610
        #ifdef MAVLINK_ENABLED_PIXHAWK
pixhawk's avatar
pixhawk committed
611 612 613 614 615 616 617 618
                uint8_t attControl = 1;
                uint8_t posXYControl = 1;
                uint8_t posZControl = 0;
                uint8_t posYawControl = 1;

                uint8_t gpsLock = 2;
                uint8_t visLock = 3;
                uint8_t posLock = qMax(gpsLock, visLock);
pixhawk's avatar
pixhawk committed
619
        messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
620 621
        #endif

pixhawk's avatar
pixhawk committed
622 623 624 625 626
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;


627

pixhawk's avatar
pixhawk committed
628 629 630
        // HEARTBEAT VEHICLE 2

        // Pack message and get size of encoded byte string
631
        messageSize = mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA);
pixhawk's avatar
pixhawk committed
632
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
633
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
634 635 636 637
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

638
//        // HEARTBEAT VEHICLE 3
639

640 641 642 643 644 645 646
//        // 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;
647

pixhawk's avatar
pixhawk committed
648
        // STATUS VEHICLE 2
649
        mavlink_sys_status_t status2;
pixhawk's avatar
pixhawk committed
650 651
        status2.mode = MAV_MODE_LOCKED;
        status2.vbat = voltage;
652
        status2.load = 120;
pixhawk's avatar
pixhawk committed
653 654 655
        status2.status = MAV_STATE_STANDBY;

        // Pack message and get size of encoded byte string
656
        messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
657
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
658
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
659 660 661
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
pixhawk's avatar
pixhawk committed
662

pixhawk's avatar
pixhawk committed
663
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
664 665 666 667 668
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
669
    /*
pixhawk's avatar
pixhawk committed
670 671 672 673
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
674
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
675 676 677 678

        // Attitude

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
679
        messageSize = mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
pixhawk's avatar
pixhawk committed
680
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
681
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
682 683 684 685 686
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
687
    }*/
pixhawk's avatar
pixhawk committed
688 689

    readyBufferMutex.lock();
690
    for (unsigned int i = 0; i < streampointer; i++)
pixhawk's avatar
pixhawk committed
691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712
    {
        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)
{
713
    //qDebug() << "Simulation received " << size << " bytes from groundstation: ";
pixhawk's avatar
pixhawk committed
714 715 716 717

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

pixhawk's avatar
pixhawk committed
718 719
    // Parse bytes
    mavlink_message_t msg;
lm's avatar
lm committed
720
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
721

722 723 724 725 726
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;

pixhawk's avatar
pixhawk committed
727 728 729 730
    // Output all bytes as hex digits
    int i;
    for (i=0; i<size; i++)
    {
pixhawk's avatar
pixhawk committed
731 732 733
        if (mavlink_parse_char(this->id, data[i], &msg, &comm))
        {
            // MESSAGE RECEIVED!
734 735
            qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
            emit messageReceived(msg);
pixhawk's avatar
pixhawk committed
736 737 738 739 740 741

            switch (msg.msgid)
            {
                // SET THE SYSTEM MODE
            case MAVLINK_MSG_ID_SET_MODE:
                {
pixhawk's avatar
pixhawk committed
742 743
                    mavlink_set_mode_t mode;
                    mavlink_msg_set_mode_decode(&msg, &mode);
pixhawk's avatar
pixhawk committed
744 745 746
                    // Set mode indepent of mode.target
                    status.mode = mode.mode;
                }
pixhawk's avatar
pixhawk committed
747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765
                break;
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
                {
                    mavlink_local_position_setpoint_set_t set;
                    mavlink_msg_local_position_setpoint_set_decode(&msg, &set);
                    spX = set.x;
                    spY = set.y;
                    spZ = set.z;
                    spYaw = set.yaw;

                    // Send back new setpoint
                    mavlink_message_t ret;
                    mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ, spYaw);
                    bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                    //add data into datastream
                    memcpy(stream+streampointer,buffer, bufferlength);
                    streampointer += bufferlength;
                }
                break;
pixhawk's avatar
pixhawk committed
766 767 768
                // EXECUTE OPERATOR ACTIONS
            case MAVLINK_MSG_ID_ACTION:
                {
pixhawk's avatar
pixhawk committed
769 770
                    mavlink_action_t action;
                    mavlink_msg_action_decode(&msg, &action);
pixhawk's avatar
pixhawk committed
771 772 773

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

pixhawk's avatar
pixhawk committed
774 775
                    switch (action.action)
                    {
776
                    case MAV_ACTION_LAUNCH:
pixhawk's avatar
pixhawk committed
777 778 779
                        status.status = MAV_STATE_ACTIVE;
                        status.mode = MAV_MODE_AUTO;
                        break;
780
                    case MAV_ACTION_RETURN:
lm's avatar
lm committed
781
                        status.status = MAV_STATE_ACTIVE;
pixhawk's avatar
pixhawk committed
782
                        break;
783
                    case MAV_ACTION_MOTORS_START:
pixhawk's avatar
pixhawk committed
784 785 786
                        status.status = MAV_STATE_ACTIVE;
                        status.mode = MAV_MODE_LOCKED;
                        break;
787
                    case MAV_ACTION_MOTORS_STOP:
pixhawk's avatar
pixhawk committed
788 789 790
                        status.status = MAV_STATE_STANDBY;
                        status.mode = MAV_MODE_LOCKED;
                        break;
791
                    case MAV_ACTION_EMCY_KILL:
pixhawk's avatar
pixhawk committed
792 793 794
                        status.status = MAV_STATE_EMERGENCY;
                        status.mode = MAV_MODE_MANUAL;
                        break;
795
                    case MAV_ACTION_SHUTDOWN:
796 797 798
                        status.status = MAV_STATE_POWEROFF;
                        status.mode = MAV_MODE_LOCKED;
                        break;
pixhawk's avatar
pixhawk committed
799 800 801
                    }
                }
                break;
lm's avatar
lm committed
802
#ifdef MAVLINK_ENABLED_PIXHAWK
803 804
            case MAVLINK_MSG_ID_MANUAL_CONTROL:
                {
pixhawk's avatar
pixhawk committed
805 806
                    mavlink_manual_control_t control;
                    mavlink_msg_manual_control_decode(&msg, &control);
807 808 809
                    qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch;
                }
                break;
810
#endif
811 812
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                {
813
                    qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
pixhawk's avatar
pixhawk committed
814 815 816 817 818
                    mavlink_param_request_list_t read;
                    mavlink_msg_param_request_list_decode(&msg, &read);
                    if (read.target_system == systemId)
                    {
                        // Output all params
lm's avatar
lm committed
819 820 821
                        // Iterate through all components, through all parameters and emit them
                        QMap<QString, float>::iterator i;
                        // Iterate through all components / subsystems
lm's avatar
lm committed
822
                        int j = 0;
lm's avatar
lm committed
823 824 825
                        for (i = onboardParams.begin(); i != onboardParams.end(); ++i)
                        {
                            // Pack message and get size of encoded byte string
lm's avatar
lm committed
826
                            mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)i.key().toStdString().c_str(), i.value(), onboardParams.size(), j);
lm's avatar
lm committed
827 828 829 830 831
                            // Allocate buffer with packet data
                            bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                            //add data into datastream
                            memcpy(stream+streampointer,buffer, bufferlength);
                            streampointer+=bufferlength;
lm's avatar
lm committed
832
                            j++;
lm's avatar
lm committed
833 834
                        }

835
                        qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
pixhawk's avatar
pixhawk committed
836
                    }
837
                }
lm's avatar
lm committed
838 839 840 841 842 843 844 845 846 847 848 849 850
                break;
            case MAVLINK_MSG_ID_PARAM_SET:
                {
                    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);
851 852

                            // Pack message and get size of encoded byte string
lm's avatar
lm committed
853
                            mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value, onboardParams.size(), 0);
854 855 856 857 858
                            // Allocate buffer with packet data
                            bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                            //add data into datastream
                            memcpy(stream+streampointer,buffer, bufferlength);
                            streampointer+=bufferlength;
lm's avatar
lm committed
859 860 861 862
                        }
                    }
                }
                break;
pixhawk's avatar
pixhawk committed
863 864 865 866
            }


        }
867
        //unsigned char v=data[i];
868
        //fprintf(stderr,"%02x ", v);
pixhawk's avatar
pixhawk committed
869
    }
870
    //fprintf(stderr,"\n");
pixhawk's avatar
pixhawk committed
871

872 873 874 875 876 877 878
    readyBufferMutex.lock();
    for (int i = 0; i < streampointer; i++)
    {
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
879 880 881
    // Update comm status
    status.packet_drop = comm.packet_rx_drop_count;

pixhawk's avatar
pixhawk committed
882 883 884
}


885
void MAVLinkSimulationLink::readBytes() {
pixhawk's avatar
pixhawk committed
886 887
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
888 889
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934
    qint64 len = maxLength;
    if (maxLength > readyBuffer.size()) len = readyBuffer.size();

    for (unsigned int i = 0; i < len; i++)
    {
        *(data + i) = readyBuffer.takeFirst();
    }

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

    readyBufferMutex.unlock();

    //    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");
    //    }
}

/**
 * Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection
 * couldn't be disconnected.
 **/
bool MAVLinkSimulationLink::disconnect() {

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

        _isConnected = false;

        emit disconnected();
935
        emit connected(false);
pixhawk's avatar
pixhawk committed
936

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

    return true;
}

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

    start(LowPriority);
956
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1);
957
    Q_UNUSED(mav1);
pixhawk's avatar
pixhawk committed
958 959 960 961
    //    timer->start(rate);
    return true;
}

962 963 964 965 966 967 968 969 970 971 972 973
/**
 * 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();
}

974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992
/**
 * 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;

    if(connect)
    {
        this->connect();
    }

    return true;
}

pixhawk's avatar
pixhawk committed
993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067
/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
bool MAVLinkSimulationLink::isConnected() {
    return _isConnected;
}

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

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

qint64 MAVLinkSimulationLink::getNominalDataRate() {
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
}

qint64 MAVLinkSimulationLink::getTotalUpstream() {
    return 0;
    //TODO Add functionality here
    // @todo Add functionality here
}

qint64 MAVLinkSimulationLink::getShortTermUpstream() {
    return 0;
}

qint64 MAVLinkSimulationLink::getCurrentUpstream() {
    return 0;
}

qint64 MAVLinkSimulationLink::getMaxUpstream() {
    return 0;
}

qint64 MAVLinkSimulationLink::getBitsSent() {
    return 0;
}

qint64 MAVLinkSimulationLink::getBitsReceived() {
    return 0;
}

qint64 MAVLinkSimulationLink::getTotalDownstream() {
    return 0;
}

qint64 MAVLinkSimulationLink::getShortTermDownstream() {
    return 0;
}

qint64 MAVLinkSimulationLink::getCurrentDownstream() {
    return 0;
}

qint64 MAVLinkSimulationLink::getMaxDownstream() {
    return 0;
}

bool MAVLinkSimulationLink::isFullDuplex() {
    /* Full duplex is no problem when running in pure software, but this is a serial simulation */
    return false;
}

int MAVLinkSimulationLink::getLinkQuality() {
    /* The Link quality is always perfect when running in software */
    return 100;
}