mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Sub: Don't check min/max configured for RC prearm check
This commit is contained in:
parent
b8e7d23cc4
commit
589416451f
@ -14,7 +14,7 @@ bool AP_Arming_Sub::rc_check(bool display_failure)
|
|||||||
sub.channel_throttle,
|
sub.channel_throttle,
|
||||||
sub.channel_yaw
|
sub.channel_yaw
|
||||||
};
|
};
|
||||||
return rc_checks_copter_sub(display_failure, channels);
|
return rc_checks_copter_sub(display_failure, channels, false /* check_min_max */);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Arming_Sub::pre_arm_checks(bool report)
|
bool AP_Arming_Sub::pre_arm_checks(bool report)
|
||||||
|
Loading…
Reference in New Issue
Block a user