Rover: remove auto trim at startup

Also add additional checks to auto trim
This commit is contained in:
Randy Mackay 2017-12-15 15:04:28 +09:00
parent 6459a4de9d
commit 241456f55f
2 changed files with 1 additions and 5 deletions

View File

@ -141,7 +141,7 @@ void Rover::trim_control_surfaces()
read_radio();
// Store control surface trim values
// ---------------------------------
if (channel_steer->get_radio_in() > 1400) {
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();

View File

@ -179,10 +179,6 @@ void Rover::startup_ground(void)
startup_INS_ground();
// read the radio to set trims
// ---------------------------
trim_radio();
// initialise mission library
mission.init();