diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 8c1215bea92cfd7c1047796ecdb3340da9c68a7e..9b725e3e6c300c4d9c049593309684fb1f2220d1 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -366,6 +366,8 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess supportedMinorNumber = 4; break; case MAV_TYPE_QUADROTOR: + // Start TCP video handshake with ARTOO in case it's a Solo running ArduPilot firmware + _soloVideoHandshake(vehicle, false /* originalSoloFirmware */); case MAV_TYPE_COAXIAL: case MAV_TYPE_HELICOPTER: case MAV_TYPE_SUBMARINE: @@ -420,7 +422,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess _setInfoSeverity(message); // Start TCP video handshake with ARTOO - _soloVideoHandshake(vehicle); + _soloVideoHandshake(vehicle, true /* originalSoloFirmware */); } else if (messageText.contains(APM_FRAME_REXP)) { // We need to parse the Frame: message in order to determine whether the motors are coaxial or not QRegExp frameTypeRegex("^Frame: (\\S*)"); @@ -750,14 +752,16 @@ bool APMFirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const return vehicle->flightMode() == "Guided"; } -void APMFirmwarePlugin::_soloVideoHandshake(Vehicle* vehicle) +void APMFirmwarePlugin::_soloVideoHandshake(Vehicle* vehicle, bool originalSoloFirmware) { Q_UNUSED(vehicle); QTcpSocket* socket = new QTcpSocket(); socket->connectToHost(_artooIP, _artooVideoHandshakePort); - QObject::connect(socket, static_cast(&QTcpSocket::error), this, &APMFirmwarePlugin::_artooSocketError); + if (originalSoloFirmware) { + QObject::connect(socket, static_cast(&QTcpSocket::error), this, &APMFirmwarePlugin::_artooSocketError); + } } void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketError) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 03762240a9161e5bfc8595b3b13fc89c4bb0acaf..54ae7245472581f3db9c85acb59dd93e68d472be 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -125,7 +125,7 @@ private: bool _handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message); void _handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message); void _handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message); - void _soloVideoHandshake(Vehicle* vehicle); + void _soloVideoHandshake(Vehicle* vehicle, bool originalSoloFirmware); bool _guidedModeTakeoff(Vehicle* vehicle, double altitudeRel); // Any instance data here must be global to all vehicles