Browse Source

Merge pull request #7941 from mavlink/px4_motor_test

PX4: enable motor test UI
QGC4.4
Beat Küng 6 years ago committed by GitHub
parent
commit
1c146595fd
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 66
      src/AutoPilotPlugins/Common/MotorComponent.qml
  2. 3
      src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc

66
src/AutoPilotPlugins/Common/MotorComponent.qml

@ -20,9 +20,10 @@ SetupPage { @@ -20,9 +20,10 @@ SetupPage {
id: motorPage
pageComponent: pageComponent
readonly property int _barHeight: 10
readonly property int _barWidth: 5
readonly property int _sliderHeight: 10
readonly property int _barHeight: 10
readonly property int _barWidth: 5
readonly property int _sliderHeight: 10
readonly property int _motorTimeoutSecs: 3
FactPanelController {
id: controller
@ -32,7 +33,13 @@ SetupPage { @@ -32,7 +33,13 @@ SetupPage {
id: pageComponent
Column {
spacing: 10
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
text: qsTr("Warning: Unable to determine motor count")
color: qgcPal.warningText
visible: controller.vehicle.motorCount == -1
}
Row {
id: motorSliders
@ -46,20 +53,6 @@ SetupPage { @@ -46,20 +53,6 @@ SetupPage {
Column {
property alias motorSlider: slider
Timer {
interval: 250
running: true
repeat: true
property real _lastValue: 0
onTriggered: {
if (_lastValue !== slider.value) {
controller.vehicle.motorTest(index + 1, slider.value, 1)
}
}
}
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: index + 1
@ -69,8 +62,30 @@ SetupPage { @@ -69,8 +62,30 @@ SetupPage {
id: slider
height: ScreenTools.defaultFontPixelHeight * _sliderHeight
orientation: Qt.Vertical
minimumValue: 0
maximumValue: 100
stepSize: 1
value: 0
updateValueWhileDragging: false
onValueChanged: {
controller.vehicle.motorTest(index + 1, value, value == 0 ? 0 : _motorTimeoutSecs)
if (value != 0) {
motorTimer.restart()
}
}
Timer {
id: motorTimer
interval: _motorTimeoutSecs * 1000
repeat: false
running: false
onTriggered: {
allSlider.value = 0
slider.value = 0
}
}
}
} // Column
} // Repeater
@ -85,8 +100,11 @@ SetupPage { @@ -85,8 +100,11 @@ SetupPage {
id: allSlider
height: ScreenTools.defaultFontPixelHeight * _sliderHeight
orientation: Qt.Vertical
minimumValue: 0
maximumValue: 100
stepSize: 1
value: 0
updateValueWhileDragging: false
onValueChanged: {
for (var sliderIndex=0; sliderIndex<sliderRepeater.count; sliderIndex++) {
@ -95,16 +113,6 @@ SetupPage { @@ -95,16 +113,6 @@ SetupPage {
}
}
} // Column
MultiRotorMotorDisplay {
anchors.top: parent.top
anchors.bottom: parent.bottom
width: height
motorCount: controller.vehicle.motorCount
xConfig: controller.vehicle.xConfigMotors
coaxial: controller.vehicle.coaxialMotors
}
} // Row
QGCLabel {
@ -131,7 +139,7 @@ SetupPage { @@ -131,7 +139,7 @@ SetupPage {
QGCLabel {
color: qgcPal.warningText
text: qsTr("Propellers are removed - Enable motor sliders")
text: safetySwitch.checked ? qsTr("Careful: Motor sliders are enabled") : qsTr("Propellers are removed - Enable motor sliders")
}
} // Row
} // Column

3
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc

@ -84,12 +84,9 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) @@ -84,12 +84,9 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
#if 0
// Coming soon
_motorComponent = new MotorComponent(_vehicle, this);
_motorComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_motorComponent));
#endif
_safetyComponent = new SafetyComponent(_vehicle, this);
_safetyComponent->setupTriggerSignals();

Loading…
Cancel
Save