mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Copter: fix merge error for g.angle_max
This commit is contained in:
parent
5e8fede19e
commit
006cf58b2d
@ -469,7 +469,7 @@ static bool arm_checks(bool display_failure)
|
|||||||
|
|
||||||
// check lean angle
|
// check lean angle
|
||||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
||||||
if (labs(ahrs.roll_sensor) > g.angle_max || labs(ahrs.pitch_sensor) > g.angle_max) {
|
if (labs(ahrs.roll_sensor) > aparm.angle_max || labs(ahrs.pitch_sensor) > aparm.angle_max) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning"));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user