Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Motor Setup #12312

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file modified docs/assets/setup/Motors.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
15 changes: 11 additions & 4 deletions docs/en/qgc-user-guide/setup_view/motors.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,21 @@ To test the motors:
You must remove props before activating the motors!
:::

1. (_PX4-only_) Enable safety switch - if used.
1. Slide the switch to enable motor sliders (labeled: _Propellers are removed - Enable motor sliders_).
1. Adjust the individual sliders to spin the motors and confirm they spin in the correct direction.
2. (_PX4-only_) Enable safety switch - if used.

3. Slide the switch to enable motor slider and buttons (labeled: _Propellers are removed - Enable slider and motors_).

4. Adjust the slider to select the power for the motors, you can use the buttons + or - to fine tune the percentage.

5. Press the button corresponding to the motor and confirm it spin in the correct direction.

::: info
The motors only spin after you release the slider and will automatically stop spinning after 3 seconds.
The motors will automatically stop spinning after 3 seconds.
You can also stop the motor by pressing the 'Stop' button.
If no motors turn, raise the “Throttle %” and try again.
:::

## Additional Information

- [Basic Configuration > Motor Setup](http://docs.px4.io/master/en/config/motors.html) (_PX4 User Guide_) - This contains additional PX4-specific information.
- [ESCS and Motors](https://ardupilot.org/copter/docs/connect-escs-and-motors.html#motor-order-diagrams) - This is the Motor order diagrams for all frames
13 changes: 9 additions & 4 deletions docs/zh/qgc-user-guide/setup_view/motors.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

Motor Setup is used to test individual motors/servos (for example, to verify that motors spin in the correct direction).

:::tip
::: tip
These instructions apply to PX4 and to most vehicle types on ArduPilot.
Vehicle-specific instructions are provided as sub-topics (e.g. [Motors Setup (ArduSub)](../setup_view/motors_ardusub.md)).
:::
Expand All @@ -21,14 +21,19 @@ To test the motors:

2. (_PX4-only_) Enable safety switch - if used.

3. Slide the switch to enable motor sliders (labeled: _Propellers are removed - Enable motor sliders_).
3. Slide the switch to enable motor slider and buttons (labeled: _Propellers are removed - Enable slider and motors_).

4. Adjust the individual sliders to spin the motors and confirm they spin in the correct direction.
4. Adjust the slider to select the power for the motors, you can use the buttons + or - to fine tune the percentage.

5. Press the button corresponding to the motor and confirm it spin in the correct direction.

::: info
The motors only spin after you release the slider and will automatically stop spinning after 3 seconds.
The motors will automatically stop spinning after 3 seconds.
You can also stop the motor by pressing the 'Stop' button.
If no motors turn, raise the “Throttle %” and try again.
:::

## Additional Information

- [Basic Configuration > Motor Setup](http://docs.px4.io/master/en/config/motors.html) (_PX4 User Guide_) - This contains additional PX4-specific information.
- [ESCS and Motors](https://ardupilot.org/copter/docs/connect-escs-and-motors.html#motor-order-diagrams) - This is the Motor order diagrams for all frames
144 changes: 76 additions & 68 deletions src/AutoPilotPlugins/APM/APMMotorComponent.qml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ SetupPage {

readonly property int _barHeight: 10
readonly property int _barWidth: 5
readonly property int _sliderHeight: 10
readonly property int _sliderWidth: 15
readonly property int _motorTimeoutSecs: 3

FactPanelController {
Expand All @@ -42,106 +42,114 @@ SetupPage {
}

Row {
id: motorSliders
enabled: safetySwitch.checked
spacing: ScreenTools.defaultFontPixelWidth * 4

Repeater {
id: sliderRepeater
model: controller.vehicle.motorCount == -1 ? 8 : controller.vehicle.motorCount
Column {

Column {
property alias motorSlider: slider
QGCLabel {
id: labelThrottle
anchors.horizontalCenter: parent.horizontalCenter
text: qsTr("Throttle") + " " + sliderThrottle.value + " " + qsTr("%")
}

QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: vehicleComponent.motorIndexToLetter(index)
Row {
id: motorSlider
enabled: safetySwitch.checked
spacing: ScreenTools.defaultFontPixelWidth * 4

QGCButton {
anchors.verticalCenter: parent.verticalCenter
id: minusMinusButton
text: qsTr("-")
onClicked: sliderThrottle.value-=1
}

QGCSlider {
id: slider
height: ScreenTools.defaultFontPixelHeight * _sliderHeight
orientation: Qt.Vertical
from: 0
to: 100
id: sliderThrottle
width: ScreenTools.defaultFontPixelHeight * _sliderWidth
orientation: Qt.Horizontal
anchors.verticalCenter: parent.verticalCenter
from: 0
to: 100
stepSize: 1
value: 0
live: false

onValueChanged: {
controller.vehicle.motorTest(index + 1, value, value == 0 ? 0 : _motorTimeoutSecs, true)
if (value != 0) {
motorTimer.restart()
}
}

Timer {
id: motorTimer
interval: _motorTimeoutSecs * 1000
repeat: false
running: false

onTriggered: {
allSlider.value = 0
slider.value = 0
}
}
live: false
displayValue: true
}
} // Column
} // Repeater

Column {
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: qsTr("All")
}

QGCSlider {
id: allSlider
height: ScreenTools.defaultFontPixelHeight * _sliderHeight
orientation: Qt.Vertical
from: 0
to: 100
stepSize: 1
value: 0
live: false

onValueChanged: {
for (var sliderIndex=0; sliderIndex<sliderRepeater.count; sliderIndex++) {
sliderRepeater.itemAt(sliderIndex).motorSlider.value = allSlider.value
}
QGCButton {
anchors.verticalCenter: parent.verticalCenter
id: plusButton
text: qsTr("+")
onClicked: sliderThrottle.value+=1
}
}
} // Row
} // 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.")
text: qsTr("Make sure you remove all props.")
}

Row {
id: motorButtons
enabled: safetySwitch.checked
spacing: ScreenTools.defaultFontPixelWidth * 4

Repeater {
id: buttonRepeater
model: controller.vehicle.motorCount === -1 ? 8 : controller.vehicle.motorCount

QGCButton {
id: button
anchors.verticalCenter: parent.verticalCenter
text: vehicleComponent.motorIndexToLetter(index)
onClicked: {
controller.vehicle.motorTest(index + 1, sliderThrottle.value, sliderThrottle.value === 0 ? 0 : _motorTimeoutSecs, true)
}
}
} // Repeater

QGCButton {
id: allButton
text: qsTr("All")
onClicked: {
for (var motorIndex=0; motorIndex<buttonRepeater.count; motorIndex++) {
controller.vehicle.motorTest(motorIndex + 1, sliderThrottle.value, sliderThrottle.value === 0 ? 0 : _motorTimeoutSecs, true)
}
}
}

QGCButton {
id: allStopButton
text: qsTr("Stop")
onClicked: {
for (var motorIndex=0; motorIndex<buttonRepeater.count; motorIndex++) {
controller.vehicle.motorTest(motorIndex + 1, 0, 0, true)
}
}
}
} // Row

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
sliderThrottle.value = 0
}
}
}

QGCLabel {
anchors.verticalCenter: parent.verticalCenter
color: qgcPal.warningText
text: safetySwitch.checked ? qsTr("Careful: Motor sliders are enabled") : qsTr("Propellers are removed - Enable motor sliders")
text: safetySwitch.checked ? qsTr("Careful : Motors are enabled") : qsTr("Propellers are removed - Enable slider and motors")
}
} // Row
} // Column
} // Component
} // SetupPahe
} // SetupPage
Loading
Loading