AC_AutoTune: stop specifying bit-widths for state

new: bin/arducopter  1670916  2544  194276  1867736
master: bin/arducopter  1671232  2544  194272  1868048

   new: bin/arduplane  1670692  2452  194364  1867508
master: bin/arduplane  1671012  2452  194364  1867828
This commit is contained in:
Peter Barker 2021-09-27 11:18:04 +10:00 committed by Andrew Tridgell
parent a350ebb358
commit 8d00152815
1 changed files with 10 additions and 10 deletions

View File

@ -158,16 +158,16 @@ private:
};
void load_gains(enum GainType gain_type);
TuneMode mode : 2; // see TuneMode for what modes are allowed
bool pilot_override : 1; // true = pilot is overriding controls so we suspend tuning temporarily
AxisType axis : 2; // see AxisType for which things can be tuned
bool positive_direction : 1; // false = tuning in negative direction (i.e. left for roll), true = positive direction (i.e. right for roll)
StepType step : 2; // see StepType for what steps are performed
TuneType tune_type : 3; // see TuneType
bool ignore_next : 1; // true = ignore the next test
bool twitch_first_iter : 1; // true on first iteration of a twitch (used to signal we must step the attitude or rate target)
bool use_poshold : 1; // true = enable position hold
bool have_position : 1; // true = start_position is value
TuneMode mode; // see TuneMode for what modes are allowed
bool pilot_override; // true = pilot is overriding controls so we suspend tuning temporarily
AxisType axis; // see AxisType for which things can be tuned
bool positive_direction; // false = tuning in negative direction (i.e. left for roll), true = positive direction (i.e. right for roll)
StepType step; // see StepType for what steps are performed
TuneType tune_type; // see TuneType
bool ignore_next; // true = ignore the next test
bool twitch_first_iter; // true on first iteration of a twitch (used to signal we must step the attitude or rate target)
bool use_poshold; // true = enable position hold
bool have_position; // true = start_position is value
Vector3f start_position;
uint8_t axes_completed; // bitmask of completed axes