Sub: Remove frame_orientation parameter
This commit is contained in:
parent
eeadfa0d92
commit
cfaf08ad31
@ -418,13 +418,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Range: 0 32767
|
||||
GSCALAR(radio_tuning_high, "TUNE_HIGH", 1000),
|
||||
|
||||
// @Param: FRAME
|
||||
// @DisplayName: Frame Orientation (+, X or V)
|
||||
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
|
||||
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B (New)
|
||||
// @User: Standard
|
||||
GSCALAR(frame_orientation, "FRAME", AP_MOTORS_X_FRAME),
|
||||
|
||||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||
|
@ -160,7 +160,6 @@ public:
|
||||
//
|
||||
k_param_compass_enabled,
|
||||
k_param_compass,
|
||||
k_param_frame_orientation,
|
||||
k_param_fs_batt_voltage,
|
||||
k_param_ch7_option,
|
||||
k_param_super_simple = 155,
|
||||
@ -366,7 +365,6 @@ public:
|
||||
AP_Int8 radio_tuning;
|
||||
AP_Int16 radio_tuning_high;
|
||||
AP_Int16 radio_tuning_low;
|
||||
AP_Int8 frame_orientation;
|
||||
AP_Int8 ch7_option;
|
||||
AP_Int8 ch8_option;
|
||||
AP_Int8 ch9_option;
|
||||
|
Loading…
Reference in New Issue
Block a user