Copter: lean angle arming check

This commit is contained in:
Randy Mackay 2014-01-17 17:31:28 +09:00
parent a7f03619f2
commit 0f957bdc5a
1 changed files with 10 additions and 0 deletions

View File

@ -471,6 +471,16 @@ static bool arm_checks(bool display_failure)
}
}
// check lean angle
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 (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning"));
}
return false;
}
}
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
if (display_failure) {