SerialLink.cc 19.7 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 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 13
    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.

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 18 19
    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
lm's avatar
lm committed
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26 27 28 29 30 31 32

======================================================================*/
/**
 * @file
 *   @brief Cross-platform support for serial ports
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QTimer>
#include <QDebug>
33
#include <QSettings>
pixhawk's avatar
pixhawk committed
34 35 36
#include <QMutexLocker>
#include "SerialLink.h"
#include "LinkManager.h"
37
#include "QGC.h"
pixhawk's avatar
pixhawk committed
38
#include <MG.h>
39
#include <iostream>
pixhawk's avatar
pixhawk committed
40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59
#ifdef _WIN32
#include "windows.h"
#endif


SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, ParityType parity, DataBitsType dataBits, StopBitsType stopBits)
{
    // Setup settings
    this->porthandle = portname.trimmed();
#ifdef _WIN32
    // Port names above 20 need the network path format - if the port name is not already in this format
    // catch this special case
    if (this->porthandle.size() > 0 && !this->porthandle.startsWith("\\"))
    {
        // Append \\.\ before the port handle. Additional backslashes are used for escaping.
        this->porthandle = "\\\\.\\" + this->porthandle;
    }
#endif
    // Set unique ID and add link to the list of links
    this->id = getNextLinkId();
60 61 62

    // Load defaults from settings
    QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
lm's avatar
lm committed
63
    settings.sync();
64 65 66
    if (settings.contains("SERIALLINK_COMM_PORT"))
    {
        this->porthandle = settings.value("SERIALLINK_COMM_PORT").toString();
lm's avatar
lm committed
67 68 69 70 71 72 73 74
    }

    // *nix (Linux, MacOS tested) serial port support
    port = new QextSerialPort(porthandle, QextSerialPort::Polling);
    //port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);

    if (settings.contains("SERIALLINK_COMM_PORT"))
    {
75 76 77 78 79 80 81 82 83 84 85 86 87 88
        setBaudRate(settings.value("SERIALLINK_COMM_BAUD").toInt());
        setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
        setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
        setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
    }
    else
    {
        this->baudrate = baudrate;
        this->flow = flow;
        this->parity = parity;
        this->dataBits = dataBits;
        this->stopBits = stopBits;
        this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
    }
lm's avatar
lm committed
89 90 91 92 93 94
    port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
    port->setBaudRate(baudrate);
    port->setFlowControl(flow);
    port->setParity(parity);
    port->setDataBits(dataBits);
    port->setStopBits(stopBits);
pixhawk's avatar
pixhawk committed
95 96 97 98

    // Set the port name
    if (porthandle == "")
    {
99 100
//        name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
        name = tr("Serial Link ") + QString::number(getId());
pixhawk's avatar
pixhawk committed
101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122
    }
    else
    {
        name = portname.trimmed();
    }

#ifdef _WIN3232
    // Windows 32bit & 64bit serial connection
    winPort = CreateFile(porthandle,
                         GENERIC_READ | GENERIC_WRITE,
                         0,
                         0,
                         OPEN_EXISTING,
                         FILE_ATTRIBUTE_NORMAL,
                         0);
    if(winPort==INVALID_HANDLE_VALUE){
        if(GetLastError()==ERROR_FILE_NOT_FOUND){
            //serial port does not exist. Inform user.
        }
        //some other error occurred. Inform user.
    }
#else
lm's avatar
lm committed
123

pixhawk's avatar
pixhawk committed
124 125 126 127 128 129 130 131 132
#endif

    // Link is setup, register it with link manager
    LinkManager::instance()->add(this);
}

SerialLink::~SerialLink()
{
    disconnect();
133
    if(port) delete port;
pixhawk's avatar
pixhawk committed
134 135 136 137 138 139 140 141
    port = NULL;
}


/**
 * @brief Runs the thread
 *
 **/
142 143
void SerialLink::run()
{
pixhawk's avatar
pixhawk committed
144 145 146 147
    // Initialize the connection
    hardwareConnect();

    // Qt way to make clear what a while(1) loop does
148 149
    forever
    {
pixhawk's avatar
pixhawk committed
150 151 152 153 154 155 156 157 158 159
        // Check if new bytes have arrived, if yes, emit the notification signal
        checkForBytes();
        /* Serial data isn't arriving that fast normally, this saves the thread
                 * from consuming too much processing time
                 */
        MG::SLEEP::msleep(SerialLink::poll_interval);
    }
}


160 161
void SerialLink::checkForBytes()
{
pixhawk's avatar
pixhawk committed
162
    /* Check if bytes are available */
163 164
    if(port->isOpen())
    {
pixhawk's avatar
pixhawk committed
165 166 167 168
        dataMutex.lock();
        qint64 available = port->bytesAvailable();
        dataMutex.unlock();

169 170 171
        if(available > 0)
        {
            readBytes();
pixhawk's avatar
pixhawk committed
172
        }
173 174 175
    }
    else
    {
pixhawk's avatar
pixhawk committed
176 177 178 179 180 181
        emit disconnected();
    }

}


182 183
void SerialLink::writeBytes(const char* data, qint64 size)
{
pixhawk's avatar
pixhawk committed
184 185
    if(port->isOpen())
    {
pixhawk's avatar
pixhawk committed
186 187 188
        int b = port->write(data, size);
        qDebug() << "Transmitted " << b << "bytes:";

pixhawk's avatar
pixhawk committed
189
        // Increase write counter
pixhawk's avatar
pixhawk committed
190 191 192
        bitsSentTotal += size * 8;

        int i;
pixhawk's avatar
pixhawk committed
193 194 195
        for (i=0; i<size; i++)
        {
            unsigned char v=data[i];
pixhawk's avatar
pixhawk committed
196

197
            //fprintf(stderr,"%02x ", v);
pixhawk's avatar
pixhawk committed
198 199 200 201 202 203 204 205 206 207
        }
    }
}

/**
 * @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
 **/
208 209
void SerialLink::readBytes()
{
pixhawk's avatar
pixhawk committed
210
    dataMutex.lock();
211 212 213 214
    if(port->isOpen())
    {
        const qint64 maxLength = 2048;
        char data[maxLength];
pixhawk's avatar
pixhawk committed
215
        qint64 numBytes = port->bytesAvailable();
216

217 218
        if(numBytes > 0)
        {
pixhawk's avatar
pixhawk committed
219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245
            /* Read as much data in buffer as possible without overflow */
            if(maxLength < numBytes) numBytes = maxLength;

            port->read(data, numBytes);
            QByteArray b(data, numBytes);
            emit bytesReceived(this, b);

            //qDebug() << "SerialLink::readBytes()" << std::hex << data;
            //            int i;
            //            for (i=0; i<numBytes; i++){
            //                unsigned int v=data[i];
            //
            //                fprintf(stderr,"%02x ", v);
            //            }
            //            fprintf(stderr,"\n");
            bitsReceivedTotal += numBytes * 8;
        }
    }
    dataMutex.unlock();
}


/**
 * @brief Get the number of bytes to read.
 *
 * @return The number of bytes to read
 **/
246 247
qint64 SerialLink::bytesAvailable()
{
pixhawk's avatar
pixhawk committed
248 249 250 251 252 253 254 255
    return port->bytesAvailable();
}

/**
 * @brief Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection couldn't be disconnected.
 **/
256 257
bool SerialLink::disconnect()
{
pixhawk's avatar
pixhawk committed
258 259 260 261 262 263 264 265
    //#if !defined _WIN32 || !defined _WIN64
    /* Block the thread until it returns from run() */
    //#endif
    dataMutex.lock();
    port->flush();
    port->close();
    dataMutex.unlock();

266 267
    if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect

pixhawk's avatar
pixhawk committed
268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308
    bool closed = true;
    //port->isOpen();

    emit disconnected();
    emit connected(false);

    return ! closed;
}

/**
 * @brief Connect the connection.
 *
 * @return True if connection has been established, false if connection couldn't be established.
 **/
bool SerialLink::connect()
{
    qDebug() << "CONNECTING LINK: " << __FILE__ << __LINE__ << "with settings" << porthandle << baudrate << dataBits << parity << stopBits;
    if (!this->isRunning())
    {
        this->start(LowPriority);
    }
    else
    {
        if(isConnected())
        {
            disconnect();
        }
        hardwareConnect();
    }

    return port->isOpen();
}

/**
 * @brief This function is called indirectly by the connect() call.
 *
 * The connect() function starts the thread and indirectly calls this method.
 *
 * @return True if the connection could be established, false otherwise
 * @see connect() For the right function to establish the connection.
 **/
309 310
bool SerialLink::hardwareConnect()
{
pixhawk's avatar
pixhawk committed
311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326
    QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected()));

    port->open(QIODevice::ReadWrite);
    port->setBaudRate(this->baudrate);
    port->setParity(this->parity);
    port->setStopBits(this->stopBits);
    port->setDataBits(this->dataBits);

    statisticsMutex.lock();
    connectionStartTime = MG::TIME::getGroundTimeNow();
    statisticsMutex.unlock();

    bool connectionUp = isConnected();
    if(connectionUp) {
        emit connected();
        emit connected(true);
lm's avatar
lm committed
327 328 329 330 331 332 333 334 335

        // Store settings
        QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
        settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
        settings.setValue("SERIALLINK_COMM_BAUD", getBaudRate());
        settings.setValue("SERIALLINK_COMM_PARITY", getParityType());
        settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBitsType());
        settings.setValue("SERIALLINK_COMM_DATABITS", getDataBitsType());
        settings.sync();
pixhawk's avatar
pixhawk committed
336 337 338 339
    }

    return connectionUp;
}
340 341


pixhawk's avatar
pixhawk committed
342 343 344 345 346
/**
 * @brief Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
347 348
bool SerialLink::isConnected()
{
lm's avatar
lm committed
349 350 351 352 353 354 355 356
    if (port)
    {
        return port->isOpen();
    }
    else
    {
        return false;
    }
pixhawk's avatar
pixhawk committed
357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375
}

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

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

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


376 377
qint64 SerialLink::getNominalDataRate()
{
pixhawk's avatar
pixhawk committed
378 379 380 381 382 383 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 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449
    qint64 dataRate = 0;
    switch (baudrate) {
    case BAUD50:
        dataRate = 50;
        break;
    case BAUD75:
        dataRate = 75;
        break;
    case BAUD110:
        dataRate = 110;
        break;
    case BAUD134:
        dataRate = 134;
        break;
    case BAUD150:
        dataRate = 150;
        break;
    case BAUD200:
        dataRate = 200;
        break;
    case BAUD300:
        dataRate = 300;
        break;
    case BAUD600:
        dataRate = 600;
        break;
    case BAUD1200:
        dataRate = 1200;
        break;
    case BAUD1800:
        dataRate = 1800;
        break;
    case BAUD2400:
        dataRate = 2400;
        break;
    case BAUD4800:
        dataRate = 4800;
        break;
    case BAUD9600:
        dataRate = 9600;
        break;
    case BAUD14400:
        dataRate = 14400;
        break;
    case BAUD19200:
        dataRate = 19200;
        break;
    case BAUD38400:
        dataRate = 38400;
        break;
    case BAUD56000:
        dataRate = 56000;
        break;
    case BAUD57600:
        dataRate = 57600;
        break;
    case BAUD76800:
        dataRate = 76800;
        break;
    case BAUD115200:
        dataRate = 115200;
        break;
    case BAUD128000:
        dataRate = 128000;
        break;
    case BAUD256000:
        dataRate = 256000;
        break;
    }
    return dataRate;
}

450 451
qint64 SerialLink::getTotalUpstream()
{
pixhawk's avatar
pixhawk committed
452 453 454 455 456
    statisticsMutex.lock();
    return bitsSentTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
    statisticsMutex.unlock();
}

457 458
qint64 SerialLink::getCurrentUpstream()
{
pixhawk's avatar
pixhawk committed
459 460 461
    return 0; // TODO
}

462 463
qint64 SerialLink::getMaxUpstream()
{
pixhawk's avatar
pixhawk committed
464 465 466
    return 0; // TODO
}

467 468
qint64 SerialLink::getBitsSent()
{
pixhawk's avatar
pixhawk committed
469 470 471
    return bitsSentTotal;
}

472 473
qint64 SerialLink::getBitsReceived()
{
pixhawk's avatar
pixhawk committed
474 475 476
    return bitsReceivedTotal;
}

477 478
qint64 SerialLink::getTotalDownstream()
{
pixhawk's avatar
pixhawk committed
479 480 481 482 483
    statisticsMutex.lock();
    return bitsReceivedTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
    statisticsMutex.unlock();
}

484 485
qint64 SerialLink::getCurrentDownstream()
{
pixhawk's avatar
pixhawk committed
486 487 488
    return 0; // TODO
}

489 490
qint64 SerialLink::getMaxDownstream()
{
pixhawk's avatar
pixhawk committed
491 492 493
    return 0; // TODO
}

494 495
bool SerialLink::isFullDuplex()
{
pixhawk's avatar
pixhawk committed
496 497 498 499
    /* Serial connections are always half duplex */
    return false;
}

500 501
int SerialLink::getLinkQuality()
{
pixhawk's avatar
pixhawk committed
502 503 504 505
    /* This feature is not supported with this interface */
    return -1;
}

506 507
QString SerialLink::getPortName()
{
pixhawk's avatar
pixhawk committed
508 509 510
    return porthandle;
}

511 512
int SerialLink::getBaudRate()
{
pixhawk's avatar
pixhawk committed
513 514 515
    return getNominalDataRate();
}

516 517
int SerialLink::getBaudRateType()
{
pixhawk's avatar
pixhawk committed
518 519 520
    return baudrate;
}

521 522
int SerialLink::getFlowType()
{
pixhawk's avatar
pixhawk committed
523 524 525
    return flow;
}

526 527
int SerialLink::getParityType()
{
pixhawk's avatar
pixhawk committed
528 529 530
    return parity;
}

531 532
int SerialLink::getDataBitsType()
{
pixhawk's avatar
pixhawk committed
533 534 535
    return dataBits;
}

536 537
int SerialLink::getStopBitsType()
{
pixhawk's avatar
pixhawk committed
538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560
    return stopBits;
}

bool SerialLink::setPortName(QString portName)
{
    if(portName.trimmed().length() > 0)
    {
        bool reconnect = false;
        if(isConnected()) {
            disconnect();
            reconnect = true;
        }
        this->porthandle = portName.trimmed();
        setName(tr("serial port ") + portName.trimmed());
#ifdef _WIN32
        // Port names above 20 need the network path format - if the port name is not already in this format
        // catch this special case
        if (!this->porthandle.startsWith("\\"))
        {
            // Append \\.\ before the port handle. Additional backslashes are used for escaping.
            this->porthandle = "\\\\.\\" + this->porthandle;
        }
#endif
561
        if(port) delete port;
pixhawk's avatar
pixhawk committed
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 596 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 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 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 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 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751
        port = new QextSerialPort(porthandle, QextSerialPort::Polling);

        port->setBaudRate(baudrate);
        port->setFlowControl(flow);
        port->setParity(parity);
        port->setDataBits(dataBits);
        port->setStopBits(stopBits);
        port->setTimeout(timeout);
        if(reconnect) connect();
        return true;
    }
    else
    {
        return false;
    }
}


bool SerialLink::setBaudRateType(int rateIndex)
{
    bool reconnect = false;
    bool accepted = true; // This is changed if none of the data rates matches
    if(isConnected()) {
        disconnect();
        reconnect = true;
    }
    switch (rateIndex) {
    case 0:
        baudrate = BAUD50;
        break;
    case 1:
        baudrate = BAUD75;
        break;
    case 2:
        baudrate = BAUD110;
        break;
    case 3:
        baudrate = BAUD134;
        break;
    case 4:
        baudrate = BAUD150;
        break;
    case 5:
        baudrate = BAUD200;
        break;
    case 6:
        baudrate = BAUD300;
        break;
    case 7:
        baudrate = BAUD600;
        break;
    case 8:
        baudrate = BAUD1200;
        break;
    case 9:
        baudrate = BAUD1800;
        break;
    case 10:
        baudrate = BAUD2400;
        break;
    case 11:
        baudrate = BAUD4800;
        break;
    case 12:
        baudrate = BAUD9600;
        break;
    case 13:
        baudrate = BAUD14400;
        break;
    case 14:
        baudrate = BAUD19200;
        break;
    case 15:
        baudrate = BAUD38400;
        break;
    case 16:
        baudrate = BAUD56000;
        break;
    case 17:
        baudrate = BAUD57600;
        break;
    case 18:
        baudrate = BAUD76800;
        break;
    case 19:
        baudrate = BAUD115200;
        break;
    case 20:
        baudrate = BAUD128000;
        break;
    case 21:
        baudrate = BAUD256000;
        break;
    default:
        // If none of the above cases matches, there must be an error
        accepted = false;
        break;
    }

    dataMutex.lock();
    port->setBaudRate(this->baudrate);
    dataMutex.unlock();
    if(reconnect) connect();
    return accepted;
}



bool SerialLink::setBaudRate(int rate)
{
    bool reconnect = false;
    bool accepted = true; // This is changed if none of the data rates matches
    if(isConnected()) {
        disconnect();
        reconnect = true;
    }

    switch (rate) {
    case 50:
        baudrate = BAUD50;
        break;
    case 75:
        baudrate = BAUD75;
        break;
    case 110:
        baudrate = BAUD110;
        break;
    case 134:
        baudrate = BAUD134;
        break;
    case 150:
        baudrate = BAUD150;
        break;
    case 200:
        baudrate = BAUD200;
        break;
    case 300:
        baudrate = BAUD300;
        break;
    case 600:
        baudrate = BAUD600;
        break;
    case 1200:
        baudrate = BAUD1200;
        break;
    case 1800:
        baudrate = BAUD1800;
        break;
    case 2400:
        baudrate = BAUD2400;
        break;
    case 4800:
        baudrate = BAUD4800;
        break;
    case 9600:
        baudrate = BAUD9600;
        break;
    case 14400:
        baudrate = BAUD14400;
        break;
    case 19200:
        baudrate = BAUD19200;
        break;
    case 38400:
        baudrate = BAUD38400;
        break;
    case 56000:
        baudrate = BAUD56000;
        break;
    case 57600:
        baudrate = BAUD57600;
        break;
    case 76800:
        baudrate = BAUD76800;
        break;
    case 115200:
        baudrate = BAUD115200;
        break;
    case 128000:
        baudrate = BAUD128000;
        break;
    case 256000:
        baudrate = BAUD256000;
        break;
    default:
        // If none of the above cases matches, there must be an error
        accepted = false;
        break;
    }

lm's avatar
lm committed
752 753 754 755 756 757 758 759 760 761
    if (port)
    {
        port->setBaudRate(this->baudrate);
        if(reconnect) connect();
        return accepted;
    }
    else
    {
        return false;
    }
pixhawk's avatar
pixhawk committed
762 763
}

764 765
bool SerialLink::setFlowType(int flow)
{
pixhawk's avatar
pixhawk committed
766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792
    bool reconnect = false;
    bool accepted = true;
    if(isConnected()) {
        disconnect();
        reconnect = true;
    }

    switch (flow) {
    case FLOW_OFF:
        this->flow = FLOW_OFF;
        break;
    case FLOW_HARDWARE:
        this->flow = FLOW_HARDWARE;
        break;
    case FLOW_XONXOFF:
        this->flow = FLOW_XONXOFF;
        break;
    default:
        // If none of the above cases matches, there must be an error
        accepted = false;
        break;
    }
    port->setFlowControl(this->flow);
    if(reconnect) connect();
    return accepted;
}

793 794
bool SerialLink::setParityType(int parity)
{
pixhawk's avatar
pixhawk committed
795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828
    bool reconnect = false;
    bool accepted = true;
    if(isConnected()) {
        disconnect();
        reconnect = true;
    }

    switch (parity) {
    case PAR_NONE:
        this->parity = PAR_NONE;
        break;
    case PAR_ODD:
        this->parity = PAR_ODD;
        break;
    case PAR_EVEN:
        this->parity = PAR_EVEN;
        break;
    case PAR_MARK:
        this->parity = PAR_MARK;
        break;
    case PAR_SPACE:
        this->parity = PAR_SPACE;
        break;
    default:
        // If none of the above cases matches, there must be an error
        accepted = false;
        break;
    }

    port->setParity(this->parity);
    if(reconnect) connect();
    return accepted;
}

829 830
bool SerialLink::setDataBitsType(int dataBits)
{
pixhawk's avatar
pixhawk committed
831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860
    bool accepted = true;

    switch (dataBits) {
    case 5:
        this->dataBits = DATA_5;
        break;
    case 6:
        this->dataBits = DATA_6;
        break;
    case 7:
        this->dataBits = DATA_7;
        break;
    case 8:
        this->dataBits = DATA_8;
        break;
    default:
        // If none of the above cases matches, there must be an error
        accepted = false;
        break;
    }

    port->setDataBits(this->dataBits);
    if(isConnected()) {
        disconnect();
        connect();
    }

    return accepted;
}

861 862
bool SerialLink::setStopBitsType(int stopBits)
{
pixhawk's avatar
pixhawk committed
863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886
    bool reconnect = false;
    bool accepted = true;
    if(isConnected()) {
        disconnect();
        reconnect = true;
    }

    switch (stopBits) {
    case 1:
        this->stopBits = STOP_1;
        break;
    case 2:
        this->stopBits = STOP_2;
        break;
    default:
        // If none of the above cases matches, there must be an error
        accepted = false;
        break;
    }

    port->setStopBits(this->stopBits);
    if(reconnect) connect();
    return accepted;
}