Skip to content

Commit

Permalink
Just notes and stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Aug 4, 2024
1 parent 4938a6b commit 7ec1f90
Show file tree
Hide file tree
Showing 15 changed files with 1,474 additions and 25 deletions.
1 change: 1 addition & 0 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -807,6 +807,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
#if AUTOTUNE_ENABLED == ENABLED
// save auto tuned parameters
if (copter.flightmode == &copter.mode_autotune) {
// it may be difficult to remove this without loosing the current capability
copter.mode_autotune.save_tuning_gains();
} else {
copter.mode_autotune.reset();
Expand Down
33 changes: 31 additions & 2 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,8 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
// the following functions do not need to be initialised:
case AUX_FUNC::ALTHOLD:
case AUX_FUNC::AUTO:
case AUX_FUNC::AUTOTUNE:
case AUX_FUNC::AUTOTUNE_MODE:
case AUX_FUNC::AUTOTUNE_SWITCH:
case AUX_FUNC::BRAKE:
case AUX_FUNC::CIRCLE:
case AUX_FUNC::DRIFT:
Expand Down Expand Up @@ -290,9 +291,37 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
#endif

#if AUTOTUNE_ENABLED == ENABLED
case AUX_FUNC::AUTOTUNE:
case AUX_FUNC::AUTOTUNE_MODE:
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
break;
case AUX_FUNC::AUTOTUNE_SWITCH:
switch(ch_flag) {
// this could also work as a two position switch by switching into Autotune using the mode switch.
// The switch wouldn't do anything if autotune had not completed.
// some challenges there to get that stretch goal
case AuxSwitchPos::LOW:
// load and save if required original gains
// we could leave the current save on disarm and only switch
copter.mode_autotune.autotune.load_orig_gains(); // this currently doesn't save the gains
// what we do with the mode is an open question
// can we switch back to the previous mode
break;
case AuxSwitchPos::MIDDLE:
// change to mode autotune or do nothing if tune is complete
if (copter.mode_autotune.autotune.) {
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
}
break;
case AuxSwitchPos::HIGH:
// load and save if required tuned gains if tuning is complete
// we could leave the current save on disarm and only switch
// we would need to change the save on disarm anyway to save the current settings not the tuned settings, but we need to maintain the ability to run autotune without the switch.
copter.mode_autotune.autotune.load_tuned_gains(); // this currently doesn't save the gains
// what we do with the mode is an open question
// can we switch back to the previous mode
break;
}
break;
#endif

case AUX_FUNC::LAND:
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/mode_autotune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,8 @@ void ModeAutoTune::run()

void ModeAutoTune::save_tuning_gains()
{
// is this too many parameters to save all at once.
// There could be 30 parameters right now. Maybe more in the future if we add tuning for other controllers.
autotune.save_tuning_gains();
}

Expand Down
Binary file added Tools/bootloaders/FSOPowerStack_bl.bin
Binary file not shown.
Loading

0 comments on commit 7ec1f90

Please sign in to comment.