Browse Source

Rover: remove auto trim at startup

Also add additional checks to auto trim
mission-4.1.18
Randy Mackay 7 years ago
parent
commit
241456f55f
  1. 2
      APMrover2/radio.cpp
  2. 4
      APMrover2/system.cpp

2
APMrover2/radio.cpp

@ -141,7 +141,7 @@ void Rover::trim_control_surfaces()
read_radio(); read_radio();
// Store control surface trim values // 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()); channel_steer->set_radio_trim(channel_steer->get_radio_in());
// save to eeprom // save to eeprom
channel_steer->save_eeprom(); channel_steer->save_eeprom();

4
APMrover2/system.cpp

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

Loading…
Cancel
Save