APM_Control: make AHRS attitude member variables private

This commit is contained in:
Peter Barker 2024-01-12 23:40:22 +11:00 committed by Peter Barker
parent c821726bf4
commit 71a00dc733
3 changed files with 6 additions and 6 deletions

View File

@ -273,7 +273,7 @@ float AP_PitchController::get_rate_out(float desired_rate, float scaler)
float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const
{
float rate_offset;
float bank_angle = AP::ahrs().roll;
float bank_angle = AP::ahrs().get_roll();
// limit bank angle between +- 80 deg if right way up
if (fabsf(bank_angle) < radians(90)) {
@ -296,7 +296,7 @@ float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inv
// don't do turn coordination handling when at very high pitch angles
rate_offset = 0;
} else {
rate_offset = cosf(_ahrs.pitch)*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
rate_offset = cosf(_ahrs.get_pitch())*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
}
if (inverted) {
rate_offset = -rate_offset;

View File

@ -206,7 +206,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
// Calculate yaw rate required to keep up with a constant height coordinated turn
float aspeed;
float rate_offset;
float bank_angle = AP::ahrs().roll;
float bank_angle = AP::ahrs().get_roll();
// limit bank angle between +- 80 deg if right way up
if (fabsf(bank_angle) < 1.5707964f) {
bank_angle = constrain_float(bank_angle,-1.3962634f,1.3962634f);

View File

@ -613,7 +613,7 @@ float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate
// return a desired turn-rate given a desired heading in radians
float AR_AttitudeControl::get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const
{
const float yaw_error = wrap_PI(heading_rad - AP::ahrs().yaw);
const float yaw_error = wrap_PI(heading_rad - AP::ahrs().get_yaw());
// Calculate the desired turn rate (in radians) from the angle error (also in radians)
float desired_rate = _steer_angle_p.get_p(yaw_error);
@ -884,7 +884,7 @@ float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float
}
// initialise output to feed forward from current pitch angle
const float pitch_rad = AP::ahrs().pitch;
const float pitch_rad = AP::ahrs().get_pitch();
float output = sinf(pitch_rad) * _pitch_to_throttle_ff;
// add regular PID control
@ -940,7 +940,7 @@ float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt)
}
_heel_controller_last_ms = now;
_sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().roll), dt);
_sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().get_roll()), dt);
// get feed-forward
const float ff = _sailboat_heel_pid.get_ff();