Skip to content

Commit

Permalink
Mavlink: Improve Image Transmission Protocol Handling
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Sep 22, 2024
1 parent c07238d commit daf0344
Show file tree
Hide file tree
Showing 36 changed files with 265 additions and 395 deletions.
2 changes: 1 addition & 1 deletion custom-example/qgroundcontrol.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@
<file alias="PlanViewSettings.qml">../src/UI/preferences/PlanViewSettings.qml</file>
<file alias="PlanViewToolBar.qml">../src/UI/toolbar/PlanViewToolBar.qml</file>
<file alias="PreFlightCheckList.qml">../src/FlightDisplay/PreFlightCheckList.qml</file>
<file alias="PX4FlowSensor.qml">../src/VehicleSetup/PX4FlowSensor.qml</file>
<file alias="OpticalFlowSensor.qml">../src/VehicleSetup/OpticalFlowSensor.qml</file>
<file alias="VerticalCompassAttitude.qml">../src/FlightMap/Widgets/VerticalCompassAttitude.qml</file>
<file alias="HorizontalCompassAttitude.qml">../src/FlightMap/Widgets/HorizontalCompassAttitude.qml</file>
<file alias="QGroundControl/Controls/AnalyzePage.qml">../src/AnalyzeView/AnalyzePage.qml</file>
Expand Down
2 changes: 1 addition & 1 deletion qgroundcontrol.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@
<file alias="PlanViewSettings.qml">src/UI/preferences/PlanViewSettings.qml</file>
<file alias="PlanViewToolBar.qml">src/UI/toolbar/PlanViewToolBar.qml</file>
<file alias="PreFlightCheckList.qml">src/FlightDisplay/PreFlightCheckList.qml</file>
<file alias="PX4FlowSensor.qml">src/VehicleSetup/PX4FlowSensor.qml</file>
<file alias="OpticalFlowSensor.qml">src/VehicleSetup/OpticalFlowSensor.qml</file>
<file alias="VerticalCompassAttitude.qml">src/FlightMap/Widgets/VerticalCompassAttitude.qml</file>
<file alias="HorizontalCompassAttitude.qml">src/FlightMap/Widgets/HorizontalCompassAttitude.qml</file>
<file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
Expand Down
3 changes: 1 addition & 2 deletions src/Comms/LinkInterface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,9 @@

QGC_LOGGING_CATEGORY(LinkInterfaceLog, "LinkInterfaceLog")

LinkInterface::LinkInterface(SharedLinkConfigurationPtr &config, bool isPX4Flow, QObject *parent)
LinkInterface::LinkInterface(SharedLinkConfigurationPtr &config, QObject *parent)
: QThread(parent)
, _config(config)
, _isPX4Flow(isPX4Flow)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
}
Expand Down
6 changes: 1 addition & 5 deletions src/Comms/LinkInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@ class LinkInterface : public QThread
{
Q_OBJECT

Q_PROPERTY(bool isPX4Flow READ isPX4Flow CONSTANT)

friend class LinkManager;

public:
Expand All @@ -40,7 +38,6 @@ class LinkInterface : public QThread
const SharedLinkConfigurationPtr linkConfiguration() const { return _config; }
uint8_t mavlinkChannel() const;
bool mavlinkChannelIsSet() const;
bool isPX4Flow() const { return _isPX4Flow; }
bool decodedFirstMavlinkPacket(void) const { return _decodedFirstMavlinkPacket; }
void setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { _decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; }
void writeBytesThreadSafe(const char *bytes, int length);
Expand All @@ -58,7 +55,7 @@ class LinkInterface : public QThread

protected:
/// Links are only created by LinkManager so constructor is not public
LinkInterface(SharedLinkConfigurationPtr &config, bool isPX4Flow = false, QObject *parent = nullptr);
LinkInterface(SharedLinkConfigurationPtr &config, QObject *parent = nullptr);

/// Called by the LinkManager during LinkInterface construction instructing the link to setup channels.
/// Default implementation allocates a single channel. But some link types (such as MockLink) need more than one.
Expand All @@ -80,7 +77,6 @@ private slots:

uint8_t _mavlinkChannel = std::numeric_limits<uint8_t>::max();
bool _decodedFirstMavlinkPacket = false;
bool _isPX4Flow = false;
int _vehicleReferenceCount = 0;
bool _signingSignatureFailure = false;
};
Expand Down
16 changes: 3 additions & 13 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -109,17 +109,15 @@ void LinkManager::createConnectedLink(const LinkConfiguration *config)
}
}

bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config, bool isPX4Flow)
bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config)
{
SharedLinkInterfacePtr link = nullptr;

switch(config->type()) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
link = std::make_shared<SerialLink>(config, isPX4Flow);
link = std::make_shared<SerialLink>(config);
break;
#else
Q_UNUSED(isPX4Flow)
#endif
case LinkConfiguration::TypeUdp:
link = std::make_shared<UDPLink>(config);
Expand Down Expand Up @@ -845,9 +843,6 @@ void LinkManager::_addSerialAutoConnectLink()
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
pSerialConfig->setUsbDirect(true);
break;
case QGCSerialPortInfo::BoardTypePX4Flow:
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
break;
case QGCSerialPortInfo::BoardTypeSiKRadio:
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
break;
Expand All @@ -872,7 +867,7 @@ void LinkManager::_addSerialAutoConnectLink()
pSerialConfig->setAutoConnect(true);

SharedLinkConfigurationPtr sharedConfig(pSerialConfig);
createConnectedLink(sharedConfig, boardType == QGCSerialPortInfo::BoardTypePX4Flow);
createConnectedLink(sharedConfig);
}
}
}
Expand All @@ -894,11 +889,6 @@ bool LinkManager::_allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardT
return true;
}
break;
case QGCSerialPortInfo::BoardTypePX4Flow:
if (_autoConnectSettings->autoConnectPX4Flow()->rawValue().toBool()) {
return true;
}
break;
case QGCSerialPortInfo::BoardTypeSiKRadio:
if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
return true;
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/LinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class LinkManager : public QGCTool
void setConnectionsAllowed() { _connectionsSuspended = false; }

/// Creates, connects (and adds) a link based on the given configuration instance.
bool createConnectedLink(SharedLinkConfigurationPtr &config, bool isPX4Flow = false);
bool createConnectedLink(SharedLinkConfigurationPtr &config);

/// Returns pointer to the mavlink forwarding link, or nullptr if it does not exist
SharedLinkInterfacePtr mavlinkForwardingLink();
Expand Down
43 changes: 0 additions & 43 deletions src/Comms/MockLink/MockLink.Parameter.MetaData.json
Original file line number Diff line number Diff line change
Expand Up @@ -18198,49 +18198,6 @@
"shortDesc": "External I2C probe",
"longDesc": "Probe for optional external I2C devices."
},
{
"name": "SENS_FLOW_ROT",
"type": "Int32",
"default": 6,
"group": "Sensors",
"shortDesc": "PX4Flow board rotation",
"longDesc": "This parameter defines the yaw rotation of the PX4FLOW board relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. The recommneded installation default for the PX4FLOW board is with the Y axis forward (270 deg yaw).",
"rebootRequired": true,
"values": [
{
"value": 0,
"description": "No rotation"
},
{
"value": 1,
"description": "Yaw 45\u00b0"
},
{
"value": 2,
"description": "Yaw 90\u00b0"
},
{
"value": 3,
"description": "Yaw 135\u00b0"
},
{
"value": 4,
"description": "Yaw 180\u00b0"
},
{
"value": 5,
"description": "Yaw 225\u00b0"
},
{
"value": 6,
"description": "Yaw 270\u00b0"
},
{
"value": 7,
"description": "Yaw 315\u00b0"
}
]
},
{
"name": "SENS_GPS_MASK",
"type": "Int32",
Expand Down
3 changes: 0 additions & 3 deletions src/Comms/QGCSerialPortInfo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -237,8 +237,6 @@ QString QGCSerialPortInfo::_boardTypeToString(BoardType_t boardType)
return QStringLiteral("Pixhawk");
case BoardTypeSiKRadio:
return QStringLiteral("SiK Radio");
case BoardTypePX4Flow:
return QStringLiteral("PX4 Flow");
case BoardTypeOpenPilot:
return QStringLiteral("OpenPilot");
case BoardTypeRTKGPS:
Expand Down Expand Up @@ -305,7 +303,6 @@ bool QGCSerialPortInfo::canFlash() const
if (getBoardInfo(boardType, name)) {
switch(boardType) {
case QGCSerialPortInfo::BoardTypePixhawk:
case QGCSerialPortInfo::BoardTypePX4Flow:
case QGCSerialPortInfo::BoardTypeSiKRadio:
return true;
default:
Expand Down
2 changes: 0 additions & 2 deletions src/Comms/QGCSerialPortInfo.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@ class QGCSerialPortInfo : public QSerialPortInfo
enum BoardType_t {
BoardTypePixhawk,
BoardTypeSiKRadio,
BoardTypePX4Flow,
BoardTypeOpenPilot,
BoardTypeRTKGPS,
BoardTypeUnknown
Expand Down Expand Up @@ -68,7 +67,6 @@ class QGCSerialPortInfo : public QSerialPortInfo
};
static constexpr const BoardClassString2BoardType_t _rgBoardClass2BoardType[BoardTypeUnknown] = {
{ "Pixhawk", QGCSerialPortInfo::BoardTypePixhawk },
{ "PX4 Flow", QGCSerialPortInfo::BoardTypePX4Flow },
{ "RTK GPS", QGCSerialPortInfo::BoardTypeRTKGPS },
{ "SiK Radio", QGCSerialPortInfo::BoardTypeSiKRadio },
{ "OpenPilot", QGCSerialPortInfo::BoardTypeOpenPilot },
Expand Down
4 changes: 2 additions & 2 deletions src/Comms/SerialLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@

QGC_LOGGING_CATEGORY(SerialLinkLog, "SerialLinkLog")

SerialLink::SerialLink(SharedLinkConfigurationPtr& config, bool isPX4Flow)
: LinkInterface(config, isPX4Flow)
SerialLink::SerialLink(SharedLinkConfigurationPtr& config)
: LinkInterface(config)
, _serialConfig(qobject_cast<const SerialConfiguration*>(config.get()))
{
qRegisterMetaType<QSerialPort::SerialPortError>();
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/SerialLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ class SerialLink : public LinkInterface
Q_OBJECT

public:
SerialLink(SharedLinkConfigurationPtr& config, bool isPX4Flow = false);
SerialLink(SharedLinkConfigurationPtr& config);
virtual ~SerialLink();

// LinkInterface overrides
Expand Down
3 changes: 0 additions & 3 deletions src/Comms/USBBoardInfo.json
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,6 @@
{ "vendorID": 13735, "productID": 1, "boardClass": "Pixhawk", "name": "ThePeach FCC-K1" },
{ "vendorID": 13735, "productID": 2, "boardClass": "Pixhawk", "name": "ThePeach FCC-R1" },

{ "vendorID": 9900, "productID": 21, "boardClass": "PX4 Flow", "name": "PX4 Flow" },

{ "vendorID": 1027, "productID": 24597, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "3DR Radio" },
{ "vendorID": 1027, "productID": 24577, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "3DR Radio on FTDI" },
{ "vendorID": 4292, "productID": 60000, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "SILabs Radio" },
Expand Down Expand Up @@ -96,7 +94,6 @@
{ "regExp": "^mRoControlZeroF7", "boardClass": "Pixhawk" },
{ "regExp": "^ARK FMU v6X.x$", "boardClass": "Pixhawk" },
{ "regExp": "^ARK BL FMU v6X.x$", "boardClass": "Pixhawk" },
{ "regExp": "PX4.*Flow", "boardClass": "PX4 Flow" },
{ "regExp": "^FT231X USB UART$", "boardClass": "SiK Radio" },
{ "regExp": "USB UART$", "boardClass": "SiK Radio", "androidOnly": true, "comment": "Very broad fallback, too dangerous for non-android" }
],
Expand Down
Loading

0 comments on commit daf0344

Please sign in to comment.