QGCXPlaneLink.cc 20 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL 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.

    QGROUNDCONTROL 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.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file QGCXPlaneLink.cc
 *   Implementation of X-Plane interface
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QTimer>
#include <QList>
#include <QDebug>
#include <QMutexLocker>
#include <iostream>
#include "QGCXPlaneLink.h"
#include "QGC.h"
#include <QHostInfo>
39
#include "UAS.h"
40 41
#include "MainWindow.h"

42
QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress localHost, quint16 localPort) :
43 44
    mav(mav),
    socket(NULL),
45 46 47
    process(NULL),
    terraSync(NULL)
{
48 49
    this->localHost = localHost;
    this->localPort = localPort/*+mav->getUASID()*/;
50
    this->connectState = false;
51
    this->name = tr("X-Plane Link (localPort:%1)").arg(localPort);
52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71
    setRemoteHost(remoteHost);
}

QGCXPlaneLink::~QGCXPlaneLink()
{   //do not disconnect unless it is connected.
    //disconnectSimulation will delete the memory that was allocated for proces, terraSync and socket
    if(connectState){
       disconnectSimulation();
    }
}

/**
 * @brief Runs the thread
 *
 **/
void QGCXPlaneLink::run()
{
    exec();
}

72
void QGCXPlaneLink::setPort(int localPort)
73
{
74
    this->localPort = localPort;
75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105
    disconnectSimulation();
    connectSimulation();
}

void QGCXPlaneLink::processError(QProcess::ProcessError err)
{
    switch(err)
    {
    case QProcess::FailedToStart:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::Crashed:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Crashed"), tr("This is a X-Plane-related problem. Please upgrade X-Plane"));
        break;
    case QProcess::Timedout:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Start Timed Out"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::WriteError:
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with X-Plane"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::ReadError:
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with X-Plane"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::UnknownError:
    default:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Error"), tr("Please check if the path and command is correct."));
        break;
    }
}

/**
106
 * @param localHost Hostname in standard formatting, e.g. locallocalHost:14551 or 192.168.1.1:14551
107
 */
108
void QGCXPlaneLink::setRemoteHost(const QString& localHost)
109
{
110
    if (localHost.contains(":"))
111
    {
112 113
        //qDebug() << "HOST: " << localHost.split(":").first();
        QHostInfo info = QHostInfo::fromName(localHost.split(":").first());
114 115
        if (info.error() == QHostInfo::NoError)
        {
116 117
            // Add localHost
            QList<QHostAddress> localHostAddresses = info.addresses();
118
            QHostAddress address;
119
            for (int i = 0; i < localHostAddresses.size(); i++)
120 121
            {
                // Exclude loopback IPv4 and all IPv6 addresses
122
                if (!localHostAddresses.at(i).toString().contains(":"))
123
                {
124
                    address = localHostAddresses.at(i);
125 126
                }
            }
127
            remoteHost = address;
128
            //qDebug() << "Address:" << address.toString();
129 130
            // Set localPort according to user input
            remotePort = localHost.split(":").last().toInt();
131 132 133 134
        }
    }
    else
    {
135
        QHostInfo info = QHostInfo::fromName(localHost);
136 137
        if (info.error() == QHostInfo::NoError)
        {
138 139
            // Add localHost
            remoteHost = info.addresses().first();
140 141 142 143 144 145 146 147
        }
    }

}

void QGCXPlaneLink::updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode)
{

148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
    #pragma pack(push, 1)
    struct payload {
        char b[5];
        int index;
        float f[8];
    } p;
    #pragma pack(pop)

    p.b[0] = 'D';
    p.b[1] = 'A';
    p.b[2] = 'T';
    p.b[3] = 'A';
    p.b[4] = '\0';

    p.index = 12;
    p.f[0] = rollAilerons;
    p.f[1] = pitchElevator;
    p.f[2] = yawRudder;

167 168 169 170
    Q_UNUSED(time);
    Q_UNUSED(systemMode);
    Q_UNUSED(navMode);

171 172 173 174 175 176 177 178 179 180 181
    // Ail / Elevon / Rudder
    writeBytes((const char*)&p, sizeof(p));

    p.index = 25;
    memset(p.f, 0, sizeof(p.f));
    p.f[0] = 0.5f;//throttle;
    p.f[1] = 0.5f;//throttle;
    p.f[2] = 0.5f;//throttle;
    p.f[3] = 0.5f;//throttle;
    // Throttle
    writeBytes((const char*)&p, sizeof(p));
182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202
}

void QGCXPlaneLink::writeBytes(const char* data, qint64 size)
{
    //#define QGCXPlaneLink_DEBUG
#if 1
    QString bytes;
    QString ascii;
    for (int i=0; i<size; i++)
    {
        unsigned char v = data[i];
        bytes.append(QString().sprintf("%02x ", v));
        if (data[i] > 31 && data[i] < 127)
        {
            ascii.append(data[i]);
        }
        else
        {
            ascii.append(219);
        }
    }
203 204 205
    //qDebug() << "Sent" << size << "bytes to" << remoteHost.toString() << ":" << remotePort << "data:";
    //qDebug() << bytes;
    //qDebug() << "ASCII:" << ascii;
206
#endif
207
    if (connectState && socket) socket->writeDatagram(data, size, remoteHost, remotePort);
208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228
}

/**
 * @brief Read a number of bytes from the interface.
 *
 * @param data Pointer to the data byte array to write the bytes to
 * @param maxLength The maximum number of bytes to write
 **/
void QGCXPlaneLink::readBytes()
{
    const qint64 maxLength = 65536;
    char data[maxLength];
    QHostAddress sender;
    quint16 senderPort;

    unsigned int s = socket->pendingDatagramSize();
    if (s > maxLength) std::cerr << __FILE__ << __LINE__ << " UDP datagram overflow, allowed to read less bytes than datagram size" << std::endl;
    socket->readDatagram(data, maxLength, &sender, &senderPort);

    QByteArray b(data, s);

229 230
    /*// Print string
    QString state(b)*/;
231

232 233 234
    // Calculate the number of data segments a 36 bytes
    // XPlane always has 5 bytes header: 'DATA@'
    unsigned nsegs = (s-5)/36;
235

236
    //qDebug() << "XPLANE:" << "LEN:" << s << "segs:" << nsegs;
237

238 239 240 241 242 243
    #pragma pack(push, 1)
    struct payload {
        int index;
        float f[8];
    } p;
    #pragma pack(pop)
244

245 246
    float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
    double lat, lon, alt;
247 248 249
    float vx, vy, vz, xacc, yacc, zacc;
    float airspeed;
    float groundspeed;
250

251 252
    float man_roll, man_pitch, man_yaw;

253 254 255 256 257 258 259 260 261 262 263 264 265 266
    if (data[0] == 'D' &&
            data[1] == 'A' &&
            data[2] == 'T' &&
            data[3] == 'A')
    {

        for (unsigned i = 0; i < nsegs; i++)
        {
            // Get index
            unsigned ioff = (5+i*36);;
            memcpy(&(p), data+ioff, sizeof(p));

            if (p.index == 3)
            {
267 268 269
                airspeed = p.f[6] * 0.44704f;
                groundspeed = p.f[7] * 0.44704;

270 271 272 273 274 275 276 277 278 279
                //qDebug() << "SPEEDS:" << "airspeed" << airspeed << "m/s, groundspeed" << groundspeed << "m/s";
            }
            else if (p.index == 8)
            {
                //qDebug() << "MAN:" << p.f[0] << p.f[3] << p.f[7];
                man_roll = p.f[0];
                man_pitch = p.f[1];
                man_yaw = p.f[2];
                UAS* uas = dynamic_cast<UAS*>(mav);
                if (uas) uas->setManualControlCommands(man_roll, man_pitch, man_yaw, 0.6);
280 281
            }
            else if (p.index == 16)
282
            {
283
                //qDebug() << "ANG VEL:" << p.f[0] << p.f[3] << p.f[7];
284 285 286
                rollspeed = p.f[2];
                pitchspeed = p.f[1];
                yawspeed = p.f[0];
287
            }
288
            else if (p.index == 17)
289
            {
290
                //qDebug() << "HDNG" << "pitch" << p.f[0] << "roll" << p.f[1] << "hding true" << p.f[2] << "hding mag" << p.f[3];
291 292 293 294
                // XXX Feeding true heading - might need fix
                pitch = (p.f[0] - 180.0f) / 180.0f * M_PI;
                roll = (p.f[1] - 180.0f) / 180.0f * M_PI;
                yaw = (p.f[2] - 180.0f) / 180.0f * M_PI;
295
            }
296

297 298 299 300 301
//            else if (p.index == 19)
//            {
//                qDebug() << "ATT:" << p.f[0] << p.f[1] << p.f[2];
//            }
            else if (p.index == 20)
302
            {
303
                //qDebug() << "LAT/LON/ALT:" << p.f[0] << p.f[1] << p.f[2];
304 305
                lat = p.f[0];
                lon = p.f[1];
306 307 308 309
                alt = p.f[2] * 0.3048f; // convert feet (MSL) to meters
            }
            else if (p.index == 12)
            {
310
                //qDebug() << "AIL/ELEV/RUD" << p.f[0] << p.f[1] << p.f[2];
311 312 313
            }
            else if (p.index == 25)
            {
314
                //qDebug() << "THROTTLE" << p.f[0] << p.f[1] << p.f[2] << p.f[3];
315 316 317
            }
            else if (p.index == 0)
            {
318
                //qDebug() << "STATS" << "fgraphics/s" << p.f[0] << "fsim/s" << p.f[2] << "t frame" << p.f[3] << "cpu load" << p.f[4] << "grnd ratio" << p.f[5] << "filt ratio" << p.f[6];
319 320 321
            }
            else if (p.index == 11)
            {
322
                //qDebug() << "CONTROLS" << "ail" << p.f[0] << "elev" << p.f[1] << "rudder" << p.f[2] << "nwheel" << p.f[3];
323 324 325
            }
            else
            {
326
                //qDebug() << "UNKNOWN #" << p.index << p.f[0] << p.f[1] << p.f[2] << p.f[3];
327 328 329 330 331 332 333
            }
        }
    }
    else
    {
        qDebug() << "UNKNOWN PACKET:" << data;
    }
334 335 336

    // Send updated state
    emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
337 338
                         pitchspeed, yawspeed, lat*1E7, lon*1E7, alt*1E3,
                         vx, vy, vz, xacc*1000, yacc*1000, zacc*1000);
339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368

    //    // Echo data for debugging purposes
    //    std::cerr << __FILE__ << __LINE__ << "Received datagram:" << std::endl;
    //    int i;
    //    for (i=0; i<s; i++)
    //    {
    //        unsigned int v=data[i];
    //        fprintf(stderr,"%02x ", v);
    //    }
    //    std::cerr << std::endl;
}


/**
 * @brief Get the number of bytes to read.
 *
 * @return The number of bytes to read
 **/
qint64 QGCXPlaneLink::bytesAvailable()
{
    return socket->pendingDatagramSize();
}

/**
 * @brief Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection couldn't be disconnected.
 **/
bool QGCXPlaneLink::disconnectSimulation()
{
369 370
    if (!connectState) return true;

371 372
    connectState = false;

373
    if (process) disconnect(process, SIGNAL(error(QProcess::ProcessError)),
374
               this, SLOT(processError(QProcess::ProcessError)));
375 376 377 378
    if (mav)
    {
        disconnect(mav, SIGNAL(hilControlsChanged(uint64_t, float, float, float, float, uint8_t, uint8_t)), this, SLOT(updateControls(uint64_t,float,float,float,float,uint8_t,uint8_t)));
        disconnect(this, SIGNAL(hilStateChanged(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)), mav, SLOT(sendHilState(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)));
379 380 381 382 383
        UAS* uas = dynamic_cast<UAS*>(mav);
        if (uas)
        {
            uas->stopHil();
        }
384
    }
385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417

    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
    if (terraSync)
    {
        terraSync->close();
        delete terraSync;
        terraSync = NULL;
    }
    if (socket)
    {
        socket->close();
        delete socket;
        socket = NULL;
    }

    emit simulationDisconnected();
    emit simulationConnected(false);
    return !connectState;
}

/**
 * @brief Connect the connection.
 *
 * @return True if connection has been established, false if connection couldn't be established.
 **/
bool QGCXPlaneLink::connectSimulation()
{
    if (!mav) return false;
418 419
    if (connectState) return false;

420
    socket = new QUdpSocket(this);
421
    connectState = socket->bind(localHost, localPort);
422
    if (!connectState) return false;
423 424 425 426 427 428 429 430 431

    QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes()));

    //process = new QProcess(this);
    //terraSync = new QProcess(this);

    connect(mav, SIGNAL(hilControlsChanged(uint64_t, float, float, float, float, uint8_t, uint8_t)), this, SLOT(updateControls(uint64_t,float,float,float,float,uint8_t,uint8_t)));
    connect(this, SIGNAL(hilStateChanged(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)), mav, SLOT(sendHilState(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)));

432 433 434 435 436
    UAS* uas = dynamic_cast<UAS*>(mav);
    if (uas)
    {
        uas->startHil();
    }
437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512

    // XXX This will later be enabled to start X-Plane from within QGroundControl with the right arguments

//    //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate()));
//    // Catch process error
//    QObject::connect( process, SIGNAL(error(QProcess::ProcessError)),
//                      this, SLOT(processError(QProcess::ProcessError)));
//    QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)),
//                      this, SLOT(processError(QProcess::ProcessError)));
//    // Start X-Plane
//    QStringList processCall;
//    QString processFgfs;
//    QString processTerraSync;
//    QString fgRoot;
//    QString fgScenery;
//    QString aircraft;

//    if (mav->getSystemType() == MAV_TYPE_FIXED_WING)
//    {
//        aircraft = "Rascal110-JSBSim";
//    }
//    else if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
//    {
//        aircraft = "arducopter";
//    }
//    else
//    {
//        aircraft = "Rascal110-JSBSim";
//    }

//#ifdef Q_OS_MACX
//    processFgfs = "/Applications/X-Plane.app/Contents/Resources/fgfs";
//    processTerraSync = "/Applications/X-Plane.app/Contents/Resources/terrasync";
//    fgRoot = "/Applications/X-Plane.app/Contents/Resources/data";
//    //fgScenery = "/Applications/X-Plane.app/Contents/Resources/data/Scenery";
//    fgScenery = "/Applications/X-Plane.app/Contents/Resources/data/Scenery-TerraSync";
//    //   /Applications/X-Plane.app/Contents/Resources/data/Scenery:
//#endif

//#ifdef Q_OS_WIN32
//    processFgfs = "C:\\Program Files (x86)\\X-Plane\\bin\\Win32\\fgfs";
//    fgRoot = "C:\\Program Files (x86)\\X-Plane\\data";
//    fgScenery = "C:\\Program Files (x86)\\X-Plane\\data\\Scenery-Terrasync";
//#endif

//#ifdef Q_OS_LINUX
//    processFgfs = "fgfs";
//    fgRoot = "/usr/share/X-Plane/data";
//    fgScenery = "/usr/share/X-Plane/data/Scenery-Terrasync";
//#endif

//    // Sanity checks
//    bool sane = true;
//    QFileInfo executable(processFgfs);
//    if (!executable.isExecutable())
//    {
//        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane was not found at %1").arg(processFgfs));
//        sane = false;
//    }

//    QFileInfo root(fgRoot);
//    if (!root.isDir())
//    {
//        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane data directory was not found at %1").arg(fgRoot));
//        sane = false;
//    }

//    QFileInfo scenery(fgScenery);
//    if (!scenery.isDir())
//    {
//        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane scenery directory was not found at %1").arg(fgScenery));
//        sane = false;
//    }

//    if (!sane) return false;

513
//    // --atlas=socket,out,1,locallocalHost,5505,udp
514 515 516 517 518 519 520
//    // terrasync -p 5505 -S -d /usr/local/share/TerraSync

//    processCall << QString("--fg-root=%1").arg(fgRoot);
//    processCall << QString("--fg-scenery=%1").arg(fgScenery);
//    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
//    {
//        // FIXME ADD QUAD-Specific protocol here
521 522
//        processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(localPort);
//        processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(remotePort);
523 524 525
//    }
//    else
//    {
526 527
//        processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(localPort);
//        processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(remotePort);
528
//    }
529
//    processCall << "--atlas=socket,out,1,locallocalHost,5505,udp";
530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595
//    processCall << "--in-air";
//    processCall << "--roll=0";
//    processCall << "--pitch=0";
//    processCall << "--vc=90";
//    processCall << "--heading=300";
//    processCall << "--timeofday=noon";
//    processCall << "--disable-hud-3d";
//    processCall << "--disable-fullscreen";
//    processCall << "--geometry=400x300";
//    processCall << "--disable-anti-alias-hud";
//    processCall << "--wind=0@0";
//    processCall << "--turbulence=0.0";
//    processCall << "--prop:/sim/frame-rate-throttle-hz=30";
//    processCall << "--control=mouse";
//    processCall << "--disable-intro-music";
//    processCall << "--disable-sound";
//    processCall << "--disable-random-objects";
//    processCall << "--disable-ai-models";
//    processCall << "--shading-flat";
//    processCall << "--fog-disable";
//    processCall << "--disable-specular-highlight";
//    //processCall << "--disable-skyblend";
//    processCall << "--disable-random-objects";
//    processCall << "--disable-panel";
//    //processCall << "--disable-horizon-effect";
//    processCall << "--disable-clouds";
//    processCall << "--fdm=jsb";
//    processCall << "--units-meters";
//    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
//    {
//        // Start all engines of the quad
//        processCall << "--prop:/engines/engine[0]/running=true";
//        processCall << "--prop:/engines/engine[1]/running=true";
//        processCall << "--prop:/engines/engine[2]/running=true";
//        processCall << "--prop:/engines/engine[3]/running=true";
//    }
//    else
//    {
//        processCall << "--prop:/engines/engine/running=true";
//    }
//    processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
//    processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
//    processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
//    // Add new argument with this: processCall << "";
//    processCall << QString("--aircraft=%2").arg(aircraft);


//    QStringList terraSyncArguments;
//    terraSyncArguments << "-p 5505";
//    terraSyncArguments << "-S";
//    terraSyncArguments << QString("-d=%1").arg(fgScenery);

//    terraSync->start(processTerraSync, terraSyncArguments);
//    process->start(processFgfs, processCall);



//    emit X-PlaneConnected(connectState);
//    if (connectState) {
//        emit X-PlaneConnected();
//        connectionStartTime = QGC::groundTimeUsecs()/1000;
//    }
//    qDebug() << "STARTING SIM";

//        qDebug() << "STARTING: " << processFgfs << processCall;

596
    qDebug() << "STARTING X-PLANE LINK, CONNECTING TO" << remoteHost << ":" << remotePort;
597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621

    start(LowPriority);
    return connectState;
}

/**
 * @brief Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
bool QGCXPlaneLink::isConnected()
{
    return connectState;
}

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

void QGCXPlaneLink::setName(QString name)
{
    this->name = name;
    //    emit nameChanged(this->name);
}