TaisyncTelemetry.cc 1.76 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#include "TaisyncTelemetry.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"

//-----------------------------------------------------------------------------
TaisyncTelemetry::TaisyncTelemetry(QObject* parent)
    : TaisyncHandler(parent)
{
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
22
bool
23 24
TaisyncTelemetry::close()
{
Gus Grubba's avatar
Gus Grubba committed
25 26 27 28 29
    if(TaisyncHandler::close()) {
        qCDebug(TaisyncLog) << "Close Taisync Telemetry";
        return true;
    }
    return false;
30 31 32
}

//-----------------------------------------------------------------------------
33
bool TaisyncTelemetry::start()
34
{
Gus Grubba's avatar
Gus Grubba committed
35
    qCDebug(TaisyncLog) << "Start Taisync Telemetry";
Gus Grubba's avatar
Gus Grubba committed
36
    return _start(TAISYNC_TELEM_PORT);
37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
}

//-----------------------------------------------------------------------------
void
TaisyncTelemetry::writeBytes(QByteArray bytes)
{
    if(_tcpSocket) {
        _tcpSocket->write(bytes);
    }
}

//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_newConnection()
{
    TaisyncHandler::_newConnection();
Gus Grubba's avatar
Gus Grubba committed
53
    qCDebug(TaisyncLog) << "New Taisync Temeletry Connection";
54 55 56 57 58 59 60 61 62 63 64
}

//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_readBytes()
{
    while(_tcpSocket->bytesAvailable()) {
        QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
        emit bytesReady(bytesIn);
    }
}