mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: make rc checks verbose on failure
This commit is contained in:
parent
078866046a
commit
ab13b3beaf
@ -89,7 +89,7 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
|
||||
bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
|
||||
{
|
||||
// pre-arm rc checks a prerequisite
|
||||
pre_arm_rc_checks();
|
||||
pre_arm_rc_checks(display_failure);
|
||||
if (!copter.ap.pre_arm_rc_check) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC not calibrated");
|
||||
@ -330,7 +330,7 @@ bool AP_Arming_Copter::pilot_throttle_checks(bool display_failure)
|
||||
}
|
||||
|
||||
// perform pre_arm_rc_checks checks and set ap.pre_arm_rc_check flag
|
||||
void AP_Arming_Copter::pre_arm_rc_checks()
|
||||
void AP_Arming_Copter::pre_arm_rc_checks(const bool display_failure)
|
||||
{
|
||||
// exit immediately if we've already successfully performed the pre-arm rc check
|
||||
if (copter.ap.pre_arm_rc_check) {
|
||||
@ -354,13 +354,21 @@ void AP_Arming_Copter::pre_arm_rc_checks()
|
||||
copter.channel_throttle,
|
||||
copter.channel_yaw
|
||||
};
|
||||
const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };
|
||||
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(channels);i++) {
|
||||
const RC_Channel *channel = channels[i];
|
||||
const char *channel_name = channel_names[i];
|
||||
if (channel->get_radio_min() > 1300) {
|
||||
if (display_failure) {
|
||||
copter.gcs_send_text_fmt(MAV_SEVERITY_CRITICAL,"PreArm: %s radio min too high", channel_name);
|
||||
}
|
||||
return;
|
||||
}
|
||||
if (channel->get_radio_max() < 1700) {
|
||||
if (display_failure) {
|
||||
copter.gcs_send_text_fmt(MAV_SEVERITY_CRITICAL,"PreArm: %s radio max too low", channel_name);
|
||||
}
|
||||
return;
|
||||
}
|
||||
if (i == 2) {
|
||||
@ -368,9 +376,15 @@ void AP_Arming_Copter::pre_arm_rc_checks()
|
||||
continue;
|
||||
}
|
||||
if (channel->get_radio_trim() < channel->get_radio_min()) {
|
||||
if (display_failure) {
|
||||
copter.gcs_send_text_fmt(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim below min", channel_name);
|
||||
}
|
||||
return;
|
||||
}
|
||||
if (channel->get_radio_trim() > channel->get_radio_max()) {
|
||||
if (display_failure) {
|
||||
copter.gcs_send_text_fmt(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim above max", channel_name);
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
|
||||
void update(void);
|
||||
bool all_checks_passing(bool arming_from_gcs);
|
||||
void pre_arm_rc_checks();
|
||||
void pre_arm_rc_checks(bool display_failure);
|
||||
|
||||
protected:
|
||||
|
||||
|
@ -56,7 +56,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
||||
}
|
||||
|
||||
// check if radio is calibrated
|
||||
arming.pre_arm_rc_checks();
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (!ap.pre_arm_rc_check) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");
|
||||
ap.compass_mot = false;
|
||||
|
@ -20,7 +20,7 @@ void Copter::esc_calibration_startup_check()
|
||||
{
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
// exit immediately if pre-arm rc checks fail
|
||||
arming.pre_arm_rc_checks();
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (!ap.pre_arm_rc_check) {
|
||||
// clear esc flag for next time
|
||||
if ((g.esc_calibrate != ESCCAL_NONE) && (g.esc_calibrate != ESCCAL_DISABLED)) {
|
||||
|
@ -73,7 +73,7 @@ void Copter::motor_test_output()
|
||||
bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
|
||||
{
|
||||
// check rc has been calibrated
|
||||
arming.pre_arm_rc_checks();
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if(check_rc && !ap.pre_arm_rc_check) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: RC not calibrated");
|
||||
return false;
|
||||
|
@ -68,7 +68,7 @@ void Copter::init_rc_out()
|
||||
esc_calibration_startup_check();
|
||||
|
||||
// enable output to motors
|
||||
arming.pre_arm_rc_checks();
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (ap.pre_arm_rc_check) {
|
||||
enable_motor_output();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user