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

pixhawk's avatar
pixhawk committed
3
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
pixhawk's avatar
pixhawk committed
4

pixhawk's avatar
pixhawk committed
5
(c) 2009, 2010 PIXHAWK PROJECT  <http://pixhawk.ethz.ch>
pixhawk's avatar
pixhawk committed
6

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

pixhawk's avatar
pixhawk committed
9 10 11 12
    PIXHAWK is free software: you can redistribute it and/or modify
    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

pixhawk's avatar
pixhawk committed
14 15 16 17
    PIXHAWK is distributed in the hope that it will be useful,
    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 20
    You should have received a copy of the GNU General Public License
    along with PIXHAWK. 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 43 44
#include "MAVLinkSimulationLink.h"
// MAVLINK includes
#include <mavlink.h>
pixhawk's avatar
pixhawk committed
45
#include "QGC.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 59 60
MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate) :
        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";
    }

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

    // Open packet log
    mavlinkLogFile = new QFile(MAVLinkProtocol::getLogfileName());
    mavlinkLogFile->open(QIODevice::ReadOnly);
pixhawk's avatar
pixhawk committed
102 103 104 105 106

    x = 0;
    y = 0;
    z = 0;
    yaw = 0;
pixhawk's avatar
pixhawk committed
107 108 109 110 111 112 113
}

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

void MAVLinkSimulationLink::run()
{
pixhawk's avatar
pixhawk committed
119 120 121 122 123 124 125

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

pixhawk's avatar
pixhawk committed
126 127 128 129 130 131 132 133 134 135
    forever
    {

        static quint64 last = 0;

        if (MG::TIME::getGroundTimeNow() - last >= rate)
        {
            if (_isConnected)
            {
                mainloop();
136 137 138 139 140 141 142 143 144 145 146 147 148 149 150

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







pixhawk's avatar
pixhawk committed
151 152 153 154
                emit bytesReady(this);
            }
            last = MG::TIME::getGroundTimeNow();
        }
155
        MG::SLEEP::msleep(2);
pixhawk's avatar
pixhawk committed
156 157 158 159

    }
}

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

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

    // Test for encoding / decoding packets

    // Test data stream
pixhawk's avatar
pixhawk committed
176
    const int streamlength = 4096;
pixhawk's avatar
pixhawk committed
177 178
    int streampointer = 0;
    //const int testoffset = 0;
pixhawk's avatar
pixhawk committed
179
    uint8_t stream[streamlength] = {};
pixhawk's avatar
pixhawk committed
180 181 182 183 184 185

    // Fake system values

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

pixhawk's avatar
pixhawk committed
188 189 190
    mavlink_attitude_t attitude;
    mavlink_raw_aux_t rawAuxValues;
    mavlink_raw_imu_t rawImuValues;
pixhawk's avatar
pixhawk committed
191 192 193 194 195 196 197 198 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;

    // 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
209
    static int state = 0;
pixhawk's avatar
pixhawk committed
210

pixhawk's avatar
pixhawk committed
211
    if (state == 0)
pixhawk's avatar
pixhawk committed
212
    {
pixhawk's avatar
pixhawk committed
213 214
        // BOOT
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
215
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
216
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
217
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
218 219 220 221 222 223 224 225 226 227 228
        //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
229
        {
pixhawk's avatar
pixhawk committed
230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247
            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);
248 249
	    // FIXME Remove multiplicaton by 1000
	    time *= 1000;
pixhawk's avatar
pixhawk committed
250 251 252 253 254 255 256 257 258 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 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340

            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;
                    }

                    if (keys.value(i, "") == "Gyro_Theta")
                    {
                        rawImuValues.ygyro = d;
                    }

                    if (keys.value(i, "") == "Gyro_Psi")
                    {
                        rawImuValues.zgyro = d;
                    }

                    if (keys.value(i, "") == "Pressure")
                    {
                        rawAuxValues.baro = d;
                    }

                    if (keys.value(i, "") == "Battery")
                    {
                        rawAuxValues.vbat = d;
                    }

                    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
341
                attitude.usec = time;
pixhawk's avatar
pixhawk committed
342
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
343
                mavlink_msg_attitude_encode(systemId, componentId, &msg, &attitude);
pixhawk's avatar
pixhawk committed
344
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
345
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
346 347 348 349 350
                //add data into datastream
                memcpy(stream+streampointer,buffer, bufferlength);
                streampointer += bufferlength;

                // IMU
351
                rawImuValues.usec = time;
pixhawk's avatar
pixhawk committed
352 353 354 355
                rawImuValues.xmag = 0;
                rawImuValues.ymag = 0;
                rawImuValues.zmag = 0;
                // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
356
                mavlink_msg_raw_imu_encode(systemId, componentId, &msg, &rawImuValues);
pixhawk's avatar
pixhawk committed
357
                // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
358
                bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
359 360 361 362 363 364 365 366 367 368
                //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
369
        }
pixhawk's avatar
pixhawk committed
370 371 372 373 374 375 376 377 378

        rate50hzCounter = 1;
    }


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

        // Move X Position
pixhawk's avatar
pixhawk committed
381 382 383 384 385 386 387 388 389 390 391 392 393 394
        x += sin(QGC::groundTimeUsecs()) * 0.1f;
        y += sin(QGC::groundTimeUsecs()) * 0.1f;
        z += sin(QGC::groundTimeUsecs()) * 0.1f;

        x = (x > 1.0f) ? 1.0f : x;
        y = (y > 1.0f) ? 1.0f : y;
        z = (z > 1.0f) ? 1.0f : z;
        // 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;
pixhawk's avatar
pixhawk committed
395 396 397 398 399
    }

    // 1 HZ TASKS
    if (rate1hzCounter == 1000 / rate / 1)
    {
pixhawk's avatar
pixhawk committed
400 401 402 403 404 405 406 407 408
        // STATE
        static int statusCounter = 0;
        if (statusCounter == 100)
        {
            status.mode = (status.mode + 1) % MAV_MODE_TEST3;
            statusCounter = 0;
        }
        statusCounter++;

409
        status.vbat = voltage * 1000; // millivolts
pixhawk's avatar
pixhawk committed
410 411

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
412
        messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
413
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
414
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
415 416 417 418
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

419
        // Pack debug text message
pixhawk's avatar
pixhawk committed
420
        mavlink_statustext_t text;
421 422
        text.severity = 0;
        strcpy((char*)(text.text), "DEBUG MESSAGE TEXT");
pixhawk's avatar
pixhawk committed
423 424
        mavlink_msg_statustext_encode(systemId, componentId, &msg, &text);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
425 426 427
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
428 429
        /*
        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
430
        messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
431
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
432
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
433 434 435 436
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;*/

pixhawk's avatar
pixhawk committed
437 438
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
439 440 441 442
        static int typeCounter = 0;
        uint8_t mavType = typeCounter % (OCU);
        typeCounter++;

pixhawk's avatar
pixhawk committed
443
        // Pack message and get size of encoded byte string
444
        messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK);
pixhawk's avatar
pixhawk committed
445
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
446
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
447 448 449 450
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
451

pixhawk's avatar
pixhawk committed
452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467
        // Send controller states
        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);

        messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;


pixhawk's avatar
pixhawk committed
468 469 470 471
        /*
        // HEARTBEAT VEHICLE 2

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
472
        messageSize = mavlink_msg_heartbeat_pack(42, componentId, &msg, MAV_FIXED_WING);
pixhawk's avatar
pixhawk committed
473
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
474
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
475 476 477 478 479 480 481 482 483 484 485
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        // STATUS VEHICLE 2
        sys_status_t status2;
        status2.mode = MAV_MODE_LOCKED;
        status2.vbat = voltage;
        status2.status = MAV_STATE_STANDBY;

        // Pack message and get size of encoded byte string
pixhawk's avatar
pixhawk committed
486
        messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
487
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
488
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
489 490 491 492
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
        */
pixhawk's avatar
pixhawk committed
493
        //qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer;
pixhawk's avatar
pixhawk committed
494

pixhawk's avatar
pixhawk committed
495 496
        // AUX STATUS
        rawAuxValues.vbat = voltage;
pixhawk's avatar
pixhawk committed
497

pixhawk's avatar
pixhawk committed
498
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
499 500 501 502 503
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
504
    /*
pixhawk's avatar
pixhawk committed
505 506 507 508
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
509
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
510 511 512 513

        // Attitude

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

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
522
    }*/
pixhawk's avatar
pixhawk committed
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

    readyBufferMutex.lock();
    for (int i = 0; i < streampointer; i++)
    {
        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)
{
    qDebug() << "Simulation received " << size << " bytes from groundstation: ";

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

pixhawk's avatar
pixhawk committed
553 554
    // Parse bytes
    mavlink_message_t msg;
lm's avatar
lm committed
555
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
556

557 558 559 560 561
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;

pixhawk's avatar
pixhawk committed
562 563 564 565
    // Output all bytes as hex digits
    int i;
    for (i=0; i<size; i++)
    {
pixhawk's avatar
pixhawk committed
566 567 568 569 570 571 572 573 574
        if (mavlink_parse_char(this->id, data[i], &msg, &comm))
        {
            // MESSAGE RECEIVED!

            switch (msg.msgid)
            {
                // SET THE SYSTEM MODE
            case MAVLINK_MSG_ID_SET_MODE:
                {
pixhawk's avatar
pixhawk committed
575 576
                    mavlink_set_mode_t mode;
                    mavlink_msg_set_mode_decode(&msg, &mode);
pixhawk's avatar
pixhawk committed
577 578 579
                    // Set mode indepent of mode.target
                    status.mode = mode.mode;
                }
pixhawk's avatar
pixhawk committed
580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598
                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
599 600 601
                // EXECUTE OPERATOR ACTIONS
            case MAVLINK_MSG_ID_ACTION:
                {
pixhawk's avatar
pixhawk committed
602 603
                    mavlink_action_t action;
                    mavlink_msg_action_decode(&msg, &action);
pixhawk's avatar
pixhawk committed
604 605 606

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

pixhawk's avatar
pixhawk committed
607 608
                    switch (action.action)
                    {
609
                    case MAV_ACTION_LAUNCH:
pixhawk's avatar
pixhawk committed
610 611 612
                        status.status = MAV_STATE_ACTIVE;
                        status.mode = MAV_MODE_AUTO;
                        break;
613
                    case MAV_ACTION_RETURN:
lm's avatar
lm committed
614
                        status.status = MAV_STATE_ACTIVE;
pixhawk's avatar
pixhawk committed
615
                        break;
616
                    case MAV_ACTION_MOTORS_START:
pixhawk's avatar
pixhawk committed
617 618 619
                        status.status = MAV_STATE_ACTIVE;
                        status.mode = MAV_MODE_LOCKED;
                        break;
620
                    case MAV_ACTION_MOTORS_STOP:
pixhawk's avatar
pixhawk committed
621 622 623
                        status.status = MAV_STATE_STANDBY;
                        status.mode = MAV_MODE_LOCKED;
                        break;
624
                    case MAV_ACTION_EMCY_KILL:
pixhawk's avatar
pixhawk committed
625 626 627
                        status.status = MAV_STATE_EMERGENCY;
                        status.mode = MAV_MODE_MANUAL;
                        break;
628
                    case MAV_ACTION_SHUTDOWN:
629 630 631
                        status.status = MAV_STATE_POWEROFF;
                        status.mode = MAV_MODE_LOCKED;
                        break;
pixhawk's avatar
pixhawk committed
632 633 634
                    }
                }
                break;
635 636 637

            case MAVLINK_MSG_ID_MANUAL_CONTROL:
                {
pixhawk's avatar
pixhawk committed
638 639
                    mavlink_manual_control_t control;
                    mavlink_msg_manual_control_decode(&msg, &control);
640 641 642
                    qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch;
                }
                break;
643 644
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                {
645
                    qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
pixhawk's avatar
pixhawk committed
646 647 648 649 650
                    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
651 652 653 654 655 656 657 658 659 660 661 662 663 664 665
                        // Iterate through all components, through all parameters and emit them
                        QMap<QString, float>::iterator i;
                        // Iterate through all components / subsystems
                        for (i = onboardParams.begin(); i != onboardParams.end(); ++i)
                        {
                            // Pack message and get size of encoded byte string
                            mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)i.key().toStdString().c_str(), i.value());
                            // 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
666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687
                        // Pack message and get size of encoded byte string
                        mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)"ROLL_K_P", 0.5f);
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;

                        // Pack message and get size of encoded byte string
                        mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)"PITCH_K_P", 0.6f);
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;

                        // Pack message and get size of encoded byte string
                        mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)"YAW_K_P", 0.8f);
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
lm's avatar
lm committed
688
                        streampointer+=bufferlength;*/
689 690

                        qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
pixhawk's avatar
pixhawk committed
691
                    }
692
                }
lm's avatar
lm committed
693 694 695 696 697 698 699 700 701 702 703 704 705
                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);
706 707 708 709 710 711 712 713

                            // Pack message and get size of encoded byte string
                            mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value);
                            // 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
714 715 716 717
                        }
                    }
                }
                break;
pixhawk's avatar
pixhawk committed
718 719 720 721
            }


        }
pixhawk's avatar
pixhawk committed
722 723 724 725
        unsigned char v=data[i];
        fprintf(stderr,"%02x ", v);
    }
    fprintf(stderr,"\n");
pixhawk's avatar
pixhawk committed
726

727 728 729 730 731 732 733
    readyBufferMutex.lock();
    for (int i = 0; i < streampointer; i++)
    {
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
734 735 736
    // Update comm status
    status.packet_drop = comm.packet_rx_drop_count;

pixhawk's avatar
pixhawk 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 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788
}


void MAVLinkSimulationLink::readBytes(char* const data, qint64 maxLength) {
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
    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();

789
        //exit();
pixhawk's avatar
pixhawk committed
790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809
    }

    return true;
}

/**
 * Connect the link.
 *
 * @return True if connection has been established, false if connection
 * couldn't be established.
 **/
bool MAVLinkSimulationLink::connect()
{
    _isConnected = true;

    start(LowPriority);
    //    timer->start(rate);
    return true;
}

810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828
/**
 * 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
829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903
/**
 * 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;
}