mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_OSD: show direction of the groundspeed vector
This commit is contained in:
parent
9f559d2f82
commit
90d6922de5
@ -263,8 +263,15 @@ void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
|
|||||||
|
|
||||||
void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
|
void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
|
||||||
{
|
{
|
||||||
float v = AP::ahrs().groundspeed() * 3.6;
|
Vector2f v = AP::ahrs().groundspeed_vector();
|
||||||
backend->write(x, y, false, "%3.0f%c", v, SYM_KMH);
|
float v_length = v.length();
|
||||||
|
char arrow = SYM_ARROW_START;
|
||||||
|
if (v_length > 1.0f) {
|
||||||
|
int32_t angle = wrap_360_cd(DEGX100 * atan2f(v.x, v.y));
|
||||||
|
int32_t interval = 36000 / SYM_ARROW_COUNT;
|
||||||
|
arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
|
||||||
|
}
|
||||||
|
backend->write(x, y, false, "%c%3.0f%c", arrow, v_length * 3.6, SYM_KMH);
|
||||||
}
|
}
|
||||||
|
|
||||||
//Thanks to betaflight/inav for simple and clean artificial horizon visual design
|
//Thanks to betaflight/inav for simple and clean artificial horizon visual design
|
||||||
|
Loading…
Reference in New Issue
Block a user