Copter: move set_pre_arm_check to arming_checks

This commit is contained in:
Randy Mackay 2016-12-26 17:03:40 +09:00
parent 4ea6cf4ce3
commit b89d3564c7
2 changed files with 15 additions and 15 deletions

View File

@ -101,21 +101,6 @@ void Copter::set_failsafe_gcs(bool b)
// ---------------------------------------------
void AP_Arming_Copter::set_pre_arm_check(bool b)
{
if(copter.ap.pre_arm_check != b) {
copter.ap.pre_arm_check = b;
AP_Notify::flags.pre_arm_check = b;
}
}
void AP_Arming_Copter::set_pre_arm_rc_check(bool b)
{
if(copter.ap.pre_arm_rc_check != b) {
copter.ap.pre_arm_rc_check = b;
}
}
void Copter::update_using_interlock()
{
#if FRAME_CONFIG == HELI_FRAME

View File

@ -792,6 +792,21 @@ enum HomeState AP_Arming_Copter::home_status() const
return copter.ap.home_state;
}
void AP_Arming_Copter::set_pre_arm_check(bool b)
{
if(copter.ap.pre_arm_check != b) {
copter.ap.pre_arm_check = b;
AP_Notify::flags.pre_arm_check = b;
}
}
void AP_Arming_Copter::set_pre_arm_rc_check(bool b)
{
if(copter.ap.pre_arm_rc_check != b) {
copter.ap.pre_arm_rc_check = b;
}
}
void AP_Arming_Copter::gcs_send_text(MAV_SEVERITY severity, const char *str)
{
copter.gcs_send_text(severity, str);