Browse Source

Plane: move from FLAP_IN_CHANNEL to RCx_Option

c415-sdk
Peter Hall 5 years ago committed by Andrew Tridgell
parent
commit
660c9a8a60
  1. 21
      ArduPlane/Parameters.cpp
  2. 3
      ArduPlane/Parameters.h
  3. 5
      ArduPlane/RC_Channel.cpp
  4. 2
      ArduPlane/servos.cpp

21
ArduPlane/Parameters.cpp

@ -760,12 +760,6 @@ const AP_Param::Info Plane::var_info[] = { @@ -760,12 +760,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: User
GSCALAR(FBWB_min_altitude_cm, "ALT_HOLD_FBWCM", ALT_HOLD_FBW_CM),
// @Param: FLAP_IN_CHANNEL
// @DisplayName: Flap input channel
// @Description: An RC input channel to use for flaps control. If this is set to a RC channel number then that channel will be used for manual flaps control. When enabled, the percentage of flaps is taken as the percentage travel from the TRIM value of the channel to the MIN value of the channel. A value above the TRIM values will give inverse flaps (spoilers). This option needs to be enabled in conjunction with a FUNCTION setting on an output channel to one of the flap functions. When a FLAP_IN_CHANNEL is combined with auto-flaps the higher of the two flap percentages is taken.
// @User: User
GSCALAR(flapin_channel, "FLAP_IN_CHANNEL", 0),
// @Param: FLAP_1_PERCNT
// @DisplayName: Flap 1 percentage
// @Description: The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps
@ -1371,6 +1365,21 @@ void Plane::load_parameters(void) @@ -1371,6 +1365,21 @@ void Plane::load_parameters(void)
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_PLANE);
// Convert flap to RCx_OPTION
AP_Int8 flap_output;
AP_Param::ConversionInfo flap_info = {
Parameters::k_param_flapin_channel_old,
0,
AP_PARAM_INT8,
nullptr
};
if (AP_Param::find_old_parameter(&flap_info, &flap_output) && flap_output.get() != 0) {
RC_Channel *flapin = rc().channel(flap_output - 1);
if (flapin != nullptr && !flapin->option.configured()) {
flapin->option.set_and_save((int16_t)RC_Channel::AUX_FUNC::FLAP); // save the new param
}
}
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}

3
ArduPlane/Parameters.h

@ -99,7 +99,7 @@ public: @@ -99,7 +99,7 @@ public:
k_param_log_bitmask,
k_param_BoardConfig,
k_param_rssi_range, // unused, replaced by rssi_ library parameters
k_param_flapin_channel,
k_param_flapin_channel_old, // unused, moved to RC_OPTION
k_param_flaperon_output, // unused
k_param_gps,
k_param_autotune_level,
@ -478,7 +478,6 @@ public: @@ -478,7 +478,6 @@ public:
AP_Int8 takeoff_throttle_slewrate;
AP_Float takeoff_pitch_limit_reduction_sec;
AP_Int8 level_roll_limit;
AP_Int8 flapin_channel;
#if AP_TERRAIN_AVAILABLE
AP_Int8 terrain_follow;
AP_Int16 terrain_lookahead;

5
ArduPlane/RC_Channel.cpp

@ -61,9 +61,10 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, @@ -61,9 +61,10 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case AUX_FUNC::ARMDISARM:
case AUX_FUNC::AUTO:
case AUX_FUNC::CIRCLE:
case AUX_FUNC::LOITER:
case AUX_FUNC::FLAP:
case AUX_FUNC::GUIDED:
case AUX_FUNC::INVERTED:
case AUX_FUNC::LOITER:
case AUX_FUNC::MANUAL:
case AUX_FUNC::RTL:
case AUX_FUNC::TAKEOFF:
@ -128,6 +129,8 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_swi @@ -128,6 +129,8 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_swi
do_aux_function_change_mode(Mode::Number::TAKEOFF, ch_flag);
break;
case AUX_FUNC::FLAP:
break; // flap input label, nothing to do
default:
RC_Channel::do_aux_function(ch_option, ch_flag);

2
ArduPlane/servos.cpp

@ -492,7 +492,7 @@ void Plane::set_servos_flaps(void) @@ -492,7 +492,7 @@ void Plane::set_servos_flaps(void)
int8_t manual_flap_percent = 0;
// work out any manual flap input
RC_Channel *flapin = RC_Channels::rc_channel(g.flapin_channel-1);
RC_Channel *flapin = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FLAP);
if (flapin != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) {
manual_flap_percent = flapin->percent_input();
}

Loading…
Cancel
Save