mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OSD: make AHRS attitude member variables private
This commit is contained in:
parent
49c697221a
commit
49bc553cda
@ -1571,7 +1571,7 @@ void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
|
|||||||
float angle = 0;
|
float angle = 0;
|
||||||
const float length = v.length();
|
const float length = v.length();
|
||||||
if (length > 1.0f) {
|
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);
|
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)) {
|
if (check_option(AP_OSD::OPTION_INVERTED_WIND)) {
|
||||||
angle = M_PI;
|
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);
|
draw_speed(x + 1, y, angle, length);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user