diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index d9e1677cda..d64d809b3a 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -351,19 +351,19 @@ void AP_Arming_Copter::pre_arm_rc_checks(const bool display_failure) // check if radio has been calibrated if (!channel->min_max_configured()) { if (display_failure) { - copter.gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC %s not configured", channel_name); + gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC %s not configured", channel_name); } return; } if (channel->get_radio_min() > 1300) { if (display_failure) { - copter.gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio min too high", channel_name); + gcs().send_text(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(MAV_SEVERITY_CRITICAL,"PreArm: %s radio max too low", channel_name); + gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio max too low", channel_name); } return; } @@ -373,13 +373,13 @@ void AP_Arming_Copter::pre_arm_rc_checks(const bool display_failure) } if (channel->get_radio_trim() < channel->get_radio_min()) { if (display_failure) { - copter.gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim below min", channel_name); + gcs().send_text(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(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim above max", channel_name); + gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim above max", channel_name); } return; }