From 5a99da106a9caea187a3d79ad7e533a9b0581e63 Mon Sep 17 00:00:00 2001 From: Rustom Jehangir Date: Fri, 19 Aug 2016 16:14:42 -0700 Subject: [PATCH] Sub: Force ch 3 trim to 1100 to match hardcoded radio settings --- ArduSub/radio.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduSub/radio.cpp b/ArduSub/radio.cpp index 50d873482c..4a96f737e1 100644 --- a/ArduSub/radio.cpp +++ b/ArduSub/radio.cpp @@ -48,6 +48,10 @@ void Sub::init_rc_in() ======= >>>>>>> Changed to ArduCopter as the base code. + // force throttle trim to 1100 + channel_throttle->set_radio_trim(1100); + channel_throttle->save_eeprom(); + //set auxiliary servo ranges // g.rc_5.set_range(0,1000); // g.rc_6.set_range(0,1000);