Browse Source

ArduPilot support for new FRAME_CLASS, FRAME_TYPE

QGC4.4
Don Gagne 8 years ago
parent
commit
cf97c4a0d7
  1. 19
      src/AutoPilotPlugins/APM/APMAirframeComponent.cc
  2. 5
      src/AutoPilotPlugins/APM/APMAirframeComponent.h
  3. 43
      src/AutoPilotPlugins/APM/APMAirframeComponent.qml
  4. 15
      src/AutoPilotPlugins/APM/APMAirframeComponentController.cc
  5. 5
      src/AutoPilotPlugins/APM/APMAirframeComponentController.h
  6. 27
      src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml
  7. 4
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  8. 6762
      src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml
  9. 1
      src/FirmwarePlugin/APM/APMResources.qrc

19
src/AutoPilotPlugins/APM/APMAirframeComponent.cc

@ -11,17 +11,28 @@ @@ -11,17 +11,28 @@
#include "ArduCopterFirmwarePlugin.h"
#include "ParameterManager.h"
const char* APMAirframeComponent::_oldFrameParam = "FRAME";
const char* APMAirframeComponent::_newFrameParam = "FRAME_CLASS";
APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent)
, _requiresFrameSetup(false)
, _name("Airframe")
{
if (qobject_cast<ArduCopterFirmwarePlugin*>(_vehicle->firmwarePlugin()) != NULL) {
ParameterManager* paramMgr = _vehicle->parameterManager();
_requiresFrameSetup = true;
if (paramMgr->parameterExists(FactSystem::defaultComponentId, _oldFrameParam)) {
_useNewFrameParam = false;
_frameParamFact = paramMgr->getParameter(FactSystem::defaultComponentId, _oldFrameParam);
MAV_TYPE vehicleType = vehicle->vehicleType();
if (vehicleType == MAV_TYPE_TRICOPTER || vehicleType == MAV_TYPE_HELICOPTER) {
_requiresFrameSetup = false;
}
} else {
_useNewFrameParam = true;
_frameParamFact = paramMgr->getParameter(FactSystem::defaultComponentId, _newFrameParam);
}
}
}
@ -49,7 +60,11 @@ bool APMAirframeComponent::requiresSetup(void) const @@ -49,7 +60,11 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const
{
if (_requiresFrameSetup) {
return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
if (_useNewFrameParam) {
return _frameParamFact->rawValue().toInt() > 0;
} else {
return _frameParamFact->rawValue().toInt() >= 0;
}
} else {
return true;
}
@ -60,7 +75,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const @@ -60,7 +75,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const
QStringList list;
if (_requiresFrameSetup) {
list << QStringLiteral("FRAME");
list << (_useNewFrameParam ? _newFrameParam : _oldFrameParam);
}
return list;

5
src/AutoPilotPlugins/APM/APMAirframeComponent.h

@ -36,6 +36,11 @@ public: @@ -36,6 +36,11 @@ public:
private:
bool _requiresFrameSetup; ///< true: FRAME parameter must be set
const QString _name;
Fact* _frameParamFact;
bool _useNewFrameParam;
static const char* _oldFrameParam;
static const char* _newFrameParam;
};
#endif

43
src/AutoPilotPlugins/APM/APMAirframeComponent.qml

@ -14,6 +14,7 @@ import QtQuick.Dialogs 1.2 @@ -14,6 +14,7 @@ import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0
@ -21,10 +22,13 @@ import QGroundControl.ScreenTools 1.0 @@ -21,10 +22,13 @@ import QGroundControl.ScreenTools 1.0
SetupPage {
id: airframePage
pageComponent: airframePageComponent
pageComponent: _useOldFrameParam ? oldFramePageComponent: newFramePageComponent
property real _margins: ScreenTools.defaultFontPixelWidth
property Fact _frame: controller.getParameterFact(-1, "FRAME")
property bool _useOldFrameParam: controller.parameterExists(-1, "FRAME")
property Fact _oldFrameParam: controller.getParameterFact(-1, "FRAME", false)
property Fact _newFrameParam: controller.getParameterFact(-1, "FRAME_CLASS", false)
property Fact _frameTypeParam: controller.getParameterFact(-1, "FRAME_TYPE", false)
APMAirframeComponentController {
id: controller
@ -88,7 +92,7 @@ SetupPage { @@ -88,7 +92,7 @@ SetupPage {
}
Component {
id: airframePageComponent
id: oldFramePageComponent
Column {
width: availableWidth
@ -129,5 +133,36 @@ SetupPage { @@ -129,5 +133,36 @@ SetupPage {
}
}
} // Column
} // Component - pageComponent
} // Component - oldFramePageComponent
Component {
id: newFramePageComponent
Grid {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margins
columns: 2
QGCLabel {
text: qsTr("Frame Class:")
}
FactComboBox {
fact: _newFrameParam
indexModel: false
width: ScreenTools.defaultFontPixelWidth * 15
}
QGCLabel {
text: qsTr("Frame Type:")
}
FactComboBox {
fact: _frameTypeParam
indexModel: false
width: ScreenTools.defaultFontPixelWidth * 15
}
}
}
} // SetupPage

15
src/AutoPilotPlugins/APM/APMAirframeComponentController.cc

@ -28,18 +28,25 @@ @@ -28,18 +28,25 @@
bool APMAirframeComponentController::_typesRegistered = false;
const char* APMAirframeComponentController::_oldFrameParam = "FRAME";
const char* APMAirframeComponentController::_newFrameParam = "FRAME_CLASS";
APMAirframeComponentController::APMAirframeComponentController(void) :
_airframeTypesModel(new QmlObjectListModel(this))
{
if (!_typesRegistered) {
_typesRegistered = true;
qmlRegisterUncreatableType<APMAirframeType>("QGroundControl.Controllers", 1, 0, "APMAiframeType", QStringLiteral("Can only reference APMAirframeType"));
qmlRegisterUncreatableType<APMAirframe>("QGroundControl.Controllers", 1, 0, "APMAiframe", QStringLiteral("Can only reference APMAirframe"));
qmlRegisterUncreatableType<APMAirframeType>("QGroundControl.Controllers", 1, 0, "APMAirframeType", QStringLiteral("Can only reference APMAirframeType"));
}
_fillAirFrames();
Fact *frame = getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"));
connect(frame, &Fact::vehicleUpdated, this, &APMAirframeComponentController::_factFrameChanged);
Fact* frame;
if (parameterExists(FactSystem::defaultComponentId, _oldFrameParam)) {
frame = getParameterFact(FactSystem::defaultComponentId, _oldFrameParam);
} else {
frame = getParameterFact(FactSystem::defaultComponentId, _newFrameParam);
}
connect(frame, &Fact::rawValueChanged, this, &APMAirframeComponentController::_factFrameChanged);
_factFrameChanged(frame->rawValue());
}

5
src/AutoPilotPlugins/APM/APMAirframeComponentController.h

@ -71,9 +71,12 @@ private slots: @@ -71,9 +71,12 @@ private slots:
private:
void _loadParametersFromDownloadFile(const QString& downloadedParamFile);
static bool _typesRegistered;
APMAirframeType *_currentAirframeType;
QmlObjectListModel *_airframeTypesModel;
static bool _typesRegistered;
static const char* _oldFrameParam;
static const char* _newFrameParam;
};
class APMAirframe : public QObject

27
src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml

@ -18,18 +18,31 @@ FactPanel { @@ -18,18 +18,31 @@ FactPanel {
factPanel: panel
}
property Fact sysIdFact: controller.getParameterFact(-1, "FRAME")
property bool _useOldFrameParam: controller.parameterExists(-1, "FRAME")
property Fact _oldFrameParam: controller.getParameterFact(-1, "FRAME", false)
property Fact _newFrameParam: controller.getParameterFact(-1, "FRAME_CLASS", false)
property Fact _frameTypeParam: controller.getParameterFact(-1, "FRAME_TYPE", false)
Column {
anchors.fill: parent
VehicleSummaryRow {
labelText: qsTr("Frame Type:")
valueText: controller.currentAirframeTypeName() + " " + _oldFrameParam.enumStringValue
visible: _useOldFrameParam
}
VehicleSummaryRow {
labelText: qsTr("Frame Class:")
valueText: _newFrameParam.enumStringValue
visible: !_useOldFrameParam
}
VehicleSummaryRow {
id: nameRow;
labelText: qsTr("Frame Type:")
valueText: controller.currentAirframeTypeName() + " " + (sysIdFact.valueString === "0" ? "Plus"
: sysIdFact.valueString === "1" ? "X"
: sysIdFact.valueString === "2" ? "V"
: sysIdFact.valueString == "3" ? "H"
: /* Fact.value == 10 */ "New Y6");
valueText: _frameTypeParam.enumStringValue
visible: !_useOldFrameParam
}

4
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -744,8 +744,10 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) @@ -744,8 +744,10 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_HELICOPTER:
if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 3)) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml");
} else {
} else if (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() == 4) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml");
} else {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
}
case MAV_TYPE_FIXED_WING:
if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 3)) {

6762
src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml

File diff suppressed because it is too large Load Diff

1
src/FirmwarePlugin/APM/APMResources.qrc

@ -45,6 +45,7 @@ @@ -45,6 +45,7 @@
<file alias="APMParameterFactMetaData.Plane.3.7.xml">APMParameterFactMetaData.Plane.3.7.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.3.xml">APMParameterFactMetaData.Copter.3.3.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.4.xml">APMParameterFactMetaData.Copter.3.4.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.5.xml">APMParameterFactMetaData.Copter.3.5.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.0.xml">APMParameterFactMetaData.Rover.3.0.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file>
<file alias="CopterGeoFenceEditor.qml">CopterGeoFenceEditor.qml</file>

Loading…
Cancel
Save