AP_OSD: make AHRS attitude member variables private

This commit is contained in:
Peter Barker 2024-01-12 23:40:23 +11:00 committed by Peter Barker
parent 49c697221a
commit 49bc553cda
1 changed files with 2 additions and 2 deletions

View File

@ -1571,7 +1571,7 @@ void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
float angle = 0;
const float length = v.length();
if (length > 1.0f) {
angle = atan2f(v.y, v.x) - ahrs.yaw;
angle = atan2f(v.y, v.x) - ahrs.get_yaw();
}
draw_speed(x + 1, y, angle, length);
}
@ -1822,7 +1822,7 @@ void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y)
if (check_option(AP_OSD::OPTION_INVERTED_WIND)) {
angle = M_PI;
}
angle = angle + atan2f(v.y, v.x) - ahrs.yaw;
angle = angle + atan2f(v.y, v.x) - ahrs.get_yaw();
}
draw_speed(x + 1, y, angle, length);