AP_OSD:add aspect ratio correction for DisplayPort

This commit is contained in:
Henry Wurzburg 2023-02-10 18:18:56 -06:00 committed by Andrew Tridgell
parent a57e6455ab
commit ed5ca01e47
3 changed files with 13 additions and 3 deletions

View File

@ -26,7 +26,7 @@ class AP_OSD_Backend
public: public:
//constructor //constructor
AP_OSD_Backend(AP_OSD &osd): _osd(osd) {}; AP_OSD_Backend(AP_OSD &osd): _osd(osd) {}
//destructor //destructor
virtual ~AP_OSD_Backend(void) {} virtual ~AP_OSD_Backend(void) {}
@ -51,7 +51,7 @@ public:
virtual void clear() virtual void clear()
{ {
blink_phase = (blink_phase+1)%4; blink_phase = (blink_phase+1)%4;
}; }
// copy the backend specific symbol set to the OSD lookup table // copy the backend specific symbol set to the OSD lookup table
virtual void init_symbol_set(uint8_t *symbols, const uint8_t size); virtual void init_symbol_set(uint8_t *symbols, const uint8_t size);

View File

@ -133,4 +133,12 @@ AP_OSD_Backend *AP_OSD_MSP_DisplayPort::probe(AP_OSD &osd)
} }
return backend; return backend;
} }
// return a correction factor used to display angles correctly
float AP_OSD_MSP_DisplayPort::get_aspect_ratio_correction() const
{
return 12.0/18.0;
}
#endif #endif

View File

@ -28,6 +28,8 @@ public:
// used to initialize the uart in the correct thread // used to initialize the uart in the correct thread
void osd_thread_run_once() override; void osd_thread_run_once() override;
// return a correction factor used to display angles correctly
float get_aspect_ratio_correction() const override;
protected: protected:
uint8_t format_string_for_osd(char* dst, uint8_t size, bool decimal_packed, const char *fmt, va_list ap) override; uint8_t format_string_for_osd(char* dst, uint8_t size, bool decimal_packed, const char *fmt, va_list ap) override;
@ -211,4 +213,4 @@ private:
bool _blink_on; bool _blink_on;
}; };
#endif #endif