Unverified Commit 64eebbef authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7392 from DonLakeFlyer/master

ArduPilot: Rover Frame setup support, Copter advanced tuning
parents 2c32b463 696bd66a
......@@ -6,6 +6,8 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* ArduPilot: Copter - Advanced Tuning support
* ArduPilot: Rover - Frame setup support
* ArduPilot: Copter - Update support to 3.5+
* ArduPilot: Plane - Update support to 3.8+
* ArduPilot: Rover - Update support to 3.4+
......
......@@ -11,28 +11,22 @@
#include "ArduCopterFirmwarePlugin.h"
#include "ParameterManager.h"
const char* APMAirframeComponent::_oldFrameParam = "FRAME";
const char* APMAirframeComponent::_newFrameParam = "FRAME_CLASS";
const char* APMAirframeComponent::_frameClassParam = "FRAME_CLASS";
APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent)
, _requiresFrameSetup(false)
, _name(tr("Airframe"))
: VehicleComponent (vehicle, autopilot, parent)
, _requiresFrameSetup (false)
, _name (tr("Frame"))
{
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);
ParameterManager* paramMgr = vehicle->parameterManager();
if (paramMgr->parameterExists(FactSystem::defaultComponentId, _frameClassParam)) {
_frameClassFact = paramMgr->getParameter(FactSystem::defaultComponentId, _frameClassParam);
if (vehicle->vehicleType() != MAV_TYPE_HELICOPTER) {
_requiresFrameSetup = true;
}
} else {
_frameClassFact = nullptr;
}
}
......@@ -43,7 +37,7 @@ QString APMAirframeComponent::name(void) const
QString APMAirframeComponent::description(void) const
{
return tr("Airframe Setup is used to select the airframe which matches your vehicle.");
return tr("Frame Setup is used to select the airframe which matches your vehicle.");
}
QString APMAirframeComponent::iconResource(void) const
......@@ -59,11 +53,7 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const
{
if (_requiresFrameSetup) {
if (_useNewFrameParam) {
return _frameParamFact->rawValue().toInt() > 0;
} else {
return _frameParamFact->rawValue().toInt() >= 0;
}
return _frameClassFact->rawValue().toInt() != 0;
} else {
return true;
}
......@@ -74,7 +64,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const
QStringList list;
if (_requiresFrameSetup) {
list << (_useNewFrameParam ? _newFrameParam : _oldFrameParam);
list << _frameClassParam;
}
return list;
......
......@@ -35,11 +35,9 @@ public:
private:
bool _requiresFrameSetup; ///< true: FRAME parameter must be set
const QString _name;
Fact* _frameParamFact;
bool _useNewFrameParam;
Fact* _frameClassFact;
static const char* _oldFrameParam;
static const char* _newFrameParam;
static const char* _frameClassParam;
};
#endif
......@@ -31,12 +31,13 @@ SetupPage {
id: mainColumn
width: availableWidth
property real _minW: ScreenTools.defaultFontPixelWidth * 20
property real _boxWidth: _minW
property real _boxSpace: ScreenTools.defaultFontPixelWidth
property real _margins: ScreenTools.defaultFontPixelWidth
property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS")
property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE")
property real _minW: ScreenTools.defaultFontPixelWidth * 20
property real _boxWidth: _minW
property real _boxSpace: ScreenTools.defaultFontPixelWidth
property real _margins: ScreenTools.defaultFontPixelWidth
property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS")
property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE", false) // FRAME_TYPE is not available on all Rover versions
property bool _frameTypeAvailable: controller.parameterExists(-1, "FRAME_TYPE")
readonly property real spacerHeight: ScreenTools.defaultFontPixelHeight
......@@ -71,7 +72,9 @@ SetupPage {
Layout.fillWidth: true
text: (_frameClass.rawValue === 0 ?
qsTr("Airframe is currently not set.") :
qsTr("Currently set to frame class '%1' and frame type '%2'.").arg(_frameClass.enumStringValue).arg(_frameType.enumStringValue)) +
qsTr("Currently set to frame class '%1'").arg(_frameClass.enumStringValue) +
(_frameTypeAvailable ? qsTr(" and frame type '%2'").arg(_frameType.enumStringValue) : "") +
qsTr(".", "period for end of sentence")) +
qsTr(" To change this configuration, select the desired frame class below and frame type.")
font.family: ScreenTools.demiboldFontFamily
wrapMode: Text.WordWrap
......
......@@ -13,6 +13,8 @@
#include "QGCApplication.h"
#include "QGCFileDownload.h"
#include "ParameterManager.h"
#include "ArduCopterFirmwarePlugin.h"
#include "ArduRoverFirmwarePlugin.h"
#include <QVariant>
#include <QQmlProperty>
......@@ -21,8 +23,7 @@
#include <QJsonParseError>
#include <QJsonObject>
// These should match the FRAME_CLASS parameter enum meta data
// These should match the ArduCopter FRAME_CLASS parameter enum meta data
#define FRAME_CLASS_UNDEFINED 0
#define FRAME_CLASS_QUAD 1
#define FRAME_CLASS_HEX 2
......@@ -38,7 +39,7 @@
#define FRAME_CLASS_DODECAHEXA 12
#define FRAME_CLASS_HELIQUAD 13
// These should match the FRAME_TYPE parameter enum meta data
// These should match the ArduCopter FRAME_TYPE parameter enum meta data
#define FRAME_TYPE_PLUS 0
#define FRAME_TYPE_X 1
#define FRAME_TYPE_V 2
......@@ -51,13 +52,24 @@
#define FRAME_TYPE_DJIX 13
#define FRAME_TYPE_CLOCKWISEX 14
// These should match the Rover FRAME_CLASS parameter enum meta data
#define FRAME_CLASS_ROVER 1
#define FRAME_CLASS_BOAT 2
#define FRAME_CLASS_BALANCEBOT 3
// These should match the Rover FRAME_TYPE parameter enum meta data
#define FRAME_TYPE_UNDEFINED 0
#define FRAME_TYPE_OMNI3 1
#define FRAME_TYPE_OMNIX 2
#define FRAME_TYPE_OMNIPLUS 3
typedef struct {
int frameClass;
int frameType;
const char* imageResource;
} FrameToImageInfo_t;
static const FrameToImageInfo_t s_rgFrameToImage[] = {
static const FrameToImageInfo_t s_rgFrameToImageCopter[] = {
{ FRAME_CLASS_QUAD, FRAME_TYPE_PLUS, "QuadRotorPlus" },
{ FRAME_CLASS_QUAD, FRAME_TYPE_X, "QuadRotorX" },
{ FRAME_CLASS_QUAD, FRAME_TYPE_V, "QuadRotorWide" },
......@@ -77,10 +89,15 @@ static const FrameToImageInfo_t s_rgFrameToImage[] = {
{ FRAME_CLASS_TRI, -1, "YPlus" },
};
static QString s_findImageResource(int frameClass, int frameType)
static const FrameToImageInfo_t s_rgFrameToImageRover[] = {
{ FRAME_CLASS_ROVER, -1, "Rover" },
{ FRAME_CLASS_BOAT, -1, "Boat" },
};
static QString s_findImageResourceCopter(int frameClass, int frameType)
{
for (size_t i=0; i<sizeof(s_rgFrameToImage)/sizeof(s_rgFrameToImage[0]); i++) {
const FrameToImageInfo_t* pFrameToImageInfo = &s_rgFrameToImage[i];
for (size_t i=0; i<sizeof(s_rgFrameToImageCopter)/sizeof(s_rgFrameToImageCopter[0]); i++) {
const FrameToImageInfo_t* pFrameToImageInfo = &s_rgFrameToImageCopter[i];
if (pFrameToImageInfo->frameClass == frameClass && pFrameToImageInfo->frameType == frameType) {
return pFrameToImageInfo->imageResource;
......@@ -92,9 +109,24 @@ static QString s_findImageResource(int frameClass, int frameType)
return QStringLiteral("AirframeUnknown");
}
static QString s_findImageResourceRover(int frameClass, int frameType)
{
Q_UNUSED(frameType);
for (size_t i=0; i<sizeof(s_rgFrameToImageRover)/sizeof(s_rgFrameToImageRover[0]); i++) {
const FrameToImageInfo_t* pFrameToImageInfo = &s_rgFrameToImageRover[i];
if (pFrameToImageInfo->frameClass == frameClass) {
return pFrameToImageInfo->imageResource;
}
}
return QStringLiteral("AirframeUnknown");
}
APMAirframeComponentController::APMAirframeComponentController(void)
: _frameClassFact (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME_CLASS")))
, _frameTypeFact (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME_TYPE")))
, _frameTypeFact (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME_TYPE"), false /* reportMissing */))
, _frameClassModel (new QmlObjectListModel(this))
{
_fillFrameClasses();
......@@ -107,26 +139,48 @@ APMAirframeComponentController::~APMAirframeComponentController()
void APMAirframeComponentController::_fillFrameClasses()
{
QList<int> frameTypeNotSupported;
frameTypeNotSupported << FRAME_CLASS_HELI
<< FRAME_CLASS_SINGLECOPTER
<< FRAME_CLASS_COAXCOPTER
<< FRAME_CLASS_BICOPTER
<< FRAME_CLASS_HELI_DUAL
<< FRAME_CLASS_HELIQUAD;
for (int i=1; i<_frameClassFact->enumStrings().count(); i++) {
QString frameClassName = _frameClassFact->enumStrings()[i];
int frameClass = _frameClassFact->enumValues()[i].toInt();
int defaultFrameType;
if (frameTypeNotSupported.contains(frameClass)) {
defaultFrameType = -1;
} else {
defaultFrameType = FRAME_TYPE_X;
FirmwarePlugin* fwPlugin = _vehicle->firmwarePlugin();
if (qobject_cast<ArduCopterFirmwarePlugin*>(fwPlugin)) {
QList<int> frameTypeNotSupported;
frameTypeNotSupported << FRAME_CLASS_HELI
<< FRAME_CLASS_SINGLECOPTER
<< FRAME_CLASS_COAXCOPTER
<< FRAME_CLASS_BICOPTER
<< FRAME_CLASS_HELI_DUAL
<< FRAME_CLASS_HELIQUAD;
for (int i=1; i<_frameClassFact->enumStrings().count(); i++) {
QString frameClassName = _frameClassFact->enumStrings()[i];
int frameClass = _frameClassFact->enumValues()[i].toInt();
int defaultFrameType;
if (frameClass == FRAME_CLASS_HELI) {
// Heli requires it's own firmware variant. You can't switch to Heli from a Copter variant firmware.
continue;
}
if (frameTypeNotSupported.contains(frameClass)) {
defaultFrameType = -1;
} else {
defaultFrameType = FRAME_TYPE_X;
}
_frameClassModel->append(new APMFrameClass(frameClassName, true /* copter */, frameClass, _frameTypeFact, defaultFrameType, _frameClassModel));
}
} else if (qobject_cast<ArduRoverFirmwarePlugin*>(fwPlugin)) {
for (int i=1; i<_frameClassFact->enumStrings().count(); i++) {
QString frameClassName = _frameClassFact->enumStrings()[i];
int frameClass = _frameClassFact->enumValues()[i].toInt();
int defaultFrameType;
if (_frameTypeFact) {
defaultFrameType = FRAME_TYPE_UNDEFINED;
} else {
defaultFrameType = -1;
}
_frameClassModel->append(new APMFrameClass(frameClassName, false /* copter */, frameClass, _frameTypeFact, defaultFrameType, _frameClassModel));
}
_frameClassModel->append(new APMFrameClass(frameClassName, frameClass, _frameTypeFact, defaultFrameType, _frameClassModel));
}
}
......@@ -216,16 +270,19 @@ void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg)
qgcApp()->restoreOverrideCursor();
}
APMFrameClass::APMFrameClass(const QString& name, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent)
APMFrameClass::APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent)
: QObject (parent)
, _name (name)
, _copter (copter)
, _frameClass (frameClass)
, _defaultFrameType (defaultFrameType)
, _frameTypeSupported (defaultFrameType != -1)
, _frameTypeFact (frameTypeFact)
{
connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::imageResourceChanged);
connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::frameTypeChanged);
if (frameTypeFact) {
connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::imageResourceChanged);
connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::frameTypeChanged);
}
}
APMFrameClass::~APMFrameClass()
......@@ -235,5 +292,14 @@ APMFrameClass::~APMFrameClass()
QString APMFrameClass::imageResource(void)
{
return QStringLiteral("/qmlimages/Airframe/%1").arg(s_findImageResource(_frameClass, _frameTypeFact->rawValue().toInt()));
QString imageResource;
int frameType = _frameTypeFact ? _frameTypeFact->rawValue().toInt() : -1;
if (_copter) {
imageResource = s_findImageResourceCopter(_frameClass, frameType);
} else {
imageResource = s_findImageResourceRover(_frameClass, frameType);
}
return QStringLiteral("/qmlimages/Airframe/%1").arg(imageResource);
}
......@@ -54,7 +54,7 @@ class APMFrameClass : public QObject
Q_OBJECT
public:
APMFrameClass(const QString& name, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent = nullptr);
APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent = nullptr);
~APMFrameClass();
Q_PROPERTY(QString name MEMBER _name CONSTANT)
......@@ -68,6 +68,7 @@ public:
QString imageResource (void);
QString _name;
bool _copter;
QString _imageResource;
int _frameClass;
int _defaultFrameType;
......
......@@ -18,32 +18,23 @@ FactPanel {
factPanel: panel
}
property bool _frameAvailable: controller.parameterExists(-1, "FRAME")
property Fact _frame: controller.getParameterFact(-1, "FRAME", false)
property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS", false)
property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS")
property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE", false)
property bool _frameTypeAvailable: controller.parameterExists(-1, "FRAME_TYPE")
Column {
anchors.fill: parent
VehicleSummaryRow {
labelText: qsTr("Frame Type")
valueText: visible ? controller.currentAirframeTypeName() + " " + _frame.enumStringValue : ""
visible: _frameAvailable
}
VehicleSummaryRow {
labelText: qsTr("Frame Class")
valueText: visible ? _frameClass.enumStringValue : ""
visible: !_frameAvailable
valueText: _frameClass.enumStringValue
}
VehicleSummaryRow {
labelText: qsTr("Frame Type")
valueText: visible ? _frameType.enumStringValue : ""
visible: !_frameAvailable
visible: _frameTypeAvailable
}
VehicleSummaryRow {
......
......@@ -10,6 +10,7 @@
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
......@@ -36,12 +37,14 @@ SetupPage {
property bool _atcInputTCAvailable: controller.parameterExists(-1, "ATC_INPUT_TC")
property Fact _rcFeel: controller.getParameterFact(-1, "RC_FEEL", false)
property Fact _atcInputTC: controller.getParameterFact(-1, "ATC_INPUT_TC", false)
property Fact _rateRollP: controller.getParameterFact(-1, "r.ATC_RAT_RLL_P")
property Fact _rateRollI: controller.getParameterFact(-1, "r.ATC_RAT_RLL_I")
property Fact _ratePitchP: controller.getParameterFact(-1, "r.ATC_RAT_PIT_P")
property Fact _ratePitchI: controller.getParameterFact(-1, "r.ATC_RAT_PIT_I")
property Fact _rateClimbP: controller.getParameterFact(-1, "r.PSC_ACCZ_P")
property Fact _rateClimbI: controller.getParameterFact(-1, "r.PSC_ACCZ_I")
property Fact _rateRollP: controller.getParameterFact(-1, "ATC_RAT_RLL_P")
property Fact _rateRollI: controller.getParameterFact(-1, "ATC_RAT_RLL_I")
property Fact _ratePitchP: controller.getParameterFact(-1, "ATC_RAT_PIT_P")
property Fact _ratePitchI: controller.getParameterFact(-1, "ATC_RAT_PIT_I")
property Fact _rateClimbP: controller.getParameterFact(-1, "PSC_ACCZ_P")
property Fact _rateClimbI: controller.getParameterFact(-1, "PSC_ACCZ_I")
property Fact _motSpinArm: controller.getParameterFact(-1, "MOT_SPIN_ARM")
property Fact _motSpinMin: controller.getParameterFact(-1, "MOT_SPIN_MIN")
property Fact _ch7Opt: controller.getParameterFact(-1, "r.RC7_OPTION")
property Fact _ch8Opt: controller.getParameterFact(-1, "r.RC8_OPTION")
......@@ -122,7 +125,6 @@ SetupPage {
Connections { target: _ch12Opt; onValueChanged: calcAutoTuneChannel() }
QGCLabel {
id: basicLabel
text: qsTr("Basic Tuning")
font.family: ScreenTools.demiboldFontFamily
}
......@@ -271,6 +273,92 @@ SetupPage {
}
} // Rectangle - Basic tuning
QGCLabel {
text: qsTr("Advanced Tuning")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: advColumnLayout.y + advColumnLayout.height + _margins
color: palette.windowShade
ColumnLayout {
id: advColumnLayout
anchors.margins: _margins
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
spacing: _margins
Column {
Layout.fillWidth: true
QGCLabel {
text: qsTr("Spin While Armed")
font.family: ScreenTools.demiboldFontFamily
}
QGCLabel {
text: qsTr("Adjust the amount the motors spin to indicate armed")
}
Slider {
anchors.left: parent.left
anchors.right: parent.right
minimumValue: 0
maximumValue: Math.max(0.3, _motSpinArm.rawValue)
stepSize: 0.01
tickmarksEnabled: true
value: _motSpinArm.rawValue
onValueChanged: {
if (_loadComplete) {
_motSpinArm.rawValue = value
}
}
}
}
Column {
id: lastAdvTuningColumn
Layout.fillWidth: true
QGCLabel {
text: qsTr("Minimum Thrust")
font.family: ScreenTools.demiboldFontFamily
}
QGCLabel {
text: qsTr("Adjust the minimum amount of thrust for a stable minimum throttle descent")
}
QGCLabel {
text: qsTr("Warning: This setting should be higher than 'Spin While Armed'")
color: palette.warningText
visible: _motSpinMin.rawValue < _motSpinArm.rawValue
}
Slider {
anchors.left: parent.left
anchors.right: parent.right
minimumValue: 0
maximumValue: Math.max(0.3, _motSpinMin.rawValue)
stepSize: 0.01
tickmarksEnabled: true
value: _motSpinMin.rawValue
onValueChanged: {
if (_loadComplete) {
_motSpinMin.rawValue = value
}
}
}
}
}
} // Rectangle - Advanced tuning
Flow {
id: flowLayout
anchors.left: parent.left
......
......@@ -132,7 +132,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name
if (reportMissing) {
_reportMissingParameter(componentId, name);
}
return NULL;
return nullptr;
}
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment