diff --git a/libraries/AP_HAL_F4Light/hardware/osd/osd.cpp b/libraries/AP_HAL_F4Light/hardware/osd/osd.cpp index 27421ecee9..b27803bbe6 100644 --- a/libraries/AP_HAL_F4Light/hardware/osd/osd.cpp +++ b/libraries/AP_HAL_F4Light/hardware/osd/osd.cpp @@ -44,6 +44,8 @@ using namespace F4Light; namespace OSDns { +class BetterStream : AP_HAL::BetterStream {}; + #include "osd_core/GCS_MAVLink.h" #include "osd_core/OSD_Max7456.h" diff --git a/libraries/AP_HAL_F4Light/hardware/osd/osd.h b/libraries/AP_HAL_F4Light/hardware/osd/osd.h index 1107e20735..55aa1a9f52 100644 --- a/libraries/AP_HAL_F4Light/hardware/osd/osd.h +++ b/libraries/AP_HAL_F4Light/hardware/osd/osd.h @@ -16,7 +16,6 @@ extern const AP_HAL::HAL& hal; #include "osd_core/compat.h" #include "osd_core/Defs.h" - #define OSD_LOW_PRIORITY 115 // 15 less than main task so runs almost only in delay() time - 1/16 of main thread #define OSD_HIGH_PRIORITY 99 // 1 more than main so uses 2/3 of CPU @@ -37,5 +36,7 @@ namespace OSDns {// OSD interface emulates UART void update_max_buffer(const uint8_t *buffer, uint16_t len); inline uint32_t millis(){ return AP_HAL::millis(); } + + class BetterStream; } #endif diff --git a/libraries/AP_HAL_F4Light/hardware/osd/osd_core/Params.h b/libraries/AP_HAL_F4Light/hardware/osd/osd_core/Params.h index 730a2d9764..4c8291b725 120000 --- a/libraries/AP_HAL_F4Light/hardware/osd/osd_core/Params.h +++ b/libraries/AP_HAL_F4Light/hardware/osd/osd_core/Params.h @@ -1 +1 @@ -/mnt/disk_d/src/quad-copter/minimosd-extra/MinimOsd_Extra/Params.h \ No newline at end of file +../../../support/minimosd-extra/MinimOsd_Extra/Params.h \ No newline at end of file diff --git a/libraries/AP_HAL_F4Light/hardware/osd/osd_core/compat.h b/libraries/AP_HAL_F4Light/hardware/osd/osd_core/compat.h index 3426d67ae2..ecff8642c6 100644 --- a/libraries/AP_HAL_F4Light/hardware/osd/osd_core/compat.h +++ b/libraries/AP_HAL_F4Light/hardware/osd/osd_core/compat.h @@ -31,6 +31,7 @@ typedef const char * PGM_P; #define TO_STRING2(x) #x #define TO_STRING(x) TO_STRING2(x) + static inline int max(int a, int b){ if(a>b) return a; return b;