mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
AP_OSD: fixed horizon roll/pitch signs
This commit is contained in:
parent
b9d36f1a77
commit
70829e67ce
@ -256,8 +256,8 @@ void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
|
|||||||
void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
|
void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
|
||||||
{
|
{
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
float roll = -ahrs.roll;
|
float roll = ahrs.roll;
|
||||||
float pitch = ahrs.pitch;
|
float pitch = -ahrs.pitch;
|
||||||
|
|
||||||
roll = constrain_float(roll, -ah_max_roll, ah_max_roll);
|
roll = constrain_float(roll, -ah_max_roll, ah_max_roll);
|
||||||
pitch = constrain_float(pitch, -ah_max_pitch, ah_max_pitch);
|
pitch = constrain_float(pitch, -ah_max_pitch, ah_max_pitch);
|
||||||
|
Loading…
Reference in New Issue
Block a user