Commit 3089da58 authored by Don Gagne's avatar Don Gagne

parent bf9dbefb
......@@ -91,7 +91,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
if (_vehicle->sub() && _vehicle->versionCompare(3, 5, 3) >= 0) {
if (!_vehicle->sub() || (_vehicle->sub() && _vehicle->versionCompare(3, 5, 3) >= 0)) {
_motorComponent = new APMMotorComponent(_vehicle, this);
_motorComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_motorComponent));
......
......@@ -22,6 +22,13 @@ QUrl APMMotorComponent::setupSource(void) const
case MAV_TYPE_SUBMARINE:
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMSubMotorComponent.qml"));
default:
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/MotorComponent.qml"));
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMMotorComponent.qml"));
}
}
QString APMMotorComponent::motorIndexToLetter(int index)
{
char letter = 'A';
return QString(letter + index);
}
......@@ -20,7 +20,11 @@ class APMMotorComponent : public MotorComponent
public:
APMMotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
QUrl setupSource(void) const final;
// VehicleComponent overrides
QUrl setupSource (void) const override;
bool allowSetupWhileArmed (void) const override { return true; }
Q_INVOKABLE QString motorIndexToLetter(int index);
private:
const QString _name;
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.ScreenTools 1.0
SetupPage {
id: motorPage
pageComponent: pageComponent
readonly property int _barHeight: 10
readonly property int _barWidth: 5
readonly property int _sliderHeight: 10
readonly property int _motorTimeoutSecs: 3
FactPanelController {
id: controller
}
Component {
id: pageComponent
Column {
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
text: qsTr("Warning: Unable to determine motor count")
color: qgcPal.warningText
visible: controller.vehicle.motorCount == -1
}
Row {
id: motorSliders
enabled: safetySwitch.checked
spacing: ScreenTools.defaultFontPixelWidth * 4
Repeater {
id: sliderRepeater
model: controller.vehicle.motorCount == -1 ? 8 : controller.vehicle.motorCount
Column {
property alias motorSlider: slider
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: vehicleComponent.motorIndexToLetter(index)
}
QGCSlider {
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
Column {
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: qsTr("All")
}
QGCSlider {
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++) {
sliderRepeater.itemAt(sliderIndex).motorSlider.value = allSlider.value
}
}
}
} // Column
} // Row
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
text: qsTr("Moving the sliders will causes the motors to spin. Make sure you remove all props.")
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
Switch {
id: safetySwitch
onClicked: {
if (!checked) {
for (var sliderIndex=0; sliderIndex<sliderRepeater.count; sliderIndex++) {
sliderRepeater.itemAt(sliderIndex).motorSlider.value = 0
}
allSlider.value = 0
}
}
}
QGCLabel {
color: qgcPal.warningText
text: safetySwitch.checked ? qsTr("Careful: Motor sliders are enabled") : qsTr("Propellers are removed - Enable motor sliders")
}
} // Row
} // Column
} // Component
} // SetupPahe
......@@ -10,6 +10,7 @@
<file alias="APMHeliComponent.qml">../../AutoPilotPlugins/APM/APMHeliComponent.qml</file>
<file alias="APMLightsComponent.qml">../../AutoPilotPlugins/APM/APMLightsComponent.qml</file>
<file alias="APMLightsComponentSummary.qml">../../AutoPilotPlugins/APM/APMLightsComponentSummary.qml</file>
<file alias="APMMotorComponent.qml">../../AutoPilotPlugins/APM/APMMotorComponent.qml</file>
<file alias="APMSubFrameComponent.qml">../../AutoPilotPlugins/APM/APMSubFrameComponent.qml</file>
<file alias="APMSubFrameComponentSummary.qml">../../AutoPilotPlugins/APM/APMSubFrameComponentSummary.qml</file>
<file alias="APMSubMotorComponent.qml">../../AutoPilotPlugins/APM/APMSubMotorComponent.qml</file>
......
......@@ -3487,9 +3487,9 @@ void Vehicle::setSoloFirmware(bool soloFirmware)
}
}
void Vehicle::motorTest(int motor, int percent)
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
{
sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, 0, 0, MOTOR_TEST_ORDER_BOARD);
sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
}
QString Vehicle::brandImageIndoor(void) const
......
......@@ -765,7 +765,8 @@ public:
/// Test motor
/// @param motor Motor number, 1-based
/// @param percent 0-no power, 100-full power
Q_INVOKABLE void motorTest(int motor, int percent);
/// @param timeoutSec Disabled motor after this amount of time
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);
......
......@@ -337,11 +337,13 @@ Rectangle {
anchors.bottom: parent.bottom
function setSource(source, vehicleComponent) {
panelLoader.source = ""
panelLoader.vehicleComponent = vehicleComponent
panelLoader.source = source
}
function setSourceComponent(sourceComponent, vehicleComponent) {
panelLoader.sourceComponent = undefined
panelLoader.vehicleComponent = vehicleComponent
panelLoader.sourceComponent = sourceComponent
}
......
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