mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Pit mode first implementation
This commit is contained in:
parent
7cc1010cb5
commit
de74dbd776
6 changed files with 137 additions and 31 deletions
|
@ -602,6 +602,10 @@ void createDefaultConfig(master_t *config)
|
|||
config->vtx_mhz = 5740; //F0
|
||||
#endif
|
||||
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
config->vtx_smartaudio_opmodel = 1; // PIT
|
||||
#endif
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware
|
||||
|
||||
|
|
|
@ -194,6 +194,10 @@ typedef struct master_s {
|
|||
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
|
||||
#endif
|
||||
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
uint8_t vtx_smartaudio_opmodel; // 0=FREE, 1=PIT
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
uint8_t blackbox_rate_num;
|
||||
uint8_t blackbox_rate_denom;
|
||||
|
|
|
@ -405,26 +405,58 @@ static const char * const smartAudioPowerNames[] = {
|
|||
|
||||
OSD_TAB_t entrySmartAudioPower = { &smartAudioPower, 4, &smartAudioPowerNames[0]};
|
||||
|
||||
static const char * const smartAudioModeNames[] = {
|
||||
// Sync with SA_RFMODE_*
|
||||
static const char * const smartAudioTxModeNames[] = {
|
||||
"------",
|
||||
"ACTIVE",
|
||||
"PIT-OR",
|
||||
"PIT-IR",
|
||||
"ACTIVE",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioMode = { &smartAudioMode, 3, &smartAudioModeNames[0]};
|
||||
OSD_TAB_t entrySmartAudioTxMode = { &smartAudioTxMode, 3, &smartAudioTxModeNames[0]};
|
||||
|
||||
OSD_UINT16_t entrySmartAudioFreq = { &smartAudioFreq, 5600, 5900, 0 };
|
||||
|
||||
static const char * const smartAudioOpModelNames[] = {
|
||||
"FREE",
|
||||
"PIT",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioOpModel = { &smartAudioOpModel, 1, &smartAudioOpModelNames[0] };
|
||||
|
||||
static const char * const smartAudioPitFModeNames[] = {
|
||||
"IN-RANGE",
|
||||
"OUT-RANGE",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioPitFMode = { &smartAudioPitFMode, 1, &smartAudioPitFModeNames[0] };
|
||||
|
||||
OSD_UINT16_t entrySmartAudioORFreq = { &smartAudioORFreq, 5600, 5900, 1 };
|
||||
|
||||
OSD_Entry menu_smartAudioConfig[] = {
|
||||
{ "--- SMARTAUDIO CONFIG ---", OME_Label, NULL, NULL },
|
||||
{ "OP MODEL", OME_TAB, smartAudioConfigureOpModelByGvar, &entrySmartAudioOpModel },
|
||||
{ "PIT FREQ", OME_TAB, smartAudioConfigurePitFModeByGvar, &entrySmartAudioPitFMode },
|
||||
{ "OR FREQ", OME_UINT16, NULL, &entrySmartAudioORFreq }, // OME_Poll_UINT16
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
||||
static const char * const smartAudioStatusNames[] = {
|
||||
"OFFLINE",
|
||||
"ONLINE V1",
|
||||
"ONLINE V2",
|
||||
};
|
||||
|
||||
OSD_TAB_t entrySmartAudioOnline = { &smartAudioStatus, 2, &smartAudioStatusNames[0] };
|
||||
OSD_UINT16_t entrySmartAudioBaudrate = { &smartAudioSmartbaud, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatBadpre = { &saerr_badpre, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatBadlen = { &saerr_badlen, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatCrcerr = { &saerr_crcerr, 0, 0, 0 };
|
||||
OSD_UINT16_t entrySmartAudioStatOooerr = { &saerr_oooresp, 0, 0, 0 };
|
||||
|
||||
OSD_Entry menu_vtxstat[] = {
|
||||
{ "--- VTX STATS ---", OME_Label, NULL, NULL },
|
||||
OSD_Entry menu_smartAudioStats[] = {
|
||||
{ "--- SMARTAUDIO STATS ---", OME_Label, NULL, NULL },
|
||||
{ "STATUS", OME_TAB, NULL, &entrySmartAudioOnline },
|
||||
{ "BAUDRATE", OME_UINT16, NULL, &entrySmartAudioBaudrate },
|
||||
{ "BADPRE", OME_UINT16, NULL, &entrySmartAudioStatBadpre },
|
||||
{ "BADLEN", OME_UINT16, NULL, &entrySmartAudioStatBadlen },
|
||||
|
@ -438,12 +470,13 @@ OSD_Entry menu_vtx[] =
|
|||
{
|
||||
{ "-- VTX SMARTAUDIO --", OME_Label, NULL, NULL },
|
||||
{ smartAudioStatusString, OME_Label, NULL, NULL },
|
||||
{ "RFMODE", OME_TAB, smartAudioSetModeByGvar, &entrySmartAudioMode },
|
||||
{ "TXMODE", OME_TAB, smartAudioSetTxModeByGvar, &entrySmartAudioTxMode },
|
||||
{ "BAND", OME_TAB, smartAudioConfigureBandByGvar, &entrySmartAudioBand },
|
||||
{ "CHAN", OME_TAB, smartAudioConfigureChanByGvar, &entrySmartAudioChan },
|
||||
{ "FREQ", OME_UINT16, NULL, &entrySmartAudioFreq },
|
||||
{ "POWER", OME_TAB, smartAudioConfigurePowerByGvar, &entrySmartAudioPower },
|
||||
{ "STAT", OME_Submenu, osdChangeScreen, &menu_vtxstat[0]},
|
||||
{ "CONFIG", OME_Submenu, osdChangeScreen, &menu_smartAudioConfig[0] },
|
||||
{ "STAT", OME_Submenu, osdChangeScreen, &menu_smartAudioStats[0] },
|
||||
{ "BACK", OME_Back, NULL, NULL },
|
||||
{ NULL, OME_END, NULL, NULL }
|
||||
};
|
||||
|
|
|
@ -925,6 +925,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
|
||||
#endif
|
||||
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
{ "vtx_smartaudio_opmodel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_smartaudio_opmodel, .config.minmax = { 0, 1 } },
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
|
||||
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
|
||||
|
|
|
@ -12,6 +12,15 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#define SMARTAUDIO_EXTENDED_API
|
||||
|
@ -127,11 +136,14 @@ static saPowerTable_t saPowerTable[] = {
|
|||
};
|
||||
|
||||
// Driver defined modes
|
||||
#define SA_RFMODE_NODEF 0
|
||||
#define SA_RFMODE_ACTIVE 1
|
||||
#define SA_RFMODE_PIT_INRANGE 2
|
||||
#define SA_RFMODE_PIT_OUTRANGE 3
|
||||
#define SA_RFMODE_OFF 4 // Should not be used with osd
|
||||
|
||||
#define SA_OPMODEL_FREE 0 // Power up transmitting
|
||||
#define SA_OPMODEL_PIT 1 // Power up in pit mode
|
||||
|
||||
#define SA_TXMODE_NODEF 0
|
||||
#define SA_TXMODE_PIT_OUTRANGE 1
|
||||
#define SA_TXMODE_PIT_INRANGE 2
|
||||
#define SA_TXMODE_ACTIVE 3
|
||||
|
||||
// Last received device ('hard') states
|
||||
|
||||
|
@ -280,6 +292,15 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
smartAudioBand = (sa_chan / 8) + 1;
|
||||
smartAudioChan = (sa_chan % 8) + 1;
|
||||
smartAudioFreq = saFreqTable[sa_chan / 8][sa_chan % 8];
|
||||
|
||||
if ((sa_opmode & SA_MODE_GET_PITMODE) == 0) {
|
||||
smartAudioTxMode = SA_TXMODE_ACTIVE;
|
||||
} else if (sa_opmode & SA_MODE_GET_IN_RANGE_PITMODE) {
|
||||
smartAudioTxMode = SA_TXMODE_PIT_INRANGE;
|
||||
} else {
|
||||
smartAudioTxMode = SA_TXMODE_PIT_OUTRANGE;
|
||||
}
|
||||
|
||||
smartAudioUpdateStatusString();
|
||||
|
||||
if (sa_vers == 2) {
|
||||
|
@ -608,11 +629,41 @@ bool smartAudioInit()
|
|||
return false;
|
||||
}
|
||||
|
||||
smartAudioOpModel = masterConfig.vtx_smartaudio_opmodel;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#ifdef SMARTAUDIO_PITMODE_DEBUG
|
||||
void smartAudioPitMode(void)
|
||||
void smartAudioConfigurePitFModeByGvar(void *opaque)
|
||||
{
|
||||
UNUSED(opaque);
|
||||
|
||||
if (smartAudioPitFMode == 0) {
|
||||
saSetMode(SA_MODE_SET_IN_RANGE_PITMODE);
|
||||
} else {
|
||||
saSetMode(SA_MODE_SET_OUT_RANGE_PITMODE);
|
||||
}
|
||||
}
|
||||
|
||||
void smartAudioConfigureOpModelByGvar(void *opaque)
|
||||
{
|
||||
UNUSED(opaque);
|
||||
|
||||
masterConfig.vtx_smartaudio_opmodel = smartAudioOpModel;
|
||||
|
||||
if (smartAudioOpModel == SA_OPMODEL_FREE) {
|
||||
// VTX should power up transmitting.
|
||||
// Turn off In-Range and Out-Range bits
|
||||
saSetMode(0);
|
||||
} else {
|
||||
// VTX should power up in pit mode.
|
||||
// Setup In-Range or Out-Range bits
|
||||
smartAudioConfigurePitFModeByGvar(opaque);
|
||||
}
|
||||
}
|
||||
|
||||
#if 0
|
||||
void
|
||||
{
|
||||
static int turn = 0;
|
||||
|
||||
|
@ -755,32 +806,36 @@ void smartAudioConfigurePowerByGvar(void *opaque)
|
|||
smartAudioSetPowerByIndex(smartAudioPower - 1);
|
||||
}
|
||||
|
||||
void smartAudioSetModeByGvar(void *opaque)
|
||||
void smartAudioSetTxModeByGvar(void *opaque)
|
||||
{
|
||||
UNUSED(opaque);
|
||||
|
||||
if (sa_vers != 2) {
|
||||
// Bounce back; not online yet or can't handle mode (V1)
|
||||
smartAudioMode = SA_RFMODE_NODEF;
|
||||
smartAudioTxMode = SA_TXMODE_NODEF;
|
||||
return;
|
||||
}
|
||||
|
||||
if (smartAudioMode == 0) {
|
||||
if (smartAudioTxMode == 0) {
|
||||
// Bouce back; no going back to undef state
|
||||
++smartAudioMode;
|
||||
++smartAudioTxMode;
|
||||
return;
|
||||
}
|
||||
|
||||
switch (smartAudioMode) {
|
||||
case SA_RFMODE_ACTIVE:
|
||||
saSetMode(SA_MODE_CLR_PITMODE);
|
||||
break;
|
||||
|
||||
case SA_RFMODE_PIT_OUTRANGE:
|
||||
break;
|
||||
|
||||
case SA_RFMODE_PIT_INRANGE:
|
||||
break;
|
||||
if (smartAudioTxMode == SA_TXMODE_ACTIVE) {
|
||||
if (smartAudioOpModel == SA_OPMODEL_FREE) {
|
||||
saSetMode(SA_MODE_CLR_PITMODE);
|
||||
} else {
|
||||
if (smartAudioPitFMode == 0)
|
||||
saSetMode(SA_MODE_CLR_PITMODE|SA_MODE_SET_IN_RANGE_PITMODE);
|
||||
else
|
||||
saSetMode(SA_MODE_CLR_PITMODE|SA_MODE_SET_OUT_RANGE_PITMODE);
|
||||
}
|
||||
} else {
|
||||
if ((sa_opmode & SA_MODE_GET_PITMODE) == 0) {
|
||||
// Can't go back to pit mode
|
||||
smartAudioTxMode = SA_TXMODE_ACTIVE;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // OSD
|
||||
|
|
|
@ -17,14 +17,20 @@ uint16_t saerr_oooresp;
|
|||
|
||||
char smartAudioStatusString[31];
|
||||
|
||||
uint8_t smartAudioOpModel;
|
||||
uint8_t smartAudioStatus;
|
||||
uint8_t smartAudioBand;
|
||||
uint8_t smartAudioChan;
|
||||
uint16_t smartAudioFreq;
|
||||
uint8_t smartAudioPower;
|
||||
uint8_t smartAudioMode;
|
||||
uint8_t smartAudioTxMode;
|
||||
uint8_t smartAudioPitFMode;
|
||||
uint16_t smartAudioORFreq;
|
||||
|
||||
void smartAudioConfigureOpModelByGvar(void *);
|
||||
void smartAudioConfigurePitFModeByGvar(void *);
|
||||
void smartAudioConfigureBandByGvar(void *);
|
||||
void smartAudioConfigureChanByGvar(void *);
|
||||
void smartAudioConfigurePowerByGvar(void *);
|
||||
void smartAudioSetModeByGvar(void *);
|
||||
void smartAudioSetTxModeByGvar(void *);
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue