AP_InertialSensor: 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 cad4bd41e9
commit a81b229997
1 changed files with 1 additions and 1 deletions

View File

@ -1340,7 +1340,7 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, Vector3f &
if (view != nullptr) {
// Use pitch to guess which axis the user is trying to trim
// 5 deg buffer to favor normal AHRS and avoid floating point funny business
if (fabsf(view->pitch) < (fabsf(AP::ahrs().pitch)+radians(5)) ) {
if (fabsf(view->pitch) < (fabsf(AP::ahrs().get_pitch())+radians(5)) ) {
// user is trying to calibrate view
rotation = view->get_rotation();
if (!is_zero(view->get_pitch_trim())) {