Skip to content

Commit

Permalink
Plane: multiplex parm set selection with tune selector channel
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Dec 28, 2023
1 parent 0e7165f commit 12a32cf
Show file tree
Hide file tree
Showing 4 changed files with 30 additions and 19 deletions.
16 changes: 0 additions & 16 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,6 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case AUX_FUNC::SERVOS_AUTO_TRIM:
case AUX_FUNC::EMERGENCY_LANDING_EN:
case AUX_FUNC::FW_AUTOTUNE:
case AUX_FUNC::TUNE_PARAM_SELECT:
break;

case AUX_FUNC::SOARING:
Expand Down Expand Up @@ -436,21 +435,6 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit
do_aux_function_armdisarm(ch_flag);
break;

case AUX_FUNC::TUNE_PARAM_SELECT: {
switch (ch_flag) {
case AuxSwitchPos::LOW:
plane.tuning.set_current_parmset(plane.tuning.get_parmset1());
break;
case AuxSwitchPos::MIDDLE:
plane.tuning.set_current_parmset(plane.tuning.get_parmset2());
break;
case AuxSwitchPos::HIGH:
plane.tuning.set_current_parmset(plane.tuning.get_parmset3());
break;
}
break;
}

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
}
Expand Down
29 changes: 28 additions & 1 deletion libraries/AP_Tuning/AP_Tuning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,33 @@ void AP_Tuning::check_selector_switch(void)
return;
}
uint16_t selector_in = selchan->get_radio_in();

int8_t parmset_switch_pos = -1;
if (selector_in < 1200) {
parmset_switch_pos = 0;
} else if (selector_in < 1400) {
parmset_switch_pos = 1;
} else if (selector_in < 1600) {
parmset_switch_pos = 2;
}

if (parmset_switch_pos > -1 && parmset_switch_pos != prev_parmset_switch_pos) {
int16_t new_parmset;
switch (parmset_switch_pos) {
case 0:
new_parmset = get_parmset1();
break;
case 1:
new_parmset = get_parmset2();
break;
case 2:
new_parmset = get_parmset3();
break;
}
set_current_parmset(new_parmset);
prev_parmset_switch_pos = parmset_switch_pos;
}

if (selector_in >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
// high selector
if (selector_start_ms == 0) {
Expand All @@ -92,7 +119,7 @@ void AP_Tuning::check_selector_switch(void)
changed = false;
need_revert = 0;
}
} else if (selector_in <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
} else if (selector_in < RC_Channel::AUX_PWM_TRIGGER_HIGH) {
// low selector
if (selector_start_ms != 0) {
uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Tuning/AP_Tuning.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,8 @@ class AP_Tuning
// the parameter we are tuning
uint8_t current_parm;

int8_t prev_parmset_switch_pos = -1;

// current index into the parameter set
uint8_t current_parm_index;

Expand Down
2 changes: 0 additions & 2 deletions libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -260,8 +260,6 @@ class RC_Channel {
MOUNT2_PITCH = 216, // mount3 pitch input
MOUNT2_YAW = 217, // mount4 yaw input

TUNE_PARAM_SELECT = 250,

// inputs 248-249 are reserved for the Skybrush fork at
// https://github.com/skybrush-io/ardupilot

Expand Down

0 comments on commit 12a32cf

Please sign in to comment.