Browse Source

Plane: Make radio trim optional at ground start.

master
Michael Day 10 years ago committed by Andrew Tridgell
parent
commit
b02098e19e
  1. 3
      ArduPlane/Parameters.h
  2. 7
      ArduPlane/Parameters.pde
  3. 4
      ArduPlane/system.pde

3
ArduPlane/Parameters.h

@ -132,6 +132,7 @@ public: @@ -132,6 +132,7 @@ public:
k_param_stall_prevention,
k_param_optflow,
k_param_cli_enabled,
k_param_trim_rc_at_start,
// 100: Arming parameters
k_param_arming = 100,
@ -332,6 +333,8 @@ public: @@ -332,6 +333,8 @@ public:
AP_Int8 rtl_autoland;
AP_Int8 trim_rc_at_start;
// Feed-forward gains
//
AP_Float kff_rudder_mix;

7
ArduPlane/Parameters.pde

@ -923,6 +923,13 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -923,6 +923,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(rtl_autoland, "RTL_AUTOLAND", 0),
// @Param: RC_TRIM_AT_START
// @DisplayNmae: 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", 1),
// barometer ground calibration. The GND_ prefix is chosen for
// compatibility with previous releases of ArduPlane
// @Group: GND_

4
ArduPlane/system.pde

@ -261,7 +261,9 @@ static void startup_ground(void) @@ -261,7 +261,9 @@ static void startup_ground(void)
// read the radio to set trims
// ---------------------------
trim_radio(); // This was commented out as a HACK. Why? I don't find a problem.
if (g.trim_rc_at_start != 0) {
trim_radio();
}
// Save the settings for in-air restart
// ------------------------------------

Loading…
Cancel
Save