mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
APM_Control: fixed build and merge errors
This commit is contained in:
parent
10ecffce01
commit
23d9c31b0a
@ -55,13 +55,13 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
|||||||
float bank_angle = _ahrs->roll;
|
float bank_angle = _ahrs->roll;
|
||||||
// limit bank angle between +- 80 deg if right way up
|
// limit bank angle between +- 80 deg if right way up
|
||||||
if (fabsf(bank_angle) < 1.5707964f) {
|
if (fabsf(bank_angle) < 1.5707964f) {
|
||||||
bank_angle = constrain(bank_angle,-1.3962634,1.3962634f);
|
bank_angle = constrain_float(bank_angle,-1.3962634f,1.3962634f);
|
||||||
}
|
}
|
||||||
if (!_ahrs->airspeed_estimate(&aspeed)) {
|
if (!_ahrs->airspeed_estimate(&aspeed)) {
|
||||||
// If no airspeed available use average of min and max
|
// If no airspeed available use average of min and max
|
||||||
aspeed = 0.5f*(float(aspd_min) + float(aspd_max));
|
aspeed = 0.5f*(float(aspd_min) + float(aspd_max));
|
||||||
}
|
}
|
||||||
rate_offset = fabsf(ToDeg((9.807f / constrain(aspeed , float(aspd_min), float(aspd_max))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
|
rate_offset = fabsf(ToDeg((9.807f / max(aspeed , float(aspd_min))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
|
||||||
|
|
||||||
//Calculate pitch angle error in centi-degrees
|
//Calculate pitch angle error in centi-degrees
|
||||||
int32_t angle_err = angle - _ahrs->pitch_sensor;
|
int32_t angle_err = angle - _ahrs->pitch_sensor;
|
||||||
@ -82,16 +82,8 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
|||||||
// Get body rate vector (radians/sec)
|
// Get body rate vector (radians/sec)
|
||||||
float omega_y = _ahrs->get_gyro().y;
|
float omega_y = _ahrs->get_gyro().y;
|
||||||
|
|
||||||
// Apply a first order lowpass filter with a 20Hz cut-off
|
|
||||||
// Coefficients derived using a first order hold discretisation method
|
|
||||||
// Use of FOH discretisation increases high frequency noise rejection
|
|
||||||
// and reduces phase loss compared to other methods
|
|
||||||
float rate = 0.0810026f * _last_rate_out + 0.6343426f * omega_y + 0.2846549f * _last_rate_in;
|
|
||||||
_last_rate_out = rate;
|
|
||||||
_last_rate_in = omega_y;
|
|
||||||
|
|
||||||
// Calculate the pitch rate error (deg/sec) and scale
|
// Calculate the pitch rate error (deg/sec) and scale
|
||||||
float rate_error = (desired_rate - ToDeg(rate)) * scaler;
|
float rate_error = (desired_rate - ToDeg(omega_y)) * scaler;
|
||||||
|
|
||||||
// Multiply pitch rate error by _ki_rate and integrate
|
// Multiply pitch rate error by _ki_rate and integrate
|
||||||
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
|
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
|
||||||
@ -114,11 +106,10 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
|||||||
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
||||||
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
||||||
// This is because acceleration scales with speed^2, but rate scales with speed.
|
// This is because acceleration scales with speed^2, but rate scales with speed.
|
||||||
float _last_out = ( (rate_error * _kp_rate) + _integrator + (desired_rate * _kp_ff) ) * scaler;
|
_last_out = ( (rate_error * _kp_rate) + _integrator + (desired_rate * _kp_ff) ) * scaler;
|
||||||
|
|
||||||
// Convert to centi-degrees and constrain
|
// Convert to centi-degrees and constrain
|
||||||
float out = constrain(_last_out * 100, -4500, 4500);
|
return constrain_float(_last_out * 100, -4500, 4500);
|
||||||
return out;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_PitchController::reset_I()
|
void AP_PitchController::reset_I()
|
||||||
|
@ -30,8 +30,6 @@ private:
|
|||||||
AP_Int16 _max_rate_neg;
|
AP_Int16 _max_rate_neg;
|
||||||
AP_Float _roll_ff;
|
AP_Float _roll_ff;
|
||||||
uint32_t _last_t;
|
uint32_t _last_t;
|
||||||
float _last_rate_in;
|
|
||||||
float _last_rate_out;
|
|
||||||
float _last_out;
|
float _last_out;
|
||||||
|
|
||||||
float _integrator;
|
float _integrator;
|
||||||
|
@ -57,16 +57,8 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
|
|||||||
// Get body rate vector (radians/sec)
|
// Get body rate vector (radians/sec)
|
||||||
float omega_x = _ahrs->get_gyro().x;
|
float omega_x = _ahrs->get_gyro().x;
|
||||||
|
|
||||||
// Apply a first order lowpass filter with a 20Hz cut-off
|
|
||||||
// Coefficients derived using a first order hold discretisation method
|
|
||||||
// Use of FOH discretisation increases high frequency noise rejection
|
|
||||||
// and reduces phase loss compared to other methods
|
|
||||||
float rate = 0.0810026f * _last_rate_out + 0.6343426f * omega_x + 0.2846549f * _last_rate_in;
|
|
||||||
_last_rate_out = rate;
|
|
||||||
_last_rate_in = omega_x;
|
|
||||||
|
|
||||||
// Calculate the roll rate error (deg/sec) and apply gain scaler
|
// Calculate the roll rate error (deg/sec) and apply gain scaler
|
||||||
float rate_error = (desired_rate - ToDeg(rate)) * scaler;
|
float rate_error = (desired_rate - ToDeg(omega_x)) * scaler;
|
||||||
|
|
||||||
// Get an airspeed estimate - default to zero if none available
|
// Get an airspeed estimate - default to zero if none available
|
||||||
float aspeed;
|
float aspeed;
|
||||||
@ -93,11 +85,10 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
|
|||||||
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
||||||
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
||||||
// This is because acceleration scales with speed^2, but rate scales with speed.
|
// This is because acceleration scales with speed^2, but rate scales with speed.
|
||||||
float _last_out = ( (rate_error * _kp_rate) + _integrator + (desired_rate * _kp_ff) ) * scaler;
|
_last_out = ( (rate_error * _kp_rate) + _integrator + (desired_rate * _kp_ff) ) * scaler;
|
||||||
|
|
||||||
// Convert to centi-degrees and constrain
|
// Convert to centi-degrees and constrain
|
||||||
float out = constrain(_last_out * 100, -4500, 4500);
|
return constrain_float(_last_out * 100, -4500, 4500);
|
||||||
return out;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_RollController::reset_I()
|
void AP_RollController::reset_I()
|
||||||
|
@ -28,8 +28,6 @@ private:
|
|||||||
AP_Float _ki_rate;
|
AP_Float _ki_rate;
|
||||||
AP_Int16 _max_rate;
|
AP_Int16 _max_rate;
|
||||||
uint32_t _last_t;
|
uint32_t _last_t;
|
||||||
float _last_rate_in;
|
|
||||||
float _last_rate_out;
|
|
||||||
float _last_out;
|
float _last_out;
|
||||||
|
|
||||||
float _integrator;
|
float _integrator;
|
||||||
|
@ -44,31 +44,23 @@ int32_t AP_YawController::get_servo_out(float scaler, bool stabilize, int16_t as
|
|||||||
float bank_angle = _ahrs->roll;
|
float bank_angle = _ahrs->roll;
|
||||||
// limit bank angle between +- 80 deg if right way up
|
// limit bank angle between +- 80 deg if right way up
|
||||||
if (fabsf(bank_angle) < 1.5707964f) {
|
if (fabsf(bank_angle) < 1.5707964f) {
|
||||||
bank_angle = constrain(bank_angle,-1.3962634,1.3962634f);
|
bank_angle = constrain_float(bank_angle,-1.3962634f,1.3962634f);
|
||||||
}
|
}
|
||||||
if (!_ahrs->airspeed_estimate(&aspeed)) {
|
if (!_ahrs->airspeed_estimate(&aspeed)) {
|
||||||
// If no airspeed available use average of min and max
|
// If no airspeed available use average of min and max
|
||||||
aspeed = 0.5f*(float(aspd_min) + float(aspd_max));
|
aspeed = 0.5f*(float(aspd_min) + float(aspd_max));
|
||||||
}
|
}
|
||||||
rate_offset = (9.807f / constrain(aspeed , float(aspd_min), float(aspd_max))) * tanf(bank_angle) * cosf(bank_angle) * _K_FF;
|
rate_offset = (9.807f / max(aspeed , float(aspd_min))) * tanf(bank_angle) * cosf(bank_angle) * _K_FF;
|
||||||
|
|
||||||
// Get body rate vector (radians/sec)
|
// Get body rate vector (radians/sec)
|
||||||
float omega_z = _ahrs->get_gyro();
|
float omega_z = _ahrs->get_gyro().z;
|
||||||
|
|
||||||
// Apply a first order lowpass filter with a 20Hz cut-off
|
|
||||||
// Coefficients derived using a first order hold discretisation method
|
|
||||||
// Use of FOH discretisation increases high frequency noise rejection
|
|
||||||
// and reduces phase loss compared to other methods
|
|
||||||
float rate = 0.0810026f * _last_rate_out + 0.6343426f * omega_z + 0.2846549f * _last_rate_in;
|
|
||||||
_last_rate_out = rate;
|
|
||||||
_last_rate_in = omega_z;
|
|
||||||
|
|
||||||
// Get the accln vector (m/s^2)
|
// Get the accln vector (m/s^2)
|
||||||
float accel_y = _ins->get_accel().y;
|
float accel_y = _ins->get_accel().y;
|
||||||
|
|
||||||
// Subtract the steady turn component of rate from the measured rate
|
// Subtract the steady turn component of rate from the measured rate
|
||||||
// to calculate the rate relative to the turn requirement in degrees/sec
|
// to calculate the rate relative to the turn requirement in degrees/sec
|
||||||
float rate_hp_in = ToDeg(rate - rate_offset);
|
float rate_hp_in = ToDeg(omega_z - rate_offset);
|
||||||
|
|
||||||
// Apply a high-pass filter to the rate to washout any steady state error
|
// Apply a high-pass filter to the rate to washout any steady state error
|
||||||
// due to bias errors in rate_offset
|
// due to bias errors in rate_offset
|
||||||
@ -112,8 +104,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool stabilize, int16_t as
|
|||||||
_last_out = _K_D * (_integrator - rate_hp_out) * scaler * scaler;
|
_last_out = _K_D * (_integrator - rate_hp_out) * scaler * scaler;
|
||||||
|
|
||||||
// Convert to centi-degrees and constrain
|
// Convert to centi-degrees and constrain
|
||||||
float out = constrain(_last_out * 100, -4500, 4500);
|
return constrain_float(_last_out * 100, -4500, 4500);
|
||||||
return out;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_YawController::reset_I()
|
void AP_YawController::reset_I()
|
||||||
|
@ -32,8 +32,6 @@ private:
|
|||||||
AP_Float _K_FF;
|
AP_Float _K_FF;
|
||||||
uint32_t _last_t;
|
uint32_t _last_t;
|
||||||
float _last_error;
|
float _last_error;
|
||||||
float _last_rate_in;
|
|
||||||
float _last_rate_out;
|
|
||||||
float _last_out;
|
float _last_out;
|
||||||
float _last_rate_hp_out;
|
float _last_rate_hp_out;
|
||||||
float _last_rate_hp_in;
|
float _last_rate_hp_in;
|
||||||
|
Loading…
Reference in New Issue
Block a user