mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Tuning: added TUNE_MODE_REVERT parameter
This commit is contained in:
parent
47c5eaa3ac
commit
fdac1d26cc
@ -40,6 +40,13 @@ const AP_Param::GroupInfo AP_Tuning::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RANGE", 5, AP_Tuning, range, 2.0f),
|
||||
|
||||
// @Param: MODE_REVERT
|
||||
// @DisplayName: Revert on mode change
|
||||
// @Description: This controls whether tuning values will revert on a flight mode change.
|
||||
// @Values: 0:Disable,1:Enable
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MODE_REVERT", 6, AP_Tuning, mode_revert, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -113,7 +120,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
||||
|
||||
// check for revert on changed flightmode
|
||||
if (flightmode != last_flightmode) {
|
||||
if (need_revert != 0) {
|
||||
if (need_revert != 0 && mode_revert != 0) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: reverted");
|
||||
revert_parameters();
|
||||
re_center();
|
||||
|
@ -45,6 +45,7 @@ private:
|
||||
AP_Int16 channel_max;
|
||||
AP_Int8 selector;
|
||||
AP_Float range;
|
||||
AP_Int8 mode_revert;
|
||||
|
||||
// when selector was triggered
|
||||
uint32_t selector_start_ms;
|
||||
|
Loading…
Reference in New Issue
Block a user