mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: fixed vector orientation
This commit is contained in:
parent
38c71bbfc7
commit
9702f4f822
|
@ -285,7 +285,7 @@ void AP_OSD_Screen::draw_speed_vector(uint8_t x, uint8_t y,Vector2f v, int32_t y
|
|||
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) - yaw);
|
||||
int32_t angle = wrap_360_cd(DEGX100 * atan2f(v.y, v.x) - yaw);
|
||||
int32_t interval = 36000 / SYM_ARROW_COUNT;
|
||||
arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue