|
|
|
@ -6,41 +6,15 @@ enum HomeState AP_Arming_Sub::home_status() const
@@ -6,41 +6,15 @@ enum HomeState AP_Arming_Sub::home_status() const
|
|
|
|
|
return sub.ap.home_state; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool AP_Arming_Sub::rc_check(bool report) |
|
|
|
|
bool AP_Arming_Sub::rc_check(bool display_failure) |
|
|
|
|
{ |
|
|
|
|
// set rc-checks to success if RC checks are disabled
|
|
|
|
|
if ((checks_to_perform != ARMING_CHECK_ALL) && !(checks_to_perform & ARMING_CHECK_RC)) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static const char* message_fail = "PreArm: Check RC min/max parameters"; |
|
|
|
|
bool ret = true; |
|
|
|
|
|
|
|
|
|
// check channels 1 & 2 have min <= 1300 and max >= 1700
|
|
|
|
|
if (sub.channel_roll->get_radio_min() > 1300 || sub.channel_roll->get_radio_max() < 1700 || sub.channel_pitch->get_radio_min() > 1300 || sub.channel_pitch->get_radio_max() < 1700) { |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check channels 3 & 4 have min <= 1300 and max >= 1700
|
|
|
|
|
if (sub.channel_throttle->get_radio_min() > 1300 || sub.channel_throttle->get_radio_max() < 1700 || sub.channel_yaw->get_radio_min() > 1300 || sub.channel_yaw->get_radio_max() < 1700) { |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check channels 1 & 2 have trim >= 1300 and <= 1700
|
|
|
|
|
if (sub.channel_roll->get_radio_trim() < 1300 || sub.channel_roll->get_radio_trim() > 1700 || sub.channel_pitch->get_radio_trim() < 1300 || sub.channel_pitch->get_radio_trim() > 1700) { |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check channel 4 has trim >= 1300 and <= 1700
|
|
|
|
|
if (sub.channel_yaw->get_radio_trim() < 1300 || sub.channel_yaw->get_radio_trim() > 1700) { |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (report && !ret) { |
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, message_fail); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return ret; |
|
|
|
|
const RC_Channel *channels[] = { |
|
|
|
|
sub.channel_roll, |
|
|
|
|
sub.channel_pitch, |
|
|
|
|
sub.channel_throttle, |
|
|
|
|
sub.channel_yaw |
|
|
|
|
}; |
|
|
|
|
return rc_checks_copter_sub(display_failure, channels); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool AP_Arming_Sub::pre_arm_checks(bool report) |
|
|
|
|