diff --git a/libraries/AP_OSD/AP_OSD_Backend.h b/libraries/AP_OSD/AP_OSD_Backend.h index b52cf9b701ab3..30e638f1f10f9 100644 --- a/libraries/AP_OSD/AP_OSD_Backend.h +++ b/libraries/AP_OSD/AP_OSD_Backend.h @@ -26,7 +26,7 @@ class AP_OSD_Backend public: //constructor - AP_OSD_Backend(AP_OSD &osd): _osd(osd) {}; + AP_OSD_Backend(AP_OSD &osd): _osd(osd) {} //destructor virtual ~AP_OSD_Backend(void) {} @@ -51,7 +51,7 @@ class AP_OSD_Backend virtual void clear() { blink_phase = (blink_phase+1)%4; - }; + } // copy the backend specific symbol set to the OSD lookup table virtual void init_symbol_set(uint8_t *symbols, const uint8_t size); diff --git a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp index 8a9191e8d8fa6..0e46dfc2cd784 100644 --- a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp +++ b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp @@ -133,4 +133,12 @@ AP_OSD_Backend *AP_OSD_MSP_DisplayPort::probe(AP_OSD &osd) } 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 diff --git a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h index a273edd5db6ec..2cc81eba279c0 100644 --- a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h +++ b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h @@ -28,6 +28,8 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend // used to initialize the uart in the correct thread void osd_thread_run_once() override; + // return a correction factor used to display angles correctly + float get_aspect_ratio_correction() const override; protected: 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 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend bool _blink_on; }; -#endif \ No newline at end of file +#endif