Merge pull request #1283 from jflyper/bfdev-smartaudio
Add TBS SmartAudio support
This commit is contained in:
commit
3cc85e83e7
4
Makefile
4
Makefile
|
@ -606,6 +606,7 @@ HIGHEND_SRC = \
|
|||
telemetry/ltm.c \
|
||||
telemetry/mavlink.c \
|
||||
sensors/esc_sensor.c \
|
||||
io/vtx_smartaudio.c
|
||||
|
||||
SPEED_OPTIMISED_SRC := ""
|
||||
SIZE_OPTIMISED_SRC := ""
|
||||
|
@ -709,7 +710,8 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
|||
cms/cms_menu_ledstrip.c \
|
||||
cms/cms_menu_misc.c \
|
||||
cms/cms_menu_osd.c \
|
||||
cms/cms_menu_vtx.c
|
||||
cms/cms_menu_vtx.c \
|
||||
io/vtx_smartaudio.c
|
||||
endif #F3
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
|
||||
|
|
|
@ -230,13 +230,28 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_Submenu:
|
||||
case OME_Funcall:
|
||||
if (IS_PRINTVALUE(p)) {
|
||||
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, ">");
|
||||
|
||||
int colPos = RIGHT_MENU_COLUMN(pDisplay);
|
||||
|
||||
if ((p->type == OME_Submenu) && p->func && (p->flags & OPTSTRING)) {
|
||||
|
||||
// Special case of sub menu entry with optional value display.
|
||||
|
||||
char *str = ((CMSMenuOptFuncPtr)p->func)();
|
||||
cnt = displayWrite(pDisplay, colPos, row, str);
|
||||
colPos += strlen(str);
|
||||
}
|
||||
|
||||
cnt += displayWrite(pDisplay, colPos, row, ">");
|
||||
|
||||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_Bool:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
if (*((uint8_t *)(p->data))) {
|
||||
|
@ -247,7 +262,8 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
case OME_TAB: {
|
||||
|
||||
case OME_TAB:
|
||||
if (IS_PRINTVALUE(p)) {
|
||||
OSD_TAB_t *ptr = p->data;
|
||||
//cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay) - 5, row, (char *)ptr->names[*ptr->val]);
|
||||
|
@ -255,7 +271,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef OSD
|
||||
case OME_VISIBLE:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
|
@ -273,6 +289,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case OME_UINT8:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
OSD_UINT8_t *ptr = p->data;
|
||||
|
@ -282,6 +299,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_INT8:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
OSD_INT8_t *ptr = p->data;
|
||||
|
@ -291,6 +309,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_UINT16:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
OSD_UINT16_t *ptr = p->data;
|
||||
|
@ -300,6 +319,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_INT16:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
OSD_UINT16_t *ptr = p->data;
|
||||
|
@ -309,6 +329,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_FLOAT:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
OSD_FLOAT_t *ptr = p->data;
|
||||
|
@ -318,6 +339,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_Label:
|
||||
if (IS_PRINTVALUE(p) && p->data) {
|
||||
// A label with optional string, immediately following text
|
||||
|
@ -325,10 +347,12 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
|||
CLR_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_OSD_Exit:
|
||||
case OME_END:
|
||||
case OME_Back:
|
||||
break;
|
||||
|
||||
case OME_MENU:
|
||||
// Fall through
|
||||
default:
|
||||
|
@ -645,17 +669,34 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
|
||||
switch (p->type) {
|
||||
case OME_Submenu:
|
||||
case OME_Funcall:
|
||||
if (key == KEY_RIGHT) {
|
||||
cmsMenuChange(pDisplay, p->data);
|
||||
res = BUTTON_PAUSE;
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_Funcall:;
|
||||
long retval;
|
||||
if (p->func && key == KEY_RIGHT) {
|
||||
retval = p->func(pDisplay, p->data);
|
||||
if (retval == MENU_CHAIN_BACK)
|
||||
cmsMenuBack(pDisplay);
|
||||
res = BUTTON_PAUSE;
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_OSD_Exit:
|
||||
if (p->func && key == KEY_RIGHT) {
|
||||
p->func(pDisplay, p->data);
|
||||
res = BUTTON_PAUSE;
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_Back:
|
||||
cmsMenuBack(pDisplay);
|
||||
res = BUTTON_PAUSE;
|
||||
break;
|
||||
|
||||
case OME_Bool:
|
||||
if (p->data) {
|
||||
uint8_t *val = p->data;
|
||||
|
@ -666,6 +707,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
SET_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef OSD
|
||||
case OME_VISIBLE:
|
||||
if (p->data) {
|
||||
|
@ -682,6 +724,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case OME_UINT8:
|
||||
case OME_FLOAT:
|
||||
if (p->data) {
|
||||
|
@ -700,6 +743,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_TAB:
|
||||
if (p->type == OME_TAB) {
|
||||
OSD_TAB_t *ptr = p->data;
|
||||
|
@ -717,6 +761,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
SET_PRINTVALUE(p);
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_INT8:
|
||||
if (p->data) {
|
||||
OSD_INT8_t *ptr = p->data;
|
||||
|
@ -734,6 +779,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_UINT16:
|
||||
if (p->data) {
|
||||
OSD_UINT16_t *ptr = p->data;
|
||||
|
@ -751,6 +797,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_INT16:
|
||||
if (p->data) {
|
||||
OSD_INT16_t *ptr = p->data;
|
||||
|
@ -768,11 +815,14 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case OME_String:
|
||||
break;
|
||||
|
||||
case OME_Label:
|
||||
case OME_END:
|
||||
break;
|
||||
|
||||
case OME_MENU:
|
||||
// Shouldn't happen
|
||||
break;
|
||||
|
|
|
@ -45,6 +45,9 @@
|
|||
#include "cms/cms_menu_ledstrip.h"
|
||||
#include "cms/cms_menu_misc.h"
|
||||
|
||||
// User supplied menus
|
||||
|
||||
#include "io/vtx_smartaudio_cms.h"
|
||||
|
||||
// Info
|
||||
|
||||
|
@ -93,6 +96,9 @@ static OSD_Entry menuFeaturesEntries[] =
|
|||
#if defined(VTX) || defined(USE_RTC6705)
|
||||
{"VTX", OME_Submenu, cmsMenuChange, &cmsx_menuVtx, 0},
|
||||
#endif // VTX || USE_RTC6705
|
||||
#if defined(VTX_SMARTAUDIO)
|
||||
{"VTX", OME_Submenu, cmsMenuChange, &cmsx_menuVtxSmartAudio, 0},
|
||||
#endif
|
||||
#ifdef LED_STRIP
|
||||
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip, 0},
|
||||
#endif // LED_STRIP
|
||||
|
|
|
@ -362,14 +362,13 @@ static OSD_Entry cmsx_menuImuEntries[] =
|
|||
|
||||
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpProfileIndex, 1, MAX_PROFILE_COUNT, 1}, 0},
|
||||
{"PID", OME_Submenu, cmsMenuChange, &cmsx_menuPid, 0},
|
||||
{"OTHER PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther, 0},
|
||||
{"MISC PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther, 0},
|
||||
{"FILT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile, 0},
|
||||
|
||||
{"RATE PROF", OME_UINT8, cmsx_rateProfileIndexOnChange, &(OSD_UINT8_t){ &tmpRateProfileIndex, 1, MAX_RATEPROFILES, 1}, 0},
|
||||
{"RATE", OME_Submenu, cmsMenuChange, &cmsx_menuRateProfile, 0},
|
||||
|
||||
{"FLT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile, 0},
|
||||
|
||||
{"FLT GLB", OME_Submenu, cmsMenuChange, &cmsx_menuFilterGlobal, 0},
|
||||
{"FILT GLB", OME_Submenu, cmsMenuChange, &cmsx_menuFilterGlobal, 0},
|
||||
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
|
|
|
@ -66,6 +66,7 @@ typedef struct
|
|||
#define PRINT_VALUE 0x01 // Value has been changed, need to redraw
|
||||
#define PRINT_LABEL 0x02 // Text label should be printed
|
||||
#define DYNAMIC 0x04 // Value should be updated dynamically
|
||||
#define OPTSTRING 0x08 // (Temporary) Flag for OME_Submenu, indicating func should be called to get a string to display.
|
||||
|
||||
#define IS_PRINTVALUE(p) ((p)->flags & PRINT_VALUE)
|
||||
#define SET_PRINTVALUE(p) { (p)->flags |= PRINT_VALUE; }
|
||||
|
@ -77,9 +78,11 @@ typedef struct
|
|||
|
||||
#define IS_DYNAMIC(p) ((p)->flags & DYNAMIC)
|
||||
|
||||
|
||||
typedef long (*CMSMenuFuncPtr)(void);
|
||||
|
||||
// Special return value(s) for function chaining by CMSMenuFuncPtr
|
||||
#define MENU_CHAIN_BACK (-1) // Causes automatic cmsMenuBack
|
||||
|
||||
/*
|
||||
onExit function is called with self:
|
||||
(1) Pointer to an OSD_Entry when cmsMenuBack() was called.
|
||||
|
@ -153,3 +156,7 @@ typedef struct
|
|||
{
|
||||
char *val;
|
||||
} OSD_String_t;
|
||||
|
||||
// This is a function used in the func member if the type is OME_Submenu.
|
||||
|
||||
typedef char * (*CMSMenuOptFuncPtr)(void);
|
||||
|
|
|
@ -198,7 +198,7 @@ typedef struct master_s {
|
|||
uint8_t transponderData[6];
|
||||
#endif
|
||||
|
||||
#ifdef USE_RTC6705
|
||||
#if defined(USE_RTC6705)
|
||||
uint8_t vtx_channel;
|
||||
uint8_t vtx_power;
|
||||
#endif
|
||||
|
|
|
@ -37,9 +37,8 @@
|
|||
#include "max7456.h"
|
||||
#include "max7456_symbols.h"
|
||||
|
||||
|
||||
|
||||
//MAX7456 opcodes
|
||||
//XXX These are not opcodes but reg addrs. Substitute with MAX7456ADD_xxx.
|
||||
#define DMM_REG 0x04
|
||||
#define DMAH_REG 0x05
|
||||
#define DMAL_REG 0x06
|
||||
|
@ -52,15 +51,21 @@
|
|||
#define MAX7456_RESET 0x02
|
||||
#define VERTICAL_SYNC_NEXT_VSYNC 0x04
|
||||
#define OSD_ENABLE 0x08
|
||||
|
||||
#define SYNC_MODE_AUTO 0x00
|
||||
#define SYNC_MODE_INTERNAL 0x30
|
||||
#define SYNC_MODE_EXTERNAL 0x20
|
||||
|
||||
#define VIDEO_MODE_PAL 0x40
|
||||
#define VIDEO_MODE_NTSC 0x00
|
||||
#define VIDEO_MODE_MASK 0x40
|
||||
#define VIDEO_MODE_IS_PAL(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_PAL)
|
||||
#define VIDEO_MODE_IS_NTSC(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_NTSC)
|
||||
|
||||
#define VIDEO_SIGNAL_DEBOUNCE_MS 100 // Time to wait for input to stabilize
|
||||
|
||||
// video mode register 1 bits
|
||||
|
||||
|
||||
// duty cycle is on_off
|
||||
#define BLINK_DUTY_CYCLE_50_50 0x00
|
||||
#define BLINK_DUTY_CYCLE_33_66 0x01
|
||||
|
@ -85,9 +90,33 @@
|
|||
|
||||
#define BACKGROUND_MODE_GRAY 0x40
|
||||
|
||||
//MAX7456 commands
|
||||
// STAT register bits
|
||||
|
||||
#define STAT_PAL 0x01
|
||||
#define STAT_NTSC 0x02
|
||||
#define STAT_LOS 0x04
|
||||
#define STAT_NVR_BUSY 0x20
|
||||
|
||||
#define STAT_IS_PAL(val) ((val) & STAT_PAL)
|
||||
#define STAT_IS_NTSC(val) ((val) & STAT_NTSC)
|
||||
#define STAT_IS_LOS(val) ((val) & STAT_LOS)
|
||||
|
||||
#define VIN_IS_PAL(val) (!STAT_IS_LOS(val) && STAT_IS_PAL(val))
|
||||
#define VIN_IS_NTSC(val) (!STAT_IS_LOS(val) && STAT_IS_NTSC(val))
|
||||
|
||||
// Kluege warning!
|
||||
// There are occasions that NTSC is not detected even with !LOS (AB7456 specific?)
|
||||
// When this happens, lower 3 bits of STAT register is read as zero.
|
||||
// To cope with this case, this macro defines !LOS && !PAL as NTSC.
|
||||
// Should be compatible with MAX7456 and non-problematic case.
|
||||
|
||||
#define VIN_IS_NTSC_alt(val) (!STAT_IS_LOS(val) && !STAT_IS_PAL(val))
|
||||
|
||||
// DMM special bits
|
||||
#define CLEAR_DISPLAY 0x04
|
||||
#define CLEAR_DISPLAY_VERT 0x06
|
||||
|
||||
// Special address for terminating incremental write
|
||||
#define END_STRING 0xff
|
||||
|
||||
|
||||
|
@ -125,7 +154,6 @@
|
|||
|
||||
#define NVM_RAM_SIZE 54
|
||||
#define WRITE_NVR 0xA0
|
||||
#define STATUS_REG_NVR_BUSY 0x20
|
||||
|
||||
/** Line multiples, for convenience & one less op at runtime **/
|
||||
#define LINE 30
|
||||
|
@ -147,12 +175,6 @@
|
|||
#define LINE16 450
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//on shared SPI buss we want to change clock for OSD chip and restore for other devices
|
||||
#ifdef MAX7456_SPI_CLK
|
||||
#define ENABLE_MAX7456 {spiSetDivisor(MAX7456_SPI_INSTANCE, MAX7456_SPI_CLK);IOLo(max7456CsPin);}
|
||||
|
@ -315,8 +337,12 @@ uint8_t max7456GetRowsCount(void)
|
|||
return (videoSignalReg & VIDEO_MODE_PAL) ? VIDEO_LINES_PAL : VIDEO_LINES_NTSC;
|
||||
}
|
||||
|
||||
#if 0
|
||||
// XXX Remove this comment, too.
|
||||
//because MAX7456 need some time to detect video system etc. we need to wait for a while to initialize it at startup
|
||||
//and in case of restart we need to reinitialize chip
|
||||
#endif
|
||||
|
||||
void max7456ReInit(void)
|
||||
{
|
||||
uint8_t maxScreenRows;
|
||||
|
@ -324,9 +350,13 @@ void max7456ReInit(void)
|
|||
uint16_t x;
|
||||
static bool firstInit = true;
|
||||
|
||||
#if 0
|
||||
// XXX We don't have to wait for the cam any more.
|
||||
// XXX Remove this when everything is stable.
|
||||
//do not init MAX before camera power up correctly
|
||||
if (millis() < 1500)
|
||||
return;
|
||||
#endif
|
||||
|
||||
ENABLE_MAX7456;
|
||||
|
||||
|
@ -334,15 +364,22 @@ void max7456ReInit(void)
|
|||
case VIDEO_SYSTEM_PAL:
|
||||
videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE;
|
||||
break;
|
||||
|
||||
case VIDEO_SYSTEM_NTSC:
|
||||
videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE;
|
||||
break;
|
||||
|
||||
case VIDEO_SYSTEM_AUTO:
|
||||
srdata = max7456Send(MAX7456ADD_STAT, 0x00);
|
||||
if ((0x02 & srdata) == 0x02)
|
||||
|
||||
if (VIN_IS_NTSC(srdata)) {
|
||||
videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE;
|
||||
else
|
||||
} else if (VIN_IS_PAL(srdata)) {
|
||||
videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE;
|
||||
} else {
|
||||
// No valid input signal, fallback to default (XXX NTSC for now)
|
||||
videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -436,22 +473,60 @@ bool max7456DmaInProgres(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
void max7456DrawScreen(void)
|
||||
{
|
||||
uint8_t check;
|
||||
uint8_t stallCheck;
|
||||
uint8_t videoSense;
|
||||
static uint32_t videoDetectTimeMs = 0;
|
||||
static uint16_t pos = 0;
|
||||
int k = 0, buff_len=0;
|
||||
|
||||
if (!max7456Lock && !fontIsLoading) {
|
||||
//-----------------detect MAX7456 fail, or initialize it at startup when it is ready--------
|
||||
|
||||
// Detect MAX7456 fail, or initialize it at startup when it is ready
|
||||
|
||||
max7456Lock = true;
|
||||
ENABLE_MAX7456;
|
||||
check = max7456Send(VM0_REG | 0x80, 0x00);
|
||||
stallCheck = max7456Send(VM0_REG | 0x80, 0x00);
|
||||
DISABLE_MAX7456;
|
||||
|
||||
if ( check != videoSignalReg)
|
||||
if (stallCheck != videoSignalReg) {
|
||||
max7456ReInit();
|
||||
|
||||
} else if (videoSignalCfg == VIDEO_SYSTEM_AUTO) {
|
||||
|
||||
// Adjust output format based on the current input format.
|
||||
|
||||
ENABLE_MAX7456;
|
||||
videoSense = max7456Send(MAX7456ADD_STAT, 0x00);
|
||||
DISABLE_MAX7456;
|
||||
|
||||
debug[0] = videoSignalReg & VIDEO_MODE_MASK;
|
||||
debug[1] = videoSense & 0x7;
|
||||
debug[3] = max7456GetRowsCount();
|
||||
|
||||
if (videoSense & STAT_LOS) {
|
||||
videoDetectTimeMs = 0;
|
||||
} else {
|
||||
// There is a case that NTSC is not detected for some reason (AB7456 specific?)
|
||||
// Here we force NTSC detection if not LOS and not PAL.
|
||||
if ((VIN_IS_PAL(videoSense) && VIDEO_MODE_IS_NTSC(videoSignalReg))
|
||||
|| (VIN_IS_NTSC_alt(videoSense) && VIDEO_MODE_IS_PAL(videoSignalReg))) {
|
||||
if (videoDetectTimeMs) {
|
||||
if (millis() - videoDetectTimeMs > VIDEO_SIGNAL_DEBOUNCE_MS) {
|
||||
max7456ReInit();
|
||||
debug[2]++;
|
||||
}
|
||||
} else {
|
||||
// Wait for signal to stabilize
|
||||
videoDetectTimeMs = millis();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//------------ end of (re)init-------------------------------------
|
||||
|
||||
for (k=0; k< MAX_CHARS2UPDATE; k++) {
|
||||
|
@ -545,12 +620,11 @@ void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data)
|
|||
max7456Send(MAX7456ADD_CMM, WRITE_NVR);
|
||||
|
||||
// wait until bit 5 in the status register returns to 0 (12ms)
|
||||
while ((max7456Send(MAX7456ADD_STAT, 0x00) & STATUS_REG_NVR_BUSY) != 0x00);
|
||||
while ((max7456Send(MAX7456ADD_STAT, 0x00) & STAT_NVR_BUSY) != 0x00);
|
||||
|
||||
DISABLE_MAX7456;
|
||||
|
||||
max7456Lock = false;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
|
|
@ -31,7 +31,17 @@ typedef enum portOptions_t {
|
|||
SERIAL_PARITY_NO = 0 << 2,
|
||||
SERIAL_PARITY_EVEN = 1 << 2,
|
||||
SERIAL_UNIDIR = 0 << 3,
|
||||
SERIAL_BIDIR = 1 << 3
|
||||
SERIAL_BIDIR = 1 << 3,
|
||||
|
||||
/*
|
||||
* Note on SERIAL_BIDIR_PP
|
||||
* With SERIAL_BIDIR_PP, the very first start bit of back-to-back bytes
|
||||
* is lost and the first data byte will be lost by a framing error.
|
||||
* To ensure the first start bit to be sent, prepend a zero byte (0x00)
|
||||
* to actual data bytes.
|
||||
*/
|
||||
SERIAL_BIDIR_OD = 0 << 4,
|
||||
SERIAL_BIDIR_PP = 1 << 4
|
||||
} portOptions_t;
|
||||
|
||||
typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
|
||||
|
|
|
@ -123,7 +123,7 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
|
|||
// UART1_RX PA10
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1);
|
||||
|
@ -194,7 +194,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
|
|||
// UART2_RX PA3
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2);
|
||||
|
@ -256,7 +256,7 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
|
|||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, 3);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, 3);
|
||||
|
|
|
@ -117,8 +117,8 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui
|
|||
{
|
||||
if (options & SERIAL_BIDIR) {
|
||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
|
||||
(options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD,
|
||||
(options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_OType_PP : GPIO_OType_OD,
|
||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
||||
);
|
||||
|
||||
IOInit(tx, OWNER_SERIAL_TX, index);
|
||||
|
|
|
@ -340,7 +340,10 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
|||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
||||
if (options & SERIAL_BIDIR_PP)
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||
else
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
||||
}
|
||||
else {
|
||||
if (mode & MODE_TX) {
|
||||
|
|
|
@ -51,6 +51,7 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/serial_cli.h"
|
||||
#include "io/transponder_ir.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
|
@ -203,6 +204,19 @@ static void taskTelemetry(timeUs_t currentTimeUs)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef VTX_CONTROL
|
||||
// Everything that listens to VTX devices
|
||||
void taskVtxControl(uint32_t currentTime)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED))
|
||||
return;
|
||||
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
smartAudioProcess(currentTime);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
void fcTasksInit(void)
|
||||
{
|
||||
schedulerInit();
|
||||
|
@ -281,6 +295,11 @@ void fcTasksInit(void)
|
|||
#ifdef STACK_CHECK
|
||||
setTaskEnabled(TASK_STACK_CHECK, true);
|
||||
#endif
|
||||
#ifdef VTX_CONTROL
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
setTaskEnabled(TASK_VTXCTRL, true);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
cfTask_t cfTasks[TASK_COUNT] = {
|
||||
|
@ -467,4 +486,13 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef VTX_CONTROL
|
||||
[TASK_VTXCTRL] = {
|
||||
.taskName = "VTXCTRL",
|
||||
.taskFunc = taskVtxControl,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(5), // 5Hz @200msec
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -37,7 +37,8 @@ typedef enum {
|
|||
FUNCTION_BLACKBOX = (1 << 7), // 128
|
||||
|
||||
FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512
|
||||
FUNCTION_ESC_SENSOR = (1 << 10) // 1024
|
||||
FUNCTION_ESC_SENSOR = (1 << 10),// 1024
|
||||
FUNCTION_VTX_CONTROL = (1 << 11),// 2048
|
||||
} serialPortFunction_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -739,7 +739,7 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef LED_STRIP
|
||||
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &ledStripConfig()->ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
|
||||
#endif
|
||||
#ifdef USE_RTC6705
|
||||
#if defined(USE_RTC6705)
|
||||
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
|
||||
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
|
||||
#endif
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,35 @@
|
|||
|
||||
// For generic API use, but here for now
|
||||
|
||||
bool smartAudioInit();
|
||||
void smartAudioProcess(uint32_t);
|
||||
|
||||
#if 0
|
||||
#ifdef CMS
|
||||
|
||||
uint16_t smartAudioSmartbaud;
|
||||
|
||||
uint16_t saerr_badpre;
|
||||
uint16_t saerr_badlen;
|
||||
uint16_t saerr_crcerr;
|
||||
uint16_t saerr_oooresp;
|
||||
|
||||
uint8_t smartAudioOpModel;
|
||||
uint8_t smartAudioStatus;
|
||||
uint8_t smartAudioBand;
|
||||
uint8_t smartAudioChan;
|
||||
uint16_t smartAudioFreq;
|
||||
uint8_t smartAudioPower;
|
||||
uint8_t smartAudioTxMode;
|
||||
uint8_t smartAudioPitFMode;
|
||||
uint16_t smartAudioORFreq;
|
||||
|
||||
long smartAudioConfigureOpModelByGvar(displayPort_t *, const void *self);
|
||||
long smartAudioConfigurePitFModeByGvar(displayPort_t *, const void *self);
|
||||
long smartAudioConfigureBandByGvar(displayPort_t *, const void *self);
|
||||
long smartAudioConfigureChanByGvar(displayPort_t *, const void *self);
|
||||
long smartAudioConfigurePowerByGvar(displayPort_t *, const void *self);
|
||||
long smartAudioSetTxModeByGvar(displayPort_t *, const void *self);
|
||||
|
||||
#endif
|
||||
#endif
|
|
@ -0,0 +1 @@
|
|||
extern CMS_Menu cmsx_menuVtxSmartAudio;
|
|
@ -30,6 +30,7 @@
|
|||
#include "common/printf.h"
|
||||
|
||||
#include "cms/cms.h"
|
||||
#include "cms/cms_types.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
@ -90,6 +91,7 @@
|
|||
#include "io/osd.h"
|
||||
#include "io/displayport_msp.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
|
@ -517,6 +519,10 @@ void init(void)
|
|||
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
||||
#endif
|
||||
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
smartAudioInit();
|
||||
#endif
|
||||
|
||||
// start all timers
|
||||
// TODO - not implemented yet
|
||||
timerStart();
|
||||
|
|
|
@ -73,4 +73,4 @@
|
|||
|
||||
#include "target/common.h"
|
||||
#include "target.h"
|
||||
|
||||
#include "target/common_post.h"
|
||||
|
|
|
@ -100,6 +100,9 @@ typedef enum {
|
|||
#ifdef CMS
|
||||
TASK_CMS,
|
||||
#endif
|
||||
#ifdef VTX_CONTROL
|
||||
TASK_VTXCTRL,
|
||||
#endif
|
||||
|
||||
/* Count of real tasks */
|
||||
TASK_COUNT,
|
||||
|
|
|
@ -162,7 +162,7 @@
|
|||
#define BUTTON_A_PIN PB1
|
||||
#define BUTTON_B_PIN PB0
|
||||
|
||||
#define AVOID_UART3_FOR_PWM_PPM
|
||||
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
|
|
|
@ -8,4 +8,3 @@ TARGET_SRC = \
|
|||
drivers/barometer_spi_bmp280.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/max7456.c
|
||||
|
||||
|
|
|
@ -101,6 +101,8 @@
|
|||
#define TELEMETRY_MAVLINK
|
||||
#define USE_RX_MSP
|
||||
#define USE_SERIALRX_JETIEXBUS
|
||||
#define VTX_CONTROL
|
||||
#define VTX_SMARTAUDIO
|
||||
#else
|
||||
#define SKIP_CLI_COMMAND_HELP
|
||||
#endif
|
||||
|
|
|
@ -0,0 +1,26 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// Touch up configuration
|
||||
|
||||
#pragma once
|
||||
|
||||
// Targets with built-in vtx do not need external vtx
|
||||
#if defined(VTX) || defined(USE_RTC6705)
|
||||
# undef VTX_CONTROL
|
||||
# undef VTX_SMARTAUDIO
|
||||
#endif
|
Loading…
Reference in New Issue