Browse Source

Copter: move set_pre_arm_check to arming_checks

master
Randy Mackay 8 years ago
parent
commit
b89d3564c7
  1. 15
      ArduCopter/AP_State.cpp
  2. 15
      ArduCopter/arming_checks.cpp

15
ArduCopter/AP_State.cpp

@ -101,21 +101,6 @@ void Copter::set_failsafe_gcs(bool b) @@ -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

15
ArduCopter/arming_checks.cpp

@ -792,6 +792,21 @@ enum HomeState AP_Arming_Copter::home_status() const @@ -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);

Loading…
Cancel
Save