MAVLinkSimulationLink.cc 30.3 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;
108
    LinkManager::instance()->_addLink(this);
pixhawk's avatar
pixhawk committed
109 110 111 112 113 114 115
}

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

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

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

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

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

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

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

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

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

    // Test for encoding / decoding packets

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

    // Fake system values

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

pixhawk's avatar
pixhawk committed
197
    mavlink_attitude_t attitude;
198
    memset(&attitude, 0, sizeof(mavlink_attitude_t));
pixhawk's avatar
pixhawk committed
199
    mavlink_raw_imu_t rawImuValues;
200
    memset(&rawImuValues, 0, sizeof(mavlink_raw_imu_t));
pixhawk's avatar
pixhawk committed
201 202 203 204 205 206 207 208 209

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

    // Vary values

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

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

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


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

252 253
            if (ok) {
                if (timeOffset == 0) {
pixhawk's avatar
pixhawk committed
254 255 256 257
                    timeOffset = time;
                    baseTime = time;
                }

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

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

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

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

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

295
                    if (keys.value(i, "") == "Gyro_Psi") {
pixhawk's avatar
pixhawk committed
296
                        rawImuValues.zgyro = d;
297
                        attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65;
pixhawk's avatar
pixhawk committed
298
                    }
299
                    if (keys.value(i, "") == "roll_IMU") {
pixhawk's avatar
pixhawk committed
300 301 302
                        attitude.roll = d;
                    }

303
                    if (keys.value(i, "") == "pitch_IMU") {
pixhawk's avatar
pixhawk committed
304 305 306
                        attitude.pitch = d;
                    }

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

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

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

342
                //qDebug() << "REALTIME" << QGC::groundTimeMilliseconds() << "ONBOARDTIME" << attitude.msec << "ROLL" << attitude.roll;
pixhawk's avatar
pixhawk committed
343 344 345

            }

pixhawk's avatar
pixhawk committed
346
        }
pixhawk's avatar
pixhawk committed
347 348 349 350 351 352

        rate50hzCounter = 1;
    }


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

356 357 358 359
        double lastX = x;
        double lastY = y;
        double lastZ = z;
        double hackDt = 0.1f; // 100 ms
360

pixhawk's avatar
pixhawk committed
361
        // Move X Position
362 363 364
        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);
365

366 367 368
        double xSpeed = (x - lastX)/hackDt;
        double ySpeed = (y - lastY)/hackDt;
        double zSpeed = (z - lastZ)/hackDt;
369

370 371


372 373
        circleCounter++;

374

375 376 377
//        x = (x > 5.0f) ? 5.0f : x;
//        y = (y > 5.0f) ? 5.0f : y;
//        z = (z > 3.0f) ? 3.0f : z;
378

379 380 381
//        x = (x < -5.0f) ? -5.0f : x;
//        y = (y < -5.0f) ? -5.0f : y;
//        z = (z < -3.0f) ? -3.0f : z;
382

pixhawk's avatar
pixhawk committed
383
        mavlink_message_t ret;
384 385

        // Send back new position
lm's avatar
lm committed
386
        mavlink_msg_local_position_ned_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
387
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
pixhawk's avatar
pixhawk committed
388 389 390
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
391

392 393 394 395 396 397
//        // 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;
398

pixhawk's avatar
pixhawk committed
399
        // GLOBAL POSITION
lm's avatar
lm committed
400
        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
401 402 403 404 405
        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

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

413 414 415
//        // 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
416 417


418
//        // GLOBAL POSITION VEHICLE 3
419
//        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);
420 421 422 423
//        bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//        //add data into datastream
//        memcpy(stream+streampointer,buffer, bufferlength);
//        streampointer += bufferlength;
424

425
        static int rcCounter = 0;
426
        if (rcCounter == 2) {
427
            mavlink_rc_channels_t chan;
lm's avatar
lm committed
428
            chan.time_boot_ms = 0;
429 430 431 432 433 434 435
            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;
436
            chan.chan8_raw = 0;
pixhawk's avatar
pixhawk committed
437
            chan.rssi = 100;
438
            mavlink_msg_rc_channels_encode(systemId, componentId, &msg, &chan);
439 440 441 442 443 444 445 446 447
            // 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
448 449 450
    }

    // 1 HZ TASKS
451
    if (rate1hzCounter == 1000 / rate / 1) {
pixhawk's avatar
pixhawk committed
452 453
        // STATE
        static int statusCounter = 0;
454
        if (statusCounter == 100) {
455
            system.base_mode = (system.base_mode + 1) % MAV_MODE_ENUM_END;
pixhawk's avatar
pixhawk committed
456 457 458 459
            statusCounter = 0;
        }
        statusCounter++;

460
        static int detectionCounter = 6;
461
        if (detectionCounter % 10 == 0) {
462 463 464
        }
        detectionCounter++;

465
        status.voltage_battery = voltage * 1000; // millivolts
466
        status.load = 33 * detectionCounter % 1000;
pixhawk's avatar
pixhawk committed
467 468

        // Pack message and get size of encoded byte string
469
        mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
470
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
471
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
472 473 474 475
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

476
        // Pack debug text message
pixhawk's avatar
pixhawk committed
477
        mavlink_statustext_t text;
478
        text.severity = 0;
479
        strcpy((char*)(text.text), "Text message from system 32");
pixhawk's avatar
pixhawk committed
480 481
        mavlink_msg_statustext_encode(systemId, componentId, &msg, &text);
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
482 483 484
        memcpy(stream+streampointer, buffer, bufferlength);
        streampointer += bufferlength;

pixhawk's avatar
pixhawk committed
485 486
        /*
        // Pack message and get size of encoded byte string
487
        mavlink_msg_boot_pack(systemId, componentId, &msg, version);
pixhawk's avatar
pixhawk committed
488
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
489
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
490 491 492 493
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;*/

pixhawk's avatar
pixhawk committed
494 495
        // HEARTBEAT

pixhawk's avatar
pixhawk committed
496
        static int typeCounter = 0;
497
        uint8_t mavType;
lm's avatar
lm committed
498 499
        if (typeCounter < 10)
        {
lm's avatar
lm committed
500
            mavType = MAV_TYPE_QUADROTOR;
lm's avatar
lm committed
501 502 503 504
        }
        else
        {
            mavType = typeCounter % (MAV_TYPE_GCS);
505
        }
pixhawk's avatar
pixhawk committed
506 507
        typeCounter++;

pixhawk's avatar
pixhawk committed
508
        // Pack message and get size of encoded byte string
509
        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
510
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
511
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
lm's avatar
lm committed
512
        //qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
pixhawk's avatar
pixhawk committed
513 514 515 516
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

517
        // Pack message and get size of encoded byte string
518
        mavlink_msg_heartbeat_pack(systemId+1, componentId+1, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status);
519 520 521 522 523 524 525
        // 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
526

pixhawk's avatar
pixhawk committed
527 528 529 530 531 532
        // Send controller states

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

pixhawk's avatar
pixhawk committed
533
        // Pack message and get size of encoded byte string
534
        mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
pixhawk's avatar
pixhawk committed
535
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
536
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
537 538 539
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;
pixhawk's avatar
pixhawk committed
540

pixhawk's avatar
pixhawk committed
541
        rate1hzCounter = 1;
pixhawk's avatar
pixhawk committed
542 543 544 545 546
    }

    // FULL RATE TASKS
    // Default is 50 Hz

pixhawk's avatar
pixhawk committed
547
    /*
pixhawk's avatar
pixhawk committed
548 549 550 551
    // 50 HZ TASKS
    if (rate50hzCounter == 1000 / rate / 50)
    {

pixhawk's avatar
pixhawk committed
552
        //streampointer = 0;
pixhawk's avatar
pixhawk committed
553 554 555 556

        // Attitude

        // Pack message and get size of encoded byte string
557
        mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
pixhawk's avatar
pixhawk committed
558
        // Allocate buffer with packet data
pixhawk's avatar
pixhawk committed
559
        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
pixhawk's avatar
pixhawk committed
560 561 562 563 564
        //add data into datastream
        memcpy(stream+streampointer,buffer, bufferlength);
        streampointer += bufferlength;

        rate50hzCounter = 1;
pixhawk's avatar
pixhawk committed
565
    }*/
pixhawk's avatar
pixhawk committed
566 567

    readyBufferMutex.lock();
568
    for (unsigned int i = 0; i < streampointer; i++) {
pixhawk's avatar
pixhawk committed
569 570 571 572 573 574 575 576 577 578 579 580 581
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

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


void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
pixhawk's avatar
pixhawk committed
582 583
    // Parse bytes
    mavlink_message_t msg;
584
    mavlink_status_t comm;
pixhawk's avatar
pixhawk committed
585

586 587 588 589
    uint8_t stream[2048];
    int streampointer = 0;
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int bufferlength = 0;
590 591 592
    
    // 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;
593

pixhawk's avatar
pixhawk committed
594
    // Output all bytes as hex digits
LM's avatar
LM committed
595
    for (int i=0; i<size; i++)
lm's avatar
lm committed
596
    {
597
        if (mavlink_parse_char(getMavlinkChannel(), data[i], &msg, &comm))
lm's avatar
lm committed
598
        {
pixhawk's avatar
pixhawk committed
599
            // MESSAGE RECEIVED!
600
//            qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
601
            emit messageReceived(msg);
pixhawk's avatar
pixhawk committed
602

LM's avatar
LM committed
603 604
            switch (msg.msgid)
            {
pixhawk's avatar
pixhawk committed
605
                // SET THE SYSTEM MODE
LM's avatar
LM committed
606 607
            case MAVLINK_MSG_ID_SET_MODE:
            {
608 609 610
                mavlink_set_mode_t mode;
                mavlink_msg_set_mode_decode(&msg, &mode);
                // Set mode indepent of mode.target
611
                system.base_mode = mode.base_mode;
612 613 614
            }
            break;
            // EXECUTE OPERATOR ACTIONS
LM's avatar
LM committed
615 616
            case MAVLINK_MSG_ID_COMMAND_LONG:
            {
pixhawk's avatar
pixhawk committed
617 618
                mavlink_command_long_t action;
                mavlink_msg_command_long_decode(&msg, &action);
619

620
//                qDebug() << "SIM" << "received action" << action.command << "for system" << action.target_system;
621

lm's avatar
lm committed
622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647
                // 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;
//                }
648 649
            }
            break;
LM's avatar
LM committed
650 651
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            {
652
//                qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
653 654
                mavlink_param_request_list_t read;
                mavlink_msg_param_request_list_decode(&msg, &read);
LM's avatar
LM committed
655 656 657 658 659 660 661 662 663 664
                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
665
                            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
666 667 668 669 670 671 672
                            // 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++;
673
                    }
674

675
//                    qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
LM's avatar
LM committed
676
                }
677
            }
LM's avatar
LM committed
678 679 680
                break;
            case MAVLINK_MSG_ID_PARAM_SET:
            {
681
                // Drop on even milliseconds
LM's avatar
LM committed
682 683
                if (QGC::groundTimeMilliseconds() % 2 == 0)
                {
684
//                    qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER";
685 686 687 688 689
                    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
690 691
                    if (onboardParams.contains(key))
                    {
692 693
                        onboardParams.remove(key);
                        onboardParams.insert(key, set.param_value);
694 695

                        // Pack message and get size of encoded byte string
696
                        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));
697 698 699 700 701 702
                        // Allocate buffer with packet data
                        bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
                        //add data into datastream
                        memcpy(stream+streampointer,buffer, bufferlength);
                        streampointer+=bufferlength;
                    }
703 704 705 706
                    //                    }
                }
            }
            break;
LM's avatar
LM committed
707 708
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            {
709
//                qDebug() << "SIMULATION RECEIVED COMMAND TO SEND PARAMETER";
710 711 712 713
                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
714 715
                if (onboardParams.contains(key))
                {
716 717 718
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
719
                    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));
720 721 722 723 724 725
                    // 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
726
                }
727
                else if (read.param_index >= 0 && read.param_index < onboardParams.keys().size())
LM's avatar
LM committed
728
                {
729 730 731 732
                    key = onboardParams.keys().at(read.param_index);
                    float paramValue = onboardParams.value(key);

                    // Pack message and get size of encoded byte string
733
                    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));
734 735 736 737 738 739
                    // 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;
740
                }
741 742
            }
            break;
pixhawk's avatar
pixhawk committed
743 744
            }
        }
pixhawk's avatar
pixhawk committed
745
    }
pixhawk's avatar
pixhawk committed
746

747 748 749 750 751 752
    // 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());

753
    readyBufferMutex.lock();
LM's avatar
LM committed
754 755
    for (int i = 0; i < streampointer; i++)
    {
756 757 758 759
        readyBuffer.enqueue(*(stream + i));
    }
    readyBufferMutex.unlock();

pixhawk's avatar
pixhawk committed
760
    // Update comm status
761
    status.errors_comm = comm.packet_rx_drop_count;
pixhawk's avatar
pixhawk committed
762

pixhawk's avatar
pixhawk committed
763 764 765
}


766 767
void MAVLinkSimulationLink::readBytes()
{
pixhawk's avatar
pixhawk committed
768 769
    // Lock concurrent resource readyBuffer
    readyBufferMutex.lock();
770 771
    const qint64 maxLength = 2048;
    char data[maxLength];
pixhawk's avatar
pixhawk committed
772
    qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
pixhawk's avatar
pixhawk committed
773

774
    for (unsigned int i = 0; i < len; i++) {
pixhawk's avatar
pixhawk committed
775 776 777 778 779 780 781
        *(data + i) = readyBuffer.takeFirst();
    }

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

782 783 784 785
    // 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
786 787 788 789 790 791 792 793
}

/**
 * Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection
 * couldn't be disconnected.
 **/
794
bool MAVLinkSimulationLink::_disconnect(void)
795
{
pixhawk's avatar
pixhawk committed
796

Lorenz Meier's avatar
Lorenz Meier committed
797 798
    if(isConnected())
    {
pixhawk's avatar
pixhawk committed
799 800 801 802 803 804
        //        timer->stop();

        _isConnected = false;

        emit disconnected();

805
        //exit();
pixhawk's avatar
pixhawk committed
806 807 808 809 810 811 812 813 814 815 816
    }

    return true;
}

/**
 * Connect the link.
 *
 * @return True if connection has been established, false if connection
 * couldn't be established.
 **/
817
bool MAVLinkSimulationLink::_connect(void)
pixhawk's avatar
pixhawk committed
818 819
{
    _isConnected = true;
820
    emit connected();
pixhawk's avatar
pixhawk committed
821 822

    start(LowPriority);
LM's avatar
LM committed
823
    MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 37.480391, -122.282883);
824
    Q_UNUSED(mav1);
825 826
//    MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
//    Q_UNUSED(mav2);
pixhawk's avatar
pixhawk committed
827 828 829 830 831 832 833 834 835
    //    timer->start(rate);
    return true;
}

/**
 * Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
836
bool MAVLinkSimulationLink::isConnected() const
837
{
pixhawk's avatar
pixhawk committed
838 839 840
    return _isConnected;
}

841
QString MAVLinkSimulationLink::getName() const
pixhawk's avatar
pixhawk committed
842 843 844 845
{
    return name;
}

846
qint64 MAVLinkSimulationLink::getConnectionSpeed() const
847
{
pixhawk's avatar
pixhawk committed
848 849
    /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
    return 100000000;
850 851 852 853 854 855 856 857 858 859 860
}

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

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