Plane: removed TRIM_RC_AT_START parameter

this option caused a lot more problems than it solved, and is buggy
This commit is contained in:
Andrew Tridgell 2017-08-26 20:16:09 +10:00
parent 1a207c919b
commit d541ac509f
3 changed files with 1 additions and 15 deletions

View File

@ -884,13 +884,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Standard
GSCALAR(rtl_autoland, "RTL_AUTOLAND", 0),
// @Param: RC_TRIM_AT_START
// @DisplayName: RC Trims auto set at start.
// @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", 0),
// @Param: CRASH_ACC_THRESH
// @DisplayName: Crash Deceleration Threshold
// @Description: X-Axis deceleration threshold to notify the crash detector that there was a possible impact which helps disarm the motor quickly after a crash. This value should be much higher than normal negative x-axis forces during normal flight, check flight log files to determine the average IMU.x values for your aircraft and motor type. Higher value means less sensative (triggers on higher impact). For electric planes that don't vibrate much during fight a value of 25 is good (that's about 2.5G). For petrol/nitro planes you'll want a higher value. Set to 0 to disable the collision detector.

View File

@ -135,7 +135,7 @@ public:
k_param_stall_prevention,
k_param_optflow,
k_param_cli_enabled_old, // unused - CLI removed
k_param_trim_rc_at_start,
k_param_trim_rc_at_start, // unused
k_param_hil_mode,
k_param_land_disarm_delay, // unused - moved to AP_Landing
k_param_glide_slope_threshold,
@ -366,7 +366,6 @@ public:
AP_Int8 rtl_autoland;
AP_Int8 trim_rc_at_start;
AP_Int8 crash_accel_threshold;
// Feed-forward gains

View File

@ -224,12 +224,6 @@ void Plane::startup_ground(void)
//
startup_INS_ground();
// read the radio to set trims
// ---------------------------
if (g.trim_rc_at_start != 0) {
trim_radio();
}
// Save the settings for in-air restart
// ------------------------------------
//save_EEPROM_groundstart();