mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: Fix motor_active check to checkout throttle output servo
This commit is contained in:
parent
91269f2126
commit
ebedc8b01e
@ -117,9 +117,9 @@ void Rover::read_trim_switch()
|
|||||||
|
|
||||||
bool Rover::motor_active()
|
bool Rover::motor_active()
|
||||||
{
|
{
|
||||||
// Check if armed and throttle is not neutral
|
// Check if armed and output throttle servo is not neutral
|
||||||
if (hal.util->get_soft_armed()) {
|
if (hal.util->get_soft_armed()) {
|
||||||
if (channel_throttle->get_servo_out() != channel_throttle->get_radio_trim()) {
|
if (channel_throttle->get_servo_out() != 0) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user