diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 4e32e06b3d..29ef7eba25 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -491,8 +491,11 @@ void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &c MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) { if (is_equal(packet.param4, 1.0f)) { - rover.trim_radio(); - return MAV_RESULT_ACCEPTED; + if (rover.trim_radio()) { + return MAV_RESULT_ACCEPTED; + } else { + return MAV_RESULT_FAILED; + } } return GCS_MAVLINK::_handle_command_preflight_calibration(packet); diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 3910be1fca..f94b27d843 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -503,8 +503,7 @@ private: void rudder_arm_disarm_check(); void read_radio(); void control_failsafe(uint16_t pwm); - void trim_control_surfaces(); - void trim_radio(); + bool trim_radio(); // sensors.cpp void init_compass(void); diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 5dc59a0fc3..0137e836bb 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -137,22 +137,20 @@ void Rover::control_failsafe(uint16_t pwm) } } -void Rover::trim_control_surfaces() +bool Rover::trim_radio() { - read_radio(); + if (failsafe.bits & FAILSAFE_EVENT_RC) { + // can't trim without valid input + return false; + } + // Store control surface trim values // --------------------------------- if ((channel_steer->get_radio_in() > 1400) && (channel_steer->get_radio_in() < 1600)) { - channel_steer->set_radio_trim(channel_steer->get_radio_in()); - // save to eeprom - channel_steer->save_eeprom(); + channel_steer->set_and_save_radio_trim(channel_steer->get_radio_in()); + } else { + return false; } -} -void Rover::trim_radio() -{ - for (uint8_t y = 0; y < 30; y++) { - read_radio(); - } - trim_control_surfaces(); + return true; }