mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: apply aspect ratio correction to horizon
This commit is contained in:
parent
9d01fc6ff6
commit
3a0329822a
|
@ -42,6 +42,9 @@ public:
|
|||
//update screen
|
||||
virtual void flush() = 0;
|
||||
|
||||
// return a correction factor used to display angles correctly
|
||||
virtual float get_aspect_ratio_correction() const {return 1;}
|
||||
|
||||
//clear screen
|
||||
//should match hw blink
|
||||
virtual void clear()
|
||||
|
@ -70,6 +73,12 @@ protected:
|
|||
}
|
||||
|
||||
int8_t blink_phase;
|
||||
|
||||
enum vid_format {
|
||||
FORMAT_UNKNOWN = 0,
|
||||
FORMAT_NTSC = 1,
|
||||
FORMAT_PAL = 2,
|
||||
} _format;
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -322,9 +322,11 @@ void AP_OSD_MAX7456::reinit()
|
|||
if (VIN_IS_PAL(sense)) {
|
||||
video_signal_reg = VIDEO_MODE_PAL | OSD_ENABLE;
|
||||
video_lines = video_lines_pal;
|
||||
_format = FORMAT_PAL;
|
||||
} else {
|
||||
video_signal_reg = VIDEO_MODE_NTSC | OSD_ENABLE;
|
||||
video_lines = video_lines_ntsc;
|
||||
_format = FORMAT_NTSC;
|
||||
}
|
||||
|
||||
// set all rows to same character black/white level
|
||||
|
@ -461,3 +463,18 @@ void AP_OSD_MAX7456::write(uint8_t x, uint8_t y, const char* text)
|
|||
++x;
|
||||
}
|
||||
}
|
||||
|
||||
// return a correction factor used to display angles correctly
|
||||
float AP_OSD_MAX7456::get_aspect_ratio_correction() const
|
||||
{
|
||||
switch (_format) {
|
||||
case FORMAT_NTSC:
|
||||
return 12.0f/18.46f;
|
||||
|
||||
case FORMAT_PAL:
|
||||
return 12.0f/15.0f;
|
||||
|
||||
default:
|
||||
return 1.0f;
|
||||
};
|
||||
}
|
||||
|
|
|
@ -37,6 +37,9 @@ public:
|
|||
//clear framebuffer
|
||||
void clear() override;
|
||||
|
||||
// return a correction factor used to display angles correctly
|
||||
float get_aspect_ratio_correction() const override;
|
||||
|
||||
private:
|
||||
|
||||
//constructor
|
||||
|
|
|
@ -1101,9 +1101,11 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
|
|||
float ky = sinf(roll);
|
||||
float kx = cosf(roll);
|
||||
|
||||
float ratio = backend->get_aspect_ratio_correction();
|
||||
|
||||
if (fabsf(ky) < fabsf(kx)) {
|
||||
for (int dx = -4; dx <= 4; dx++) {
|
||||
float fy = dx * (ky/kx) + pitch * ah_pitch_rad_to_char + 0.5f;
|
||||
float fy = (ratio * dx) * (ky/kx) + pitch * ah_pitch_rad_to_char + 0.5f;
|
||||
int dy = floorf(fy);
|
||||
char c = (fy - dy) * SYM_AH_H_COUNT;
|
||||
//chars in font in reversed order
|
||||
|
@ -1114,7 +1116,7 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
|
|||
}
|
||||
} else {
|
||||
for (int dy=-4; dy<=4; dy++) {
|
||||
float fx = (dy - pitch * ah_pitch_rad_to_char) * (kx/ky) + 0.5f;
|
||||
float fx = ((dy / ratio) - pitch * ah_pitch_rad_to_char) * (kx/ky) + 0.5f;
|
||||
int dx = floorf(fx);
|
||||
char c = (fx - dx) * SYM_AH_V_COUNT;
|
||||
c = SYM_AH_V_START + c;
|
||||
|
|
Loading…
Reference in New Issue