TaisyncTelemetry.cc 3.49 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * 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 30 31 32 33
    if(_mavlinkChannel >= 0) {
        qgcApp()->toolbox()->linkManager()->_freeMavlinkChannel(_mavlinkChannel);
        _mavlinkChannel = -1;
    }
    if(TaisyncHandler::close()) {
        qCDebug(TaisyncLog) << "Close Taisync Telemetry";
        return true;
    }
    return false;
34 35 36
}

//-----------------------------------------------------------------------------
37
bool TaisyncTelemetry::start()
38
{
Gus Grubba's avatar
Gus Grubba committed
39 40 41 42 43 44 45 46 47 48
    qCDebug(TaisyncLog) << "Start Taisync Telemetry";
    if(_start(TAISYNC_TELEM_PORT)) {
        _mavlinkChannel = qgcApp()->toolbox()->linkManager()->_reserveMavlinkChannel();
        _heartbeatTimer.setInterval(1000);
        _heartbeatTimer.setSingleShot(false);
        connect(&_heartbeatTimer, &QTimer::timeout, this, &TaisyncTelemetry::_sendGCSHeartbeat);
        _heartbeatTimer.start();
        return true;
    }
    return false;
49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64
}

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

//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_newConnection()
{
    TaisyncHandler::_newConnection();
Gus Grubba's avatar
Gus Grubba committed
65
    qCDebug(TaisyncLog) << "New Taisync Temeletry Connection";
66 67 68 69 70 71
}

//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_readBytes()
{
Gus Grubba's avatar
Gus Grubba committed
72
    _heartbeatTimer.stop();
73 74 75 76 77
    while(_tcpSocket->bytesAvailable()) {
        QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
        emit bytesReady(bytesIn);
    }
}
Gus Grubba's avatar
Gus Grubba committed
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

//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_sendGCSHeartbeat()
{
    //-- TODO: This is temporary. We should not have to send out heartbeats for a link to start.
    if(_tcpSocket) {
        MAVLinkProtocol* pMavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();
        if(pMavlinkProtocol && _mavlinkChannel >= 0) {
            qCDebug(TaisyncLog) << "Taisync heartbeat out";
            mavlink_message_t message;
            mavlink_msg_heartbeat_pack_chan(
                static_cast<uint8_t>(pMavlinkProtocol->getSystemId()),
                static_cast<uint8_t>(pMavlinkProtocol->getComponentId()),
                static_cast<uint8_t>(_mavlinkChannel),
                &message,
                MAV_TYPE_GCS,            // MAV_TYPE
                MAV_AUTOPILOT_INVALID,   // MAV_AUTOPILOT
                MAV_MODE_MANUAL_ARMED,   // MAV_MODE
                0,                       // custom mode
                MAV_STATE_ACTIVE);       // MAV_STATE
            uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
            int len = mavlink_msg_to_send_buffer(buffer, &message);
            _tcpSocket->write(reinterpret_cast<const char*>(buffer), len);
        }
    }
}