mirror of https://github.com/ArduPilot/ardupilot
Rover: change motor_active to be based on servo out rather than radio in
This commit is contained in:
parent
cfee3b6c0e
commit
f1b776e4eb
|
@ -119,7 +119,7 @@ bool Rover::motor_active()
|
||||||
{
|
{
|
||||||
// Check if armed and throttle is not neutral
|
// Check if armed and throttle is not neutral
|
||||||
if (hal.util->get_soft_armed()) {
|
if (hal.util->get_soft_armed()) {
|
||||||
if (!channel_throttle->in_trim_dz()) {
|
if (channel_throttle->get_servo_out() != channel_throttle->get_radio_trim()) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue