AC_AttControl: move freeze_ff to flags structure

This commit is contained in:
Randy Mackay 2014-06-06 13:30:45 +09:00
parent a662f87ffb
commit 4d4c7a2118
2 changed files with 8 additions and 8 deletions

View File

@ -312,11 +312,11 @@ void AC_PosControl::rate_to_accel_z()
// feed forward desired acceleration calculation
if (_dt > 0.0f) {
if(!_limit.freeze_ff_z) {
if (!_flags.freeze_ff_z) {
_accel_feedforward.z = (_vel_target.z - _vel_last.z)/_dt;
} else {
// stop the feed forward being calculated during a known discontinuity
_limit.freeze_ff_z = false;
_flags.freeze_ff_z = false;
}
} else {
_accel_feedforward.z = 0.0f;
@ -698,12 +698,12 @@ void AC_PosControl::rate_to_accel_xy(float dt)
// feed forward desired acceleration calculation
if (dt > 0.0f) {
if(!_limit.freeze_ff_xy) {
if (!_flags.freeze_ff_xy) {
_accel_feedforward.x = (_vel_target.x - _vel_last.x)/dt;
_accel_feedforward.y = (_vel_target.y - _vel_last.y)/dt;
} else {
// stop the feed forward being calculated during a known discontinuity
_limit.freeze_ff_xy = false;
_flags.freeze_ff_xy = false;
}
} else {
_accel_feedforward.x = 0.0f;

View File

@ -180,10 +180,10 @@ public:
void trigger_xy() { _flags.force_recalc_xy = true; }
/// freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity
void freeze_ff_z() { _limit.freeze_ff_z = true; }
void freeze_ff_z() { _flags.freeze_ff_z = true; }
/// freeze_ff_xy - used to stop the feed forward being calculated during a known discontinuity
void freeze_ff_xy() { _limit.freeze_ff_xy = true; }
void freeze_ff_xy() { _flags.freeze_ff_xy = true; }
// is_active_xy - returns true if the xy position controller has been run very recently
bool is_active_xy() const;
@ -240,6 +240,8 @@ private:
uint8_t reset_rate_to_accel_xy : 1; // 1 if we should reset the rate_to_accel_xy step
uint8_t reset_rate_to_accel_z : 1; // 1 if we should reset the rate_to_accel_z step
uint8_t reset_accel_to_throttle : 1; // 1 if we should reset the accel_to_throttle step of the z-axis controller
uint8_t freeze_ff_xy : 1; // 1 use to freeze feed forward during step updates
uint8_t freeze_ff_z : 1; // 1 use to freeze feed forward during step updates
} _flags;
// limit flags structure
@ -249,8 +251,6 @@ private:
uint8_t vel_up : 1; // 1 if we have hit the vertical velocity limit going up
uint8_t vel_down : 1; // 1 if we have hit the vertical velocity limit going down
uint8_t accel_xy : 1; // 1 if we have hit the horizontal accel limit
uint8_t freeze_ff_xy: 1; // 1 use to freeze feed forward during step updates
uint8_t freeze_ff_z : 1; // 1 use to freeze feed forward during step updates
} _limit;
///