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
/**
 * @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)
 **/
58
MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate) :
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);
pixhawk's avatar
pixhawk committed
110 111 112 113 114 115 116
}

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

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

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

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

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

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

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

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

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

    // Test for encoding / decoding packets

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

    // Fake system values

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

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

    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength;
    mavlink_message_t msg;

    // Timers
    static unsigned int rate1hzCounter = 1;
    static unsigned int rate10hzCounter = 1;
    static unsigned int rate50hzCounter = 1;
215
    static unsigned int circleCounter = 0;
pixhawk's avatar
pixhawk committed
216 217 218 219 220 221

    // Vary values

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

pixhawk's avatar
pixhawk committed
224
    static int state = 0;
pixhawk's avatar
pixhawk committed
225

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


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

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

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

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

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

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

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

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

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

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

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

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

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

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

            }

pixhawk's avatar
pixhawk committed
360
        }
pixhawk's avatar
pixhawk committed
361 362 363 364 365 366

        rate50hzCounter = 1;
    }


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

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

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

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

384 385


386 387
        circleCounter++;

388

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

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

pixhawk's avatar
pixhawk committed
397
        mavlink_message_t ret;
398 399

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

406 407 408 409 410 411
//        // 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;
412

pixhawk's avatar
pixhawk committed
413
        // GLOBAL POSITION
lm's avatar
lm committed
414
        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
415 416 417 418 419
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

420 421 422 423 424 425
        // 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;
426

427 428 429
//        // 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
430 431


432
//        // GLOBAL POSITION VEHICLE 3
433
//        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);
434 435 436 437
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
438

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

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

475
        static int detectionCounter = 6;
476
        if (detectionCounter % 10 == 0) {
lm's avatar
lm committed
477
#ifdef MAVLINK_ENABLED_PIXHAWK
478 479
            mavlink_pattern_detected_t detected;
            detected.confidence = 5.0f;
480
            detected.type = 0;  // compiler confused into thinking type is used unitialized, bogus init to silence
481

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

520
        status.voltage_battery = voltage * 1000; // millivolts
521
        status.load = 33 * detectionCounter % 1000;
pixhawk's avatar
pixhawk committed
522 523

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

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

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

pixhawk's avatar
pixhawk committed
549 550
        // HEARTBEAT

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

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

572
        // Pack message and get size of encoded byte string
573
        mavlink_msg_heartbeat_pack(systemId+1, componentId+1, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status);
574 575 576 577 578 579 580
        // 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
581

pixhawk's avatar
pixhawk committed
582 583 584 585 586 587 588
        // Send controller states

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


589

590
//        // HEARTBEAT VEHICLE 2
pixhawk's avatar
pixhawk committed
591

592
//        // Pack message and get size of encoded byte string
593
//        mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA);
594 595 596 597 598
//        // 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
599

600
//        // HEARTBEAT VEHICLE 3
601

602
//        // Pack message and get size of encoded byte string
603
//        mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
604 605 606 607 608
//        // Allocate buffer with packet data
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
609

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

pixhawk's avatar
pixhawk committed
618
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
619 620 621 622 623
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
624
    /*
pixhawk's avatar
pixhawk committed
625 626 627 628
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
629
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
630 631 632 633

        // Attitude

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

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
642
    }*/
pixhawk's avatar
pixhawk committed
643 644

    readyBufferMutex.lock();
645
    for (unsigned int i = 0; i < streampointer; i++) {
pixhawk's avatar
pixhawk committed
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666
        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
667 668
    // Parse bytes
    mavlink_message_t msg;
669
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
670

671 672 673 674
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;
675 676 677
    
    // Initialize drop count to 0 so it isn't referenced uninitialized when returned at the bottom of this function
    comm.packet_rx_drop_count = 0;
678

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

LM's avatar
LM committed
688 689
            switch (msg.msgid)
            {
pixhawk's avatar
pixhawk committed
690
                // SET THE SYSTEM MODE
LM's avatar
LM committed
691 692
            case MAVLINK_MSG_ID_SET_MODE:
            {
693 694 695
                mavlink_set_mode_t mode;
                mavlink_msg_set_mode_decode(&msg, &mode);
                // Set mode indepent of mode.target
696
                system.base_mode = mode.base_mode;
697 698 699
            }
            break;
            // EXECUTE OPERATOR ACTIONS
LM's avatar
LM committed
700 701
            case MAVLINK_MSG_ID_COMMAND_LONG:
            {
pixhawk's avatar
pixhawk committed
702 703
                mavlink_command_long_t action;
                mavlink_msg_command_long_decode(&msg, &action);
704

705
//                qDebug() << "SIM" << "received action" << action.command << "for system" << action.target_system;
706

lm's avatar
lm committed
707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732
                // 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;
//                }
733 734
            }
            break;
lm's avatar
lm committed
735
#ifdef MAVLINK_ENABLED_PIXHAWK
736 737 738
            case MAVLINK_MSG_ID_MANUAL_CONTROL: {
                mavlink_manual_control_t control;
                mavlink_msg_manual_control_decode(&msg, &control);
739
//                qDebug() << "\n" << "ROLL:" << control.x << "PITCH:" << control.y;
740 741
            }
            break;
742
#endif
LM's avatar
LM committed
743 744
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            {
745
//                qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
746 747
                mavlink_param_request_list_t read;
                mavlink_msg_param_request_list_decode(&msg, &read);
LM's avatar
LM committed
748 749 750 751 752 753 754 755 756 757
                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
758
                            mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), MAV_PARAM_TYPE_REAL32, onboardParams.size(), j);
LM's avatar
LM committed
759 760 761 762 763 764 765
                            // 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++;
766
                    }
767

768
//                    qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
LM's avatar
LM committed
769
                }
770
            }
LM's avatar
LM committed
771 772 773
                break;
            case MAVLINK_MSG_ID_PARAM_SET:
            {
774
                // Drop on even milliseconds
LM's avatar
LM committed
775 776
                if (QGC::groundTimeMilliseconds() % 2 == 0)
                {
777
//                    qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER";
778 779 780 781 782
                    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
783 784
                    if (onboardParams.contains(key))
                    {
785 786
                        onboardParams.remove(key);
                        onboardParams.insert(key, set.param_value);
787 788

                        // Pack message and get size of encoded byte string
789
                        mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, MAV_PARAM_TYPE_REAL32, onboardParams.size(), onboardParams.keys().indexOf(key));
790 791 792 793 794 795
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
796 797 798 799
                    //                    }
                }
            }
            break;
LM's avatar
LM committed
800 801
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            {
802
//                qDebug() << "SIMULATION RECEIVED COMMAND TO SEND PARAMETER";
803 804 805 806
                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
807 808
                if (onboardParams.contains(key))
                {
809 810 811
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
812
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAV_PARAM_TYPE_REAL32, onboardParams.size(), onboardParams.keys().indexOf(key));
813 814 815 816 817 818
                    // 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
819
                }
820
                else if (read.param_index >= 0 && read.param_index < onboardParams.keys().size())
LM's avatar
LM committed
821
                {
822 823 824 825
                    key = onboardParams.keys().at(read.param_index);
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
826
                    mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAV_PARAM_TYPE_REAL32, onboardParams.size(), onboardParams.keys().indexOf(key));
827 828 829 830 831 832
                    // 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;
833
                }
834 835
            }
            break;
pixhawk's avatar
pixhawk committed
836 837
            }
        }
pixhawk's avatar
pixhawk committed
838
    }
pixhawk's avatar
pixhawk committed
839

840 841 842 843 844 845
    // Log the amount and time written out for future data rate calculations.
    // While this interface doesn't actually write any data to external systems,
    // this data "transmit" here should still count towards the outgoing data rate.
    QMutexLocker dataRateLocker(&dataRateMutex);
    logDataRateToBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, size, QDateTime::currentMSecsSinceEpoch());

846
    readyBufferMutex.lock();
LM's avatar
LM committed
847 848
    for (int i = 0; i < streampointer; i++)
    {
849 850 851 852
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
853
    // Update comm status
854
    status.errors_comm = comm.packet_rx_drop_count;
pixhawk's avatar
pixhawk committed
855

pixhawk's avatar
pixhawk committed
856 857 858
}


859 860
void MAVLinkSimulationLink::readBytes()
{
pixhawk's avatar
pixhawk committed
861 862
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
863 864
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
865
    qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
pixhawk's avatar
pixhawk committed
866

867
    for (unsigned int i = 0; i < len; i++) {
pixhawk's avatar
pixhawk committed
868 869 870 871 872 873 874
        *(data + i) = readyBuffer.takeFirst();
    }

    QByteArray b(data, len);
    emit bytesReceived(this, b);
    readyBufferMutex.unlock();

875 876 877 878
    // Log the amount and time received for future data rate calculations.
    QMutexLocker dataRateLocker(&dataRateMutex);
    logDataRateToBuffer(inDataWriteAmounts, inDataWriteTimes, &inDataIndex, len, QDateTime::currentMSecsSinceEpoch());

pixhawk's avatar
pixhawk committed
879 880 881 882 883 884 885 886
}

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

Lorenz Meier's avatar
Lorenz Meier committed
890 891
    if(isConnected())
    {
pixhawk's avatar
pixhawk committed
892 893 894 895 896
        //        timer->stop();

        _isConnected = false;

        emit disconnected();
897
        emit connected(false);
pixhawk's avatar
pixhawk committed
898

899
        //exit();
pixhawk's avatar
pixhawk committed
900 901 902 903 904 905 906 907 908 909 910 911 912 913
    }

    return true;
}

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

    start(LowPriority);
LM's avatar
LM committed
918
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 37.480391, -122.282883);
919
    Q_UNUSED(mav1);
920 921
//    MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
//    Q_UNUSED(mav2);
pixhawk's avatar
pixhawk committed
922 923 924 925
    //    timer->start(rate);
    return true;
}

926 927 928 929 930 931 932 933 934 935 936 937
/**
 * 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();
}

938 939 940 941 942 943 944 945 946 947 948
/**
 * 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;

949
    if(connect) {
950 951 952 953 954 955
        this->connect();
    }

    return true;
}

pixhawk's avatar
pixhawk committed
956 957 958 959 960
/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
961
bool MAVLinkSimulationLink::isConnected() const
962
{
pixhawk's avatar
pixhawk committed
963 964 965
    return _isConnected;
}

966
int MAVLinkSimulationLink::getId() const
pixhawk's avatar
pixhawk committed
967 968 969 970
{
    return id;
}

971
QString MAVLinkSimulationLink::getName() const
pixhawk's avatar
pixhawk committed
972 973 974 975
{
    return name;
}

976
qint64 MAVLinkSimulationLink::getConnectionSpeed() const
977
{
pixhawk's avatar
pixhawk committed
978 979
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
980 981 982 983 984 985 986 987 988 989 990
}

qint64 MAVLinkSimulationLink::getCurrentInDataRate() const
{
    return 0;
}

qint64 MAVLinkSimulationLink::getCurrentOutDataRate() const
{
    return 0;
}