diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 0d093cfa6642335c01bf9afced6ef0f10581c180..b2b18d2e91f68b02f294b8effa0e55b8fa3bf160 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -131,10 +131,6 @@ public: /// set into the link when it is added to LinkManager uint8_t getMavlinkChannel(void) const { Q_ASSERT(_mavlinkChannelSet); return _mavlinkChannel; } - /// @return true: "sh /etc/init.d/rc.usb" must be sent on link to start mavlink - virtual bool requiresUSBMavlinkStart(void) const { return false; } - - // These are left unimplemented in order to cause linker errors which indicate incorrect usage of // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. bool connect(void); diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 5f8bc4a291a2643bb570946a93aed866f2fbb414..a3a5b5d14e9101d5446c7529b1ab1e9d0443c481 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -189,8 +189,6 @@ void LinkManager::_addLink(LinkInterface* link) connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); - connect(link, &LinkInterface::connected, _mavlinkProtocol, &MAVLinkProtocol::linkConnected); - connect(link, &LinkInterface::disconnected, _mavlinkProtocol, &MAVLinkProtocol::linkDisconnected); _mavlinkProtocol->resetMetadataForLink(link); diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 0ece393fa4a7bfba8e36a93b9dd9a960941df088..18f8602013dcb63e05ee44bd4aa6590870f44841 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -173,41 +173,6 @@ void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link) currLossCounter[channel] = 0; } -void MAVLinkProtocol::linkConnected(void) -{ - LinkInterface* link = qobject_cast(QObject::sender()); - Q_ASSERT(link); - - _linkStatusChanged(link, true); -} - -void MAVLinkProtocol::linkDisconnected(void) -{ - LinkInterface* link = qobject_cast(QObject::sender()); - Q_ASSERT(link); - - _linkStatusChanged(link, false); -} - -void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) -{ - qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected; - Q_ASSERT(link); - - if (connected) { - if (link->requiresUSBMavlinkStart()) { - // Send command to start MAVLink - // XXX hacky but safe - // Start NSH - const char init[] = {0x0d, 0x0d, 0x0d, 0x0d}; - link->writeBytes(init, sizeof(init)); - const char* cmd = "sh /etc/init.d/rc.usb\n"; - link->writeBytes(cmd, strlen(cmd)); - link->writeBytes(init, 4); - } - } -} - /** * This method parses all incoming bytes and constructs a MAVLink packet. * It can handle multiple links in parallel, as each link has it's own buffer/ diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index b24491ee6f5c47063fe8c43d608edf4ea4d72d89..c3de7bc1c4b7d235c629e4a65187c1f064ed6b33 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -155,9 +155,6 @@ public slots: /** @brief Receive bytes from a communication interface */ void receiveBytes(LinkInterface* link, QByteArray b); - void linkConnected(void); - void linkDisconnected(void); - /** @brief Set the rate at which heartbeats are emitted */ void setHeartbeatRate(int rate); /** @brief Set the system id of this application */ @@ -285,7 +282,6 @@ private slots: void _vehicleCountChanged(int count); private: - void _linkStatusChanged(LinkInterface* link, bool connected); void _sendMessage(mavlink_message_t message); void _sendMessage(LinkInterface* link, mavlink_message_t message); void _sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 4f1b250874f3b9bee310137aa4d467c5d58e6cb4..b64be4932c7456d1ac6b8ea7c921685d6b964ec5 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -377,15 +377,6 @@ LinkConfiguration* SerialLink::getLinkConfiguration() return _config; } -bool SerialLink::requiresUSBMavlinkStart(void) const -{ - if (_port) { - return QGCSerialPortInfo(*_port).boardTypePixhawk(); - } else { - return false; - } -} - //-------------------------------------------------------------------------- //-- SerialConfiguration diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index 12b360103768058aa0a32a660fdc8cbbf403ba11..7f43d62aa28431cd2ed79dc28e2f046636c5c254 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -146,7 +146,6 @@ public: void requestReset(); bool isConnected() const; qint64 getConnectionSpeed() const; - bool requiresUSBMavlinkStart(void) const; // These are left unimplemented in order to cause linker errors which indicate incorrect usage of // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.