mirror of https://github.com/ArduPilot/ardupilot
AP_OSD:add aspect ratio correction for DisplayPort
This commit is contained in:
parent
a57e6455ab
commit
ed5ca01e47
|
@ -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 @@ public:
|
|||
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);
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -28,6 +28,8 @@ public:
|
|||
// 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 @@ private:
|
|||
|
||||
bool _blink_on;
|
||||
};
|
||||
#endif
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue