mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Tramp prototype driver
This commit is contained in:
parent
033e41500c
commit
58ed2ed590
11 changed files with 306 additions and 5 deletions
4
Makefile
4
Makefile
|
@ -610,7 +610,9 @@ HIGHEND_SRC = \
|
|||
telemetry/mavlink.c \
|
||||
telemetry/ibus.c \
|
||||
sensors/esc_sensor.c \
|
||||
io/vtx_smartaudio.c
|
||||
drivers/vtx_var.c \
|
||||
io/vtx_smartaudio.c \
|
||||
io/vtx_tramp.c
|
||||
|
||||
SPEED_OPTIMISED_SRC := ""
|
||||
SIZE_OPTIMISED_SRC := ""
|
||||
|
|
|
@ -48,6 +48,7 @@
|
|||
// User supplied menus
|
||||
|
||||
#include "io/vtx_smartaudio_cms.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
|
||||
// Info
|
||||
|
||||
|
@ -97,7 +98,10 @@ static OSD_Entry menuFeaturesEntries[] =
|
|||
{"VTX", OME_Submenu, cmsMenuChange, &cmsx_menuVtx, 0},
|
||||
#endif // VTX || USE_RTC6705
|
||||
#if defined(VTX_SMARTAUDIO)
|
||||
{"VTX", OME_Submenu, cmsMenuChange, &cmsx_menuVtxSmartAudio, 0},
|
||||
{"VTX SA", OME_Submenu, cmsMenuChange, &cmsx_menuVtxSmartAudio, 0},
|
||||
#endif
|
||||
#if defined(VTX_TRAMP)
|
||||
{"VTX TR", OME_Submenu, cmsMenuChange, &cmsx_menuVtxTramp, 0},
|
||||
#endif
|
||||
#ifdef LED_STRIP
|
||||
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip, 0},
|
||||
|
|
24
src/main/drivers/vtx_var.c
Normal file
24
src/main/drivers/vtx_var.c
Normal file
|
@ -0,0 +1,24 @@
|
|||
#include <stdint.h>
|
||||
#include "vtx_var.h"
|
||||
|
||||
const uint16_t vtx58FreqTable[5][8] =
|
||||
{
|
||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boacam A
|
||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||
{ 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // RaceBand
|
||||
};
|
||||
|
||||
const char * const vtx58BandNames[] = {
|
||||
"--------",
|
||||
"BOSCAM A",
|
||||
"BOSCAM B",
|
||||
"BOSCAM E",
|
||||
"FATSHARK",
|
||||
"RACEBAND",
|
||||
};
|
||||
|
||||
const char * const vtx58ChanNames[] = {
|
||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
||||
};
|
5
src/main/drivers/vtx_var.h
Normal file
5
src/main/drivers/vtx_var.h
Normal file
|
@ -0,0 +1,5 @@
|
|||
#include <stdint.h>
|
||||
|
||||
extern const uint16_t vtx58FreqTable[5][8];
|
||||
extern const char * const vtx58BandNames[];
|
||||
extern const char * const vtx58ChanNames[];
|
21
src/main/drivers/vtxtab.c
Normal file
21
src/main/drivers/vtxtab.c
Normal file
|
@ -0,0 +1,21 @@
|
|||
static const uint16_t vtx58FreqTable[5][8] =
|
||||
{
|
||||
{ 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // Boacam A
|
||||
{ 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // Boscam B
|
||||
{ 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 }, // Boscam E
|
||||
{ 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 }, // FatShark
|
||||
{ 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // RaceBand
|
||||
};
|
||||
|
||||
static const char * const vtx58BandNames[] = {
|
||||
"--------",
|
||||
"BOSCAM A",
|
||||
"BOSCAM B",
|
||||
"BOSCAM E",
|
||||
"FATSHARK",
|
||||
"RACEBAND",
|
||||
};
|
||||
|
||||
static const char * const vtx58ChanNames[] = {
|
||||
"-", "1", "2", "3", "4", "5", "6", "7", "8",
|
||||
};
|
|
@ -92,6 +92,7 @@
|
|||
#include "io/displayport_msp.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
|
@ -527,6 +528,10 @@ void init(void)
|
|||
smartAudioInit();
|
||||
#endif
|
||||
|
||||
#ifdef VTX_TRAMP
|
||||
trampInit();
|
||||
#endif
|
||||
|
||||
// start all timers
|
||||
// TODO - not implemented yet
|
||||
timerStart();
|
||||
|
|
|
@ -38,7 +38,7 @@ typedef enum {
|
|||
FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512
|
||||
FUNCTION_ESC_SENSOR = (1 << 10), // 1024
|
||||
FUNCTION_VTX_CONTROL = (1 << 11), // 2048
|
||||
FUNCTION_TELEMETRY_IBUS = (1 << 12) // 4096
|
||||
FUNCTION_TELEMETRY_IBUS = (1 << 12), // 4096
|
||||
} serialPortFunction_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
35
src/main/io/vtx_common.h
Normal file
35
src/main/io/vtx_common.h
Normal file
|
@ -0,0 +1,35 @@
|
|||
|
||||
struct vtxVTable_s;
|
||||
typedef struct vtxDevice_s {
|
||||
const struct vtxVTable_s *vTable;
|
||||
uint8_t numBand;
|
||||
uint8_t numChan;
|
||||
uint8_t numPower;
|
||||
|
||||
uint16_t *freqTable;
|
||||
|
||||
// Config variable?
|
||||
uint8_t opModel; // Power up in: 0 = transmitting, 1 = pit mode
|
||||
|
||||
// CMS only?
|
||||
uint8_t curBand;
|
||||
uint8_t curChan;
|
||||
uint8_t curPower;
|
||||
uint8_t curPitState; // 0 = PIT, 1 = non-PIT
|
||||
|
||||
// CMS only?
|
||||
char *bandNames;
|
||||
char *chanNames;
|
||||
char *powerNames;
|
||||
} vtxDevice_t;
|
||||
|
||||
typedef struct vtxVTable_s {
|
||||
void (*setBandChan)(uint8_t band, uint8_t chan);
|
||||
void (*setFreq)(uint16_t freq);
|
||||
void (*setRFPower)(uint8_t level); // 0 = OFF, 1~ = device dep.
|
||||
void (*setPitmode)(uint8_t onoff);
|
||||
} vtxVTable_t;
|
||||
|
||||
// PIT mode is defined as LOWEST POSSIBLE RF POWER.
|
||||
// - It can be a dedicated mode, or lowest RF power possible.
|
||||
// - It is *NOT* RF on/off control.
|
195
src/main/io/vtx_tramp.c
Normal file
195
src/main/io/vtx_tramp.c
Normal file
|
@ -0,0 +1,195 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
/* Created by jflyper */
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef VTX_TRAMP
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/vtx_var.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
|
||||
static serialPort_t *trampSerialPort = NULL;
|
||||
|
||||
static uint8_t trampCmdBuffer[16];
|
||||
|
||||
void trampClearBuffer(uint8_t *buf)
|
||||
{
|
||||
for (int i = 0 ; i < 16 ; i++) {
|
||||
buf[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void trampPrepareBuffer(uint8_t *buf, uint8_t cmd)
|
||||
{
|
||||
trampClearBuffer(buf);
|
||||
|
||||
trampCmdBuffer[0] = 15;
|
||||
trampCmdBuffer[1] = cmd;
|
||||
}
|
||||
|
||||
void trampWriteBuf(uint8_t *buf)
|
||||
{
|
||||
serialWriteBuf(trampSerialPort, buf, 16);
|
||||
}
|
||||
|
||||
void trampChecksum(uint8_t *buf)
|
||||
{
|
||||
uint8_t cksum = 0;
|
||||
|
||||
for (int i = 0 ; i < 14 ; i++)
|
||||
cksum += buf[i];
|
||||
|
||||
buf[14] = cksum;
|
||||
}
|
||||
|
||||
void trampSetFreq(uint16_t freq)
|
||||
{
|
||||
if (!trampSerialPort)
|
||||
return;
|
||||
|
||||
trampPrepareBuffer(trampCmdBuffer, 'F');
|
||||
trampCmdBuffer[2] = freq & 0xff;
|
||||
trampCmdBuffer[3] = (freq >> 8) & 0xff;
|
||||
trampChecksum(trampCmdBuffer);
|
||||
trampWriteBuf(trampCmdBuffer);
|
||||
}
|
||||
|
||||
void trampSetBandChan(uint8_t band, uint8_t chan)
|
||||
{
|
||||
if (!trampSerialPort)
|
||||
return;
|
||||
|
||||
debug[0] = band;
|
||||
debug[1] = chan;
|
||||
debug[2] = vtx58FreqTable[band - 1][chan - 1];
|
||||
|
||||
trampSetFreq(vtx58FreqTable[band - 1][chan - 1]);
|
||||
}
|
||||
|
||||
void trampSetRFPower(uint8_t level)
|
||||
{
|
||||
if (!trampSerialPort)
|
||||
return;
|
||||
|
||||
trampPrepareBuffer(trampCmdBuffer, 'F');
|
||||
trampCmdBuffer[2] = level;
|
||||
trampChecksum(trampCmdBuffer);
|
||||
trampWriteBuf(trampCmdBuffer);
|
||||
}
|
||||
|
||||
void trampSetPitmode(uint8_t onoff)
|
||||
{
|
||||
if (!trampSerialPort)
|
||||
return;
|
||||
|
||||
trampPrepareBuffer(trampCmdBuffer, 'I');
|
||||
trampCmdBuffer[2] = onoff;
|
||||
trampChecksum(trampCmdBuffer);
|
||||
trampWriteBuf(trampCmdBuffer);
|
||||
}
|
||||
|
||||
bool trampInit()
|
||||
{
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_CONTROL);
|
||||
|
||||
if (portConfig) {
|
||||
trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_CONTROL, NULL, 9600, MODE_RXTX, 0); // MODE_TX possible?
|
||||
}
|
||||
|
||||
if (!trampSerialPort) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#ifdef CMS
|
||||
#include "cms/cms.h"
|
||||
#include "cms/cms_types.h"
|
||||
|
||||
uint8_t trampCmsBand = 1;
|
||||
uint8_t trampCmsChan = 1;
|
||||
|
||||
static OSD_TAB_t trampCmsEntBand = { &trampCmsBand, 5, vtx58BandNames, NULL };
|
||||
|
||||
static OSD_TAB_t trampCmsEntChan = { &trampCmsChan, 8, vtx58ChanNames, NULL };
|
||||
|
||||
static long trampCmsCommence(displayPort_t *pDisp, const void *self)
|
||||
{
|
||||
UNUSED(pDisp);
|
||||
UNUSED(self);
|
||||
|
||||
trampSetBandChan(trampCmsBand, trampCmsChan);
|
||||
|
||||
return MENU_CHAIN_BACK;
|
||||
}
|
||||
|
||||
static OSD_Entry trampCmsMenuCommenceEntries[] = {
|
||||
{ "CONFIRM", OME_Label, NULL, NULL, 0 },
|
||||
{ "YES", OME_Funcall, trampCmsCommence, NULL, 0 },
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
};
|
||||
|
||||
static CMS_Menu trampCmsMenuCommence = {
|
||||
.GUARD_text = "XVTXTRC",
|
||||
.GUARD_type = OME_MENU,
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = trampCmsMenuCommenceEntries,
|
||||
};
|
||||
|
||||
static OSD_Entry trampMenuEntries[] =
|
||||
{
|
||||
{ "- TRAMP -", OME_Label, NULL, NULL, 0 },
|
||||
|
||||
//{ "", OME_Label, NULL, saCmsStatusString, DYNAMIC },
|
||||
{ "BAND", OME_TAB, NULL, &trampCmsEntBand, 0 },
|
||||
{ "CHAN", OME_TAB, NULL, &trampCmsEntChan, 0 },
|
||||
//{ "(FREQ)", OME_UINT16, NULL, &trampCmsEntFreqRef, DYNAMIC },
|
||||
//{ "POWER", OME_TAB, saCmsConfigPowerByGvar, &saCmsEntPower, 0 },
|
||||
{ "SET", OME_Submenu, cmsMenuChange, &trampCmsMenuCommence, 0 },
|
||||
//{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
};
|
||||
|
||||
CMS_Menu cmsx_menuVtxTramp = {
|
||||
.GUARD_text = "XVTXTR",
|
||||
.GUARD_type = OME_MENU,
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = trampMenuEntries,
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif // VTX_TRAMP
|
9
src/main/io/vtx_tramp.h
Normal file
9
src/main/io/vtx_tramp.h
Normal file
|
@ -0,0 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
bool trampInit();
|
||||
|
||||
#ifdef CMS
|
||||
#include "cms/cms.h"
|
||||
#include "cms/cms_types.h"
|
||||
extern CMS_Menu cmsx_menuVtxTramp;
|
||||
#endif
|
|
@ -103,8 +103,9 @@
|
|||
#define TELEMETRY_IBUS
|
||||
#define USE_RX_MSP
|
||||
#define USE_SERIALRX_JETIEXBUS
|
||||
#define VTX_CONTROL
|
||||
#define VTX_SMARTAUDIO
|
||||
//#define VTX_CONTROL
|
||||
//#define VTX_SMARTAUDIO
|
||||
#define VTX_TRAMP
|
||||
#define USE_SENSOR_NAMES
|
||||
#else
|
||||
#define SKIP_CLI_COMMAND_HELP
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue