@ -29,6 +29,8 @@
@@ -29,6 +29,8 @@
# include "QGCMAVLink.h"
# include "QGCApplication.h"
# include <QTcpSocket>
QGC_LOGGING_CATEGORY ( APMFirmwarePluginLog , " APMFirmwarePluginLog " )
static const QRegExp APM_COPTER_REXP ( " ^(ArduCopter|APM:Copter) " ) ;
@ -49,6 +51,8 @@ static const QString MIN_COPTER_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Copter V
@@ -49,6 +51,8 @@ static const QString MIN_COPTER_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Copter V
static const QString MIN_PLANE_VERSION_WITH_CORRECT_SEVERITY_MSGS ( " APM:Plane V3.4.0 " ) ;
static const QString MIN_ROVER_VERSION_WITH_CORRECT_SEVERITY_MSGS ( " APM:Rover V2.6.0 " ) ;
const char * APMFirmwarePlugin : : _artooIP = " 10.1.1.1 " ; ///< IP address of ARTOO controller
const int APMFirmwarePlugin : : _artooVideoHandshakePort = 5502 ; ///< Port for video handshake on ARTOO controller
/*
* @ brief APMFirmwareVersion is a small class to represent the firmware version
@ -372,11 +376,21 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
@@ -372,11 +376,21 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
// The following messages are incorrectly labeled as warning message.
// Fixed in newer firmware (unreleased at this point), but still in older firmware.
if ( messageText . contains ( APM_COPTER_REXP ) | | messageText . contains ( APM_SOLO_REXP ) | | messageText . contains ( APM_ PLANE_REXP ) | | messageText . contains ( APM_ROVER_REXP ) | |
if ( messageText . contains ( APM_COPTER_REXP ) | | messageText . contains ( APM_PLANE_REXP ) | | messageText . contains ( APM_ROVER_REXP ) | |
messageText . contains ( APM_PX4NUTTX_REXP ) | | messageText . contains ( APM_FRAME_REXP ) | | messageText . contains ( APM_SYSID_REXP ) ) {
_setInfoSeverity ( message ) ;
}
if ( messageText . contains ( APM_SOLO_REXP ) ) {
qDebug ( ) < < " Found Solo " ;
// Fix up severity
_setInfoSeverity ( message ) ;
// Start TCP video handshake with ARTOO
_soloVideoHandshake ( vehicle ) ;
}
// ArduPilot PreArm messages can come across very frequently especially on Solo, which seems to send them once a second.
// Filter them out if they come too quickly.
if ( messageText . startsWith ( " PreArm " ) ) {
@ -599,3 +613,18 @@ void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle)
@@ -599,3 +613,18 @@ void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle)
// Best we can do in this case
vehicle - > setFlightMode ( " Loiter " ) ;
}
void APMFirmwarePlugin : : _soloVideoHandshake ( Vehicle * vehicle )
{
Q_UNUSED ( vehicle ) ;
QTcpSocket * socket = new QTcpSocket ( ) ;
socket - > connectToHost ( _artooIP , _artooVideoHandshakePort ) ;
QObject : : connect ( socket , static_cast < void ( QTcpSocket : : * ) ( QAbstractSocket : : SocketError ) > ( & QTcpSocket : : error ) , this , & APMFirmwarePlugin : : _artooSocketError ) ;
}
void APMFirmwarePlugin : : _artooSocketError ( QAbstractSocket : : SocketError socketError )
{
qgcApp ( ) - > showMessage ( tr ( " Error during Solo video link setup: %1 " ) . arg ( socketError ) ) ;
}