From 6186b7a4533a21bb76290f606594ff7822caf19c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Aug 2015 16:30:44 +1000 Subject: [PATCH] Plane: disable TRIM_RC_AT_START by default --- ArduPlane/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 39fc63346d..1eab0e9d4c 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -971,7 +971,7 @@ const AP_Param::Info Plane::var_info[] PROGMEM = { // @Description: Automatically set roll/pitch trim from Tx at ground start. This makes the assumption that the RC transmitter has not been altered since trims were last captured. // @Values: 0:Disable,1:Enable // @User: Standard - GSCALAR(trim_rc_at_start, "TRIM_RC_AT_START", 1), + GSCALAR(trim_rc_at_start, "TRIM_RC_AT_START", 0), // barometer ground calibration. The GND_ prefix is chosen for // compatibility with previous releases of ArduPlane