mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Merge pull request #2114 from jflyper/bfdev-vtx-abstraction-1
VTX abstraction (testing)
This commit is contained in:
commit
bbfb8775c8
15 changed files with 2473 additions and 19 deletions
4
Makefile
4
Makefile
|
@ -591,6 +591,7 @@ HIGHEND_SRC = \
|
|||
drivers/serial_escserial.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/vtx_common.c \
|
||||
flight/navigation.c \
|
||||
flight/gps_conversion.c \
|
||||
io/dashboard.c \
|
||||
|
@ -612,7 +613,7 @@ HIGHEND_SRC = \
|
|||
telemetry/mavlink.c \
|
||||
telemetry/ibus.c \
|
||||
sensors/esc_sensor.c \
|
||||
io/vtx_common.c \
|
||||
io/vtx_string.c \
|
||||
io/vtx_smartaudio.c \
|
||||
io/vtx_tramp.c
|
||||
|
||||
|
@ -706,6 +707,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
|||
|
||||
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
||||
drivers/serial_escserial.c \
|
||||
drivers/vtx_common.c \
|
||||
io/cli.c \
|
||||
io/serial_4way.c \
|
||||
io/serial_4way_avrootloader.c \
|
||||
|
|
124
src/main/drivers/vtx_common.c
Normal file
124
src/main/drivers/vtx_common.c
Normal file
|
@ -0,0 +1,124 @@
|
|||
/*
|
||||
* 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 <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#if defined(VTX_COMMON)
|
||||
|
||||
#include "vtx_common.h"
|
||||
|
||||
vtxDevice_t *vtxDevice = NULL;
|
||||
|
||||
void vtxCommonInit(void)
|
||||
{
|
||||
}
|
||||
|
||||
// Whatever registered last will win
|
||||
|
||||
void vtxCommonRegisterDevice(vtxDevice_t *pDevice)
|
||||
{
|
||||
vtxDevice = pDevice;
|
||||
}
|
||||
|
||||
void vtxCommonProcess(uint32_t currentTimeUs)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return;
|
||||
|
||||
if (vtxDevice->vTable->process)
|
||||
vtxDevice->vTable->process(currentTimeUs);
|
||||
}
|
||||
|
||||
vtxDevType_e vtxCommonGetDeviceType(void)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return VTXDEV_UNKNOWN;
|
||||
|
||||
return vtxDevice->devtype;
|
||||
}
|
||||
|
||||
// band and chan are 1 origin
|
||||
void vtxCommonSetBandChan(uint8_t band, uint8_t chan)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return;
|
||||
|
||||
if (vtxDevice->vTable->setBandChan)
|
||||
vtxDevice->vTable->setBandChan(band, chan);
|
||||
}
|
||||
|
||||
// index is zero origin, zero = power off completely
|
||||
void vtxCommonSetPowerByIndex(uint8_t index)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return;
|
||||
|
||||
if (vtxDevice->vTable->setPowerByIndex)
|
||||
vtxDevice->vTable->setPowerByIndex(index);
|
||||
}
|
||||
|
||||
// on = 1, off = 0
|
||||
void vtxCommonSetPitmode(uint8_t onoff)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return;
|
||||
|
||||
if (vtxDevice->vTable->setPitmode)
|
||||
vtxDevice->vTable->setPitmode(onoff);
|
||||
}
|
||||
|
||||
bool vtxCommonGetBandChan(uint8_t *pBand, uint8_t *pChan)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return false;
|
||||
|
||||
if (vtxDevice->vTable->getBandChan)
|
||||
return vtxDevice->vTable->getBandChan(pBand, pChan);
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
bool vtxCommonGetPowerIndex(uint8_t *pIndex)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return false;
|
||||
|
||||
if (vtxDevice->vTable->getPowerIndex)
|
||||
return vtxDevice->vTable->getPowerIndex(pIndex);
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
bool vtxCommonGetPitmode(uint8_t *pOnoff)
|
||||
{
|
||||
if (!vtxDevice)
|
||||
return false;
|
||||
|
||||
if (vtxDevice->vTable->getPitmode)
|
||||
return vtxDevice->vTable->getPitmode(pOnoff);
|
||||
else
|
||||
return false;
|
||||
}
|
||||
#endif
|
83
src/main/drivers/vtx_common.h
Normal file
83
src/main/drivers/vtx_common.h
Normal file
|
@ -0,0 +1,83 @@
|
|||
/*
|
||||
* 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 */
|
||||
|
||||
typedef enum {
|
||||
VTXDEV_UNKNOWN = 0,
|
||||
VTXDEV_SMARTAUDIO = 3,
|
||||
VTXDEV_TRAMP = 4,
|
||||
} vtxDevType_e;
|
||||
|
||||
struct vtxVTable_s;
|
||||
|
||||
typedef struct vtxDevice_s {
|
||||
const struct vtxVTable_s *vTable;
|
||||
|
||||
vtxDevType_e devtype; // 3.1 only; eventually goes away
|
||||
|
||||
uint8_t numBand;
|
||||
uint8_t numChan;
|
||||
uint8_t numPower;
|
||||
|
||||
uint16_t *freqTable; // Array of [numBand][numChan]
|
||||
char **bandNames; // char *bandNames[numBand]
|
||||
char **chanNames; // char *chanNames[numChan]
|
||||
char **powerNames; // char *powerNames[numPower]
|
||||
|
||||
uint8_t curBand;
|
||||
uint8_t curChan;
|
||||
uint8_t curPowerIndex;
|
||||
uint8_t curPitState; // 0 = non-PIT, 1 = PIT
|
||||
|
||||
} vtxDevice_t;
|
||||
|
||||
// {set,get}BandChan: band and chan are 1 origin
|
||||
// {set,get}PowerByIndex: 0 = Power OFF, 1 = device dependent
|
||||
// {set,get}Pitmode: 0 = OFF, 1 = ON
|
||||
|
||||
typedef struct vtxVTable_s {
|
||||
void (*process)(uint32_t currentTimeUs);
|
||||
vtxDevType_e (*getDeviceType)(void);
|
||||
bool (*isReady)(void);
|
||||
|
||||
void (*setBandChan)(uint8_t band, uint8_t chan);
|
||||
void (*setPowerByIndex)(uint8_t level);
|
||||
void (*setPitmode)(uint8_t onoff);
|
||||
|
||||
bool (*getBandChan)(uint8_t *pBand, uint8_t *pChan);
|
||||
bool (*getPowerIndex)(uint8_t *pIndex);
|
||||
bool (*getPitmode)(uint8_t *pOnoff);
|
||||
} vtxVTable_t;
|
||||
|
||||
// 3.1.0
|
||||
// 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 ?
|
||||
|
||||
void vtxCommonInit(void);
|
||||
void vtxCommonRegisterDevice(vtxDevice_t *pDevice);
|
||||
|
||||
// VTable functions
|
||||
void vtxCommonProcess(uint32_t currentTimeUs);
|
||||
uint8_t vtxCommonGetDeviceType(void);
|
||||
void vtxCommonSetBandChan(uint8_t band, uint8_t chan);
|
||||
void vtxCommonSetPowerByIndex(uint8_t level);
|
||||
void vtxCommonSetPitmode(uint8_t onoff);
|
||||
bool vtxCommonGetBandChan(uint8_t *pBand, uint8_t *pChan);
|
||||
bool vtxCommonGetPowerIndex(uint8_t *pIndex);
|
||||
bool vtxCommonGetPitmode(uint8_t *pOnoff);
|
|
@ -87,7 +87,9 @@
|
|||
#define DISABLE_RTC6705 GPIO_SetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
|
||||
#define ENABLE_RTC6705 GPIO_ResetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
|
||||
|
||||
#if defined(SPRACINGF3NEO)
|
||||
static IO_t vtxPowerPin = IO_NONE;
|
||||
#endif
|
||||
|
||||
#define ENABLE_VTX_POWER IOLo(vtxPowerPin)
|
||||
#define DISABLE_VTX_POWER IOHi(vtxPowerPin)
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
#include "drivers/compass.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/stack_check.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_msp.h"
|
||||
|
@ -52,8 +53,7 @@
|
|||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/transponder_ir.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
#include "io/vtx_tramp.h" // Will be gone
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
|
@ -213,9 +213,10 @@ void taskVtxControl(uint32_t currentTime)
|
|||
if (ARMING_FLAG(ARMED))
|
||||
return;
|
||||
|
||||
#ifdef VTX_SMARTAUDIO
|
||||
smartAudioProcess(currentTime);
|
||||
#ifdef VTX_COMMON
|
||||
vtxCommonProcess(currentTime);
|
||||
#endif
|
||||
// Call to trampProcess() will be gone
|
||||
#ifdef VTX_TRAMP
|
||||
trampProcess(currentTime);
|
||||
#endif
|
||||
|
|
517
src/main/fc/fc_tasks.c.orig
Normal file
517
src/main/fc/fc_tasks.c.orig
Normal file
|
@ -0,0 +1,517 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "cms/cms.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/stack_check.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_msp.h"
|
||||
#include "fc/fc_tasks.h"
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/cli.h"
|
||||
#include "fc/fc_dispatch.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/dashboard.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/transponder_ir.h"
|
||||
<<<<<<< HEAD
|
||||
=======
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
>>>>>>> betaflight/master
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sonar.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#ifdef USE_BST
|
||||
void taskBstMasterProcess(timeUs_t currentTimeUs);
|
||||
#endif
|
||||
|
||||
#define TASK_PERIOD_HZ(hz) (1000000 / (hz))
|
||||
#define TASK_PERIOD_MS(ms) ((ms) * 1000)
|
||||
#define TASK_PERIOD_US(us) (us)
|
||||
|
||||
/* VBAT monitoring interval (in microseconds) - 1s*/
|
||||
#define VBATINTERVAL (6 * 3500)
|
||||
/* IBat monitoring interval (in microseconds) - 6 default looptimes */
|
||||
#define IBATINTERVAL (6 * 3500)
|
||||
|
||||
|
||||
static void taskUpdateAccelerometer(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
accUpdate(&accelerometerConfig()->accelerometerTrims);
|
||||
}
|
||||
|
||||
static void taskHandleSerial(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
#ifdef USE_CLI
|
||||
// in cli mode, all serial stuff goes to here. enter cli mode by sending #
|
||||
if (cliMode) {
|
||||
cliProcess();
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand);
|
||||
}
|
||||
|
||||
static void taskUpdateBattery(timeUs_t currentTimeUs)
|
||||
{
|
||||
#if defined(USE_ADC) || defined(USE_ESC_SENSOR)
|
||||
if (feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) {
|
||||
static uint32_t vbatLastServiced = 0;
|
||||
if (cmp32(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
|
||||
vbatLastServiced = currentTimeUs;
|
||||
updateBattery();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||
static uint32_t ibatLastServiced = 0;
|
||||
const int32_t ibatTimeSinceLastServiced = cmp32(currentTimeUs, ibatLastServiced);
|
||||
|
||||
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
||||
ibatLastServiced = currentTimeUs;
|
||||
updateCurrentMeter(ibatTimeSinceLastServiced, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void taskUpdateRxMain(timeUs_t currentTimeUs)
|
||||
{
|
||||
processRx(currentTimeUs);
|
||||
isRXDataNew = true;
|
||||
|
||||
#if !defined(BARO) && !defined(SONAR)
|
||||
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
||||
updateRcCommands();
|
||||
#endif
|
||||
updateLEDs();
|
||||
|
||||
#ifdef BARO
|
||||
if (sensors(SENSOR_BARO)) {
|
||||
updateAltHoldState();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
if (sensors(SENSOR_SONAR)) {
|
||||
updateSonarAltHoldState();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef MAG
|
||||
static void taskUpdateCompass(timeUs_t currentTimeUs)
|
||||
{
|
||||
if (sensors(SENSOR_MAG)) {
|
||||
compassUpdate(currentTimeUs, &compassConfig()->magZero);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
static void taskUpdateBaro(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
if (sensors(SENSOR_BARO)) {
|
||||
const uint32_t newDeadline = baroUpdate();
|
||||
if (newDeadline != 0) {
|
||||
rescheduleTask(TASK_SELF, newDeadline);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
static void taskCalculateAltitude(timeUs_t currentTimeUs)
|
||||
{
|
||||
if (false
|
||||
#if defined(BARO)
|
||||
|| (sensors(SENSOR_BARO) && isBaroReady())
|
||||
#endif
|
||||
#if defined(SONAR)
|
||||
|| sensors(SENSOR_SONAR)
|
||||
#endif
|
||||
) {
|
||||
calculateEstimatedAltitude(currentTimeUs);
|
||||
}}
|
||||
#endif
|
||||
|
||||
#ifdef TELEMETRY
|
||||
static void taskTelemetry(timeUs_t currentTimeUs)
|
||||
{
|
||||
telemetryCheckState();
|
||||
|
||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||
telemetryProcess(currentTimeUs, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef VTX_CONTROL
|
||||
// Everything that listens to VTX devices
|
||||
void taskVtxControl(uint32_t currentTime)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED))
|
||||
return;
|
||||
|
||||
#ifdef VTX_COMMON
|
||||
vtxCommonProcess(currentTime);
|
||||
#endif
|
||||
#ifdef VTX_TRAMP
|
||||
trampProcess(currentTime);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
void fcTasksInit(void)
|
||||
{
|
||||
schedulerInit();
|
||||
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
setTaskEnabled(TASK_ACCEL, true);
|
||||
rescheduleTask(TASK_ACCEL, acc.accSamplingInterval);
|
||||
}
|
||||
|
||||
setTaskEnabled(TASK_ATTITUDE, sensors(SENSOR_ACC));
|
||||
setTaskEnabled(TASK_SERIAL, true);
|
||||
rescheduleTask(TASK_SERIAL, TASK_PERIOD_HZ(serialConfig()->serial_update_rate_hz));
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
|
||||
setTaskEnabled(TASK_RX, true);
|
||||
|
||||
setTaskEnabled(TASK_DISPATCH, dispatchIsEnabled());
|
||||
|
||||
#ifdef BEEPER
|
||||
setTaskEnabled(TASK_BEEPER, true);
|
||||
#endif
|
||||
#ifdef GPS
|
||||
setTaskEnabled(TASK_GPS, feature(FEATURE_GPS));
|
||||
#endif
|
||||
#ifdef MAG
|
||||
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
||||
#if defined(USE_SPI) && defined(USE_MAG_AK8963)
|
||||
// fixme temporary solution for AK6983 via slave I2C on MPU9250
|
||||
rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40));
|
||||
#endif
|
||||
#endif
|
||||
#ifdef BARO
|
||||
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
|
||||
#endif
|
||||
#ifdef SONAR
|
||||
setTaskEnabled(TASK_SONAR, sensors(SENSOR_SONAR));
|
||||
#endif
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || sensors(SENSOR_SONAR));
|
||||
#endif
|
||||
#ifdef USE_DASHBOARD
|
||||
setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD));
|
||||
#endif
|
||||
#ifdef TELEMETRY
|
||||
setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
|
||||
if (feature(FEATURE_TELEMETRY)) {
|
||||
if (rxConfig()->serialrx_provider == SERIALRX_JETIEXBUS) {
|
||||
// Reschedule telemetry to 500hz for Jeti Exbus
|
||||
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
|
||||
} else if (rxConfig()->serialrx_provider == SERIALRX_CRSF) {
|
||||
// Reschedule telemetry to 500hz, 2ms for CRSF
|
||||
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#ifdef LED_STRIP
|
||||
setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP));
|
||||
#endif
|
||||
#ifdef TRANSPONDER
|
||||
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
|
||||
#endif
|
||||
#ifdef OSD
|
||||
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
||||
#endif
|
||||
#ifdef USE_BST
|
||||
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
||||
#endif
|
||||
#ifdef USE_ESC_SENSOR
|
||||
setTaskEnabled(TASK_ESC_SENSOR, feature(FEATURE_ESC_SENSOR));
|
||||
#endif
|
||||
#ifdef CMS
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
setTaskEnabled(TASK_CMS, true);
|
||||
#else
|
||||
setTaskEnabled(TASK_CMS, feature(FEATURE_OSD) || feature(FEATURE_DASHBOARD));
|
||||
#endif
|
||||
#endif
|
||||
#ifdef STACK_CHECK
|
||||
setTaskEnabled(TASK_STACK_CHECK, true);
|
||||
#endif
|
||||
#ifdef VTX_CONTROL
|
||||
#if defined(VTX_SMARTAUDIO) || defined(VTX_TRAMP)
|
||||
setTaskEnabled(TASK_VTXCTRL, true);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
cfTask_t cfTasks[TASK_COUNT] = {
|
||||
[TASK_SYSTEM] = {
|
||||
.taskName = "SYSTEM",
|
||||
.taskFunc = taskSystem,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz, every 100 ms
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
|
||||
},
|
||||
|
||||
[TASK_GYROPID] = {
|
||||
.taskName = "PID",
|
||||
.subTaskName = "GYRO",
|
||||
.taskFunc = taskMainPidLoop,
|
||||
.desiredPeriod = TASK_GYROPID_DESIRED_PERIOD,
|
||||
.staticPriority = TASK_PRIORITY_REALTIME,
|
||||
},
|
||||
|
||||
[TASK_ACCEL] = {
|
||||
.taskName = "ACCEL",
|
||||
.taskFunc = taskUpdateAccelerometer,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(1000), // 1000Hz, every 1ms
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
[TASK_ATTITUDE] = {
|
||||
.taskName = "ATTITUDE",
|
||||
.taskFunc = imuUpdateAttitude,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100),
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
[TASK_RX] = {
|
||||
.taskName = "RX",
|
||||
.checkFunc = rxUpdateCheck,
|
||||
.taskFunc = taskUpdateRxMain,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50), // If event-based scheduling doesn't work, fallback to periodic scheduling
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
[TASK_SERIAL] = {
|
||||
.taskName = "SERIAL",
|
||||
.taskFunc = taskHandleSerial,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
|
||||
[TASK_DISPATCH] = {
|
||||
.taskName = "DISPATCH",
|
||||
.taskFunc = dispatchProcess,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(1000),
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
[TASK_BATTERY] = {
|
||||
.taskName = "BATTERY",
|
||||
.taskFunc = taskUpdateBattery,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50), // 50 Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
#ifdef BEEPER
|
||||
[TASK_BEEPER] = {
|
||||
.taskName = "BEEPER",
|
||||
.taskFunc = beeperUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef GPS
|
||||
[TASK_GPS] = {
|
||||
.taskName = "GPS",
|
||||
.taskFunc = gpsUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // GPS usually don't go raster than 10Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
[TASK_COMPASS] = {
|
||||
.taskName = "COMPASS",
|
||||
.taskFunc = taskUpdateCompass,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // Compass is updated at 10 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
[TASK_BARO] = {
|
||||
.taskName = "BARO",
|
||||
.taskFunc = taskUpdateBaro,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(20),
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
[TASK_SONAR] = {
|
||||
.taskName = "SONAR",
|
||||
.taskFunc = sonarUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_MS(70), // 70ms required so that SONAR pulses do not interfer with each other
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
[TASK_ALTITUDE] = {
|
||||
.taskName = "ALTITUDE",
|
||||
.taskFunc = taskCalculateAltitude,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(40),
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
[TASK_TRANSPONDER] = {
|
||||
.taskName = "TRANSPONDER",
|
||||
.taskFunc = transponderUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(250), // 250 Hz, 4ms
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_DASHBOARD
|
||||
[TASK_DASHBOARD] = {
|
||||
.taskName = "DASHBOARD",
|
||||
.taskFunc = dashboardUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10),
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
#ifdef OSD
|
||||
[TASK_OSD] = {
|
||||
.taskName = "OSD",
|
||||
.taskFunc = osdUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(60), // 60 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
#ifdef TELEMETRY
|
||||
[TASK_TELEMETRY] = {
|
||||
.taskName = "TELEMETRY",
|
||||
.taskFunc = taskTelemetry,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(250), // 250 Hz, 4ms
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef LED_STRIP
|
||||
[TASK_LEDSTRIP] = {
|
||||
.taskName = "LEDSTRIP",
|
||||
.taskFunc = ledStripUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz, 10ms
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_BST
|
||||
[TASK_BST_MASTER_PROCESS] = {
|
||||
.taskName = "BST_MASTER_PROCESS",
|
||||
.taskFunc = taskBstMasterProcess,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50), // 50 Hz, 20ms
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
[TASK_ESC_SENSOR] = {
|
||||
.taskName = "ESC_SENSOR",
|
||||
.taskFunc = escSensorProcess,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz every 10ms
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef CMS
|
||||
[TASK_CMS] = {
|
||||
.taskName = "CMS",
|
||||
.taskFunc = cmsHandler,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(60), // 60 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef STACK_CHECK
|
||||
[TASK_STACK_CHECK] = {
|
||||
.taskName = "STACKCHECK",
|
||||
.taskFunc = taskStackCheck,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz
|
||||
.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
|
||||
};
|
110
src/main/io/vtx_singularity.c
Normal file
110
src/main/io/vtx_singularity.c
Normal file
|
@ -0,0 +1,110 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
|
||||
// Get target build configuration
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef VTX_SINGULARITY
|
||||
|
||||
// Own interfaces
|
||||
#include "io/vtx_singularity.h"
|
||||
#include "io/osd.h"
|
||||
|
||||
//External dependencies
|
||||
#include "config/config_master.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "drivers/vtx_rtc6705.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
|
||||
static uint8_t locked = 0;
|
||||
|
||||
void vtxSingularityInit(void)
|
||||
{
|
||||
rtc6705Init();
|
||||
if (masterConfig.vtx_mode == 0) {
|
||||
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
|
||||
} else if (masterConfig.vtx_mode == 1) {
|
||||
rtc6705SetFreq(masterConfig.vtx_mhz);
|
||||
}
|
||||
}
|
||||
|
||||
static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_t min, int32_t max)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
locked = 1;
|
||||
}
|
||||
|
||||
if (masterConfig.vtx_mode == 0 && !locked) {
|
||||
uint8_t temp = (*bandOrChannel) + step;
|
||||
temp = constrain(temp, min, max);
|
||||
*bandOrChannel = temp;
|
||||
|
||||
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
|
||||
writeEEPROM();
|
||||
readEEPROM();
|
||||
beeperConfirmationBeeps(temp);
|
||||
}
|
||||
}
|
||||
|
||||
void vtxSingularityIncrementBand(void)
|
||||
{
|
||||
setChannelSaveAndNotify(&(masterConfig.vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
|
||||
}
|
||||
|
||||
void vtxSingularityDecrementBand(void)
|
||||
{
|
||||
setChannelSaveAndNotify(&(masterConfig.vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
|
||||
}
|
||||
|
||||
void vtxSingularityIncrementChannel(void)
|
||||
{
|
||||
setChannelSaveAndNotify(&(masterConfig.vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
|
||||
}
|
||||
|
||||
void vtxSingularityDecrementChannel(void)
|
||||
{
|
||||
setChannelSaveAndNotify(&(masterConfig.vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
|
||||
}
|
||||
|
||||
void vtxSingularityUpdateActivatedChannel(void)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
locked = 1;
|
||||
}
|
||||
|
||||
if (masterConfig.vtx_mode == 2 && !locked) {
|
||||
static uint8_t lastIndex = -1;
|
||||
uint8_t index;
|
||||
|
||||
for (index = 0; index < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; index++) {
|
||||
vtxChannelActivationCondition_t *vtxChannelActivationCondition = &masterConfig.vtxChannelActivationConditions[index];
|
||||
|
||||
if (isRangeActive(vtxChannelActivationCondition->auxChannelIndex, &vtxChannelActivationCondition->range)
|
||||
&& index != lastIndex) {
|
||||
lastIndex = index;
|
||||
rtc6705SetChannel(vtxChannelActivationCondition->band, vtxChannelActivationCondition->channel);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
41
src/main/io/vtx_singularity.h
Normal file
41
src/main/io/vtx_singularity.h
Normal file
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#define VTX_BAND_MIN 1
|
||||
#define VTX_BAND_MAX 5
|
||||
#define VTX_CHANNEL_MIN 1
|
||||
#define VTX_CHANNEL_MAX 8
|
||||
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10
|
||||
|
||||
typedef struct vtxChannelActivationCondition_s {
|
||||
uint8_t auxChannelIndex;
|
||||
uint8_t band;
|
||||
uint8_t channel;
|
||||
channelRange_t range;
|
||||
} vtxChannelActivationCondition_t;
|
||||
|
||||
void vtxSingularityInit(void);
|
||||
void vtxSingularityIncrementBand(void);
|
||||
void vtxSingularityDecrementBand(void);
|
||||
void vtxSingularityIncrementChannel(void);
|
||||
void vtxSingularityDecrementChannel(void);
|
||||
void vtxSingularityUpdateActivatedChannel(void);
|
||||
|
|
@ -33,9 +33,10 @@
|
|||
#include "common/utils.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_common.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -70,6 +71,25 @@ static void saUpdateStatusString(void); // Forward
|
|||
|
||||
static serialPort_t *smartAudioSerialPort = NULL;
|
||||
|
||||
#if defined(CMS) || defined(VTX_COMMON)
|
||||
static const char * const saPowerNames[] = {
|
||||
"---", "25 ", "200", "500", "800",
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef VTX_COMMON
|
||||
static vtxVTable_t saVTable; // Forward
|
||||
static vtxDevice_t vtxSmartAudio = {
|
||||
.vTable = &saVTable,
|
||||
.numBand = 5,
|
||||
.numChan = 8,
|
||||
.numPower = 4,
|
||||
.bandNames = (char **)vtx58BandNames,
|
||||
.chanNames = (char **)vtx58ChannelNames,
|
||||
.powerNames = (char **)saPowerNames,
|
||||
};
|
||||
#endif
|
||||
|
||||
// SmartAudio command and response codes
|
||||
enum {
|
||||
SA_CMD_NONE = 0x00,
|
||||
|
@ -228,11 +248,11 @@ static int saDacToPowerIndex(int dac)
|
|||
{
|
||||
int idx;
|
||||
|
||||
for (idx = 0 ; idx < 4 ; idx++) {
|
||||
for (idx = 3 ; idx >= 0 ; idx--) {
|
||||
if (saPowerTable[idx].valueV1 <= dac)
|
||||
return(idx);
|
||||
}
|
||||
return(3);
|
||||
return(0);
|
||||
}
|
||||
|
||||
//
|
||||
|
@ -367,6 +387,10 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
saPrintSettings();
|
||||
saDevicePrev = saDevice;
|
||||
|
||||
#ifdef VTX_COMMON
|
||||
// Todo: Update states in saVtxDevice?
|
||||
#endif
|
||||
|
||||
#ifdef CMS
|
||||
// Export current device status for CMS
|
||||
saCmsUpdate();
|
||||
|
@ -661,10 +685,13 @@ bool smartAudioInit()
|
|||
return false;
|
||||
}
|
||||
|
||||
vtxSmartAudio.vTable = &saVTable;
|
||||
vtxCommonRegisterDevice(&vtxSmartAudio);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void smartAudioProcess(uint32_t now)
|
||||
void vtxSAProcess(uint32_t now)
|
||||
{
|
||||
static bool initialSent = false;
|
||||
|
||||
|
@ -703,8 +730,120 @@ void smartAudioProcess(uint32_t now)
|
|||
saGetSettings();
|
||||
saSendQueue();
|
||||
}
|
||||
|
||||
#ifdef SMARTAUDIO_TEST_VTX_COMMON
|
||||
// Testing VTX_COMMON API
|
||||
{
|
||||
static uint32_t lastMonitorUs = 0;
|
||||
if (cmp32(now, lastMonitorUs) < 5 * 1000 * 1000)
|
||||
return;
|
||||
|
||||
static uint8_t monBand;
|
||||
static uint8_t monChan;
|
||||
static uint8_t monPower;
|
||||
|
||||
vtxCommonGetBandChan(&monBand, &monChan);
|
||||
vtxCommonGetPowerIndex(&monPower);
|
||||
debug[0] = monBand;
|
||||
debug[1] = monChan;
|
||||
debug[2] = monPower;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef VTX_COMMON
|
||||
// Interface to common VTX API
|
||||
|
||||
vtxDevType_e vtxSAGetDeviceType(void)
|
||||
{
|
||||
return VTXDEV_SMARTAUDIO;
|
||||
}
|
||||
|
||||
bool vtxSAIsReady(void)
|
||||
{
|
||||
return !(saDevice.version == 0);
|
||||
}
|
||||
|
||||
void vtxSASetBandChan(uint8_t band, uint8_t chan)
|
||||
{
|
||||
if (band && chan)
|
||||
saSetBandChan(band - 1, chan - 1);
|
||||
}
|
||||
|
||||
void vtxSASetPowerByIndex(uint8_t index)
|
||||
{
|
||||
if (index == 0) {
|
||||
// SmartAudio doesn't support power off.
|
||||
return;
|
||||
}
|
||||
|
||||
saSetPowerByIndex(index - 1);
|
||||
}
|
||||
|
||||
void vtxSASetPitmode(uint8_t onoff)
|
||||
{
|
||||
if (!(vtxSAIsReady() && (saDevice.version == 2)))
|
||||
return;
|
||||
|
||||
if (onoff) {
|
||||
// SmartAudio can not turn pit mode on by software.
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t newmode = SA_MODE_CLR_PITMODE;
|
||||
|
||||
if (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE)
|
||||
newmode |= SA_MODE_SET_IN_RANGE_PITMODE;
|
||||
|
||||
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
|
||||
newmode |= SA_MODE_SET_OUT_RANGE_PITMODE;
|
||||
|
||||
saSetMode(newmode);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool vtxSAGetBandChan(uint8_t *pBand, uint8_t *pChan)
|
||||
{
|
||||
if (!vtxSAIsReady())
|
||||
return false;
|
||||
|
||||
*pBand = (saDevice.chan / 8) + 1;
|
||||
*pChan = (saDevice.chan % 8) + 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool vtxSAGetPowerIndex(uint8_t *pIndex)
|
||||
{
|
||||
if (!vtxSAIsReady())
|
||||
return false;
|
||||
|
||||
*pIndex = ((saDevice.version == 1) ? saDacToPowerIndex(saDevice.power) : saDevice.power) + 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool vtxSAGetPitmode(uint8_t *pOnoff)
|
||||
{
|
||||
if (!(vtxSAIsReady() && (saDevice.version == 2)))
|
||||
return false;
|
||||
|
||||
*pOnoff = (saDevice.mode & SA_MODE_GET_PITMODE) ? 1 : 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
static vtxVTable_t saVTable = {
|
||||
.process = vtxSAProcess,
|
||||
.getDeviceType = vtxSAGetDeviceType,
|
||||
.isReady = vtxSAIsReady,
|
||||
.setBandChan = vtxSASetBandChan,
|
||||
.setPowerByIndex = vtxSASetPowerByIndex,
|
||||
.setPitmode = vtxSASetPitmode,
|
||||
.getBandChan = vtxSAGetBandChan,
|
||||
.getPowerIndex = vtxSAGetPowerIndex,
|
||||
.getPitmode = vtxSAGetPitmode,
|
||||
};
|
||||
#endif // VTX_COMMON
|
||||
|
||||
#ifdef CMS
|
||||
|
||||
// Interface to CMS
|
||||
|
@ -806,7 +945,7 @@ if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
|
|||
else
|
||||
saCmsPitFMode = 0;
|
||||
|
||||
saCmsStatusString[0] = "-FP"[(saDevice.mode & SA_MODE_GET_PITMODE) ? SACMS_OPMODEL_RACE : SACMS_OPMODEL_FREE];
|
||||
saCmsStatusString[0] = "-FR"[saCmsOpmodel];
|
||||
saCmsStatusString[2] = "ABEFR"[saDevice.chan / 8];
|
||||
saCmsStatusString[3] = '1' + (saDevice.chan % 8);
|
||||
|
||||
|
@ -846,15 +985,13 @@ static long saCmsConfigBandByGvar(displayPort_t *pDisp, const void *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
dprintf(("saCmsConfigBand: band req %d ", saCmsBand));
|
||||
|
||||
if (saCmsBand == 0) {
|
||||
// Bouce back, no going back to undef state
|
||||
saCmsBand = 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
|
||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
||||
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
||||
|
||||
saCmsFreqRef = vtx58FreqTable[saCmsBand - 1][saCmsChan - 1];
|
||||
|
@ -879,7 +1016,7 @@ static long saCmsConfigChanByGvar(displayPort_t *pDisp, const void *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
if (!(saCmsOpmodel == SACMS_OPMODEL_FREE && saDeferred))
|
||||
if ((saCmsOpmodel == SACMS_OPMODEL_FREE) && !saDeferred)
|
||||
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
||||
|
||||
saCmsFreqRef = vtx58FreqTable[saCmsBand - 1][saCmsChan - 1];
|
||||
|
@ -904,7 +1041,8 @@ static long saCmsConfigPowerByGvar(displayPort_t *pDisp, const void *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
saSetPowerByIndex(saCmsPower - 1);
|
||||
if (saCmsOpmodel == SACMS_OPMODEL_FREE)
|
||||
saSetPowerByIndex(saCmsPower - 1);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -985,7 +1123,7 @@ static CMS_Menu saCmsMenuStats = {
|
|||
|
||||
static OSD_TAB_t saCmsEntBand = { &saCmsBand, 5, vtx58BandNames, NULL };
|
||||
|
||||
static OSD_TAB_t saCmsEntChan = { &saCmsChan, 8, &vtx58ChannelNames[0], NULL };
|
||||
static OSD_TAB_t saCmsEntChan = { &saCmsChan, 8, vtx58ChannelNames, NULL };
|
||||
|
||||
static const char * const saCmsPowerNames[] = {
|
||||
"---",
|
||||
|
@ -1048,11 +1186,21 @@ static long saCmsCommence(displayPort_t *pDisp, const void *self)
|
|||
UNUSED(self);
|
||||
|
||||
if (saCmsOpmodel == SACMS_OPMODEL_RACE) {
|
||||
// Race model
|
||||
// Setup band, freq and power.
|
||||
|
||||
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
||||
saSetPowerByIndex(saCmsPower - 1);
|
||||
|
||||
// If in pit mode, cancel it.
|
||||
|
||||
if (saCmsPitFMode == 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 {
|
||||
// Freestyle model
|
||||
// Setup band and freq / user freq
|
||||
if (saCmsFselMode == 0)
|
||||
saSetBandChan(saCmsBand - 1, saCmsChan - 1);
|
||||
else
|
||||
|
|
1422
src/main/io/vtx_smartaudio.c.orig
Normal file
1422
src/main/io/vtx_smartaudio.c.orig
Normal file
File diff suppressed because it is too large
Load diff
|
@ -25,7 +25,7 @@
|
|||
#include "platform.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#if defined(VTX_CONTROL)
|
||||
#if defined(VTX_COMMON)
|
||||
|
||||
const uint16_t vtx58FreqTable[5][8] =
|
||||
{
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
#if defined(VTX_CONTROL)
|
||||
#if defined(VTX_COMMON)
|
||||
|
||||
extern const uint16_t vtx58FreqTable[5][8];
|
||||
extern const char * const vtx58BandNames[];
|
|
@ -35,7 +35,7 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
#include "io/vtx_common.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
static serialPort_t *trampSerialPort = NULL;
|
||||
|
||||
|
|
|
@ -103,6 +103,7 @@
|
|||
#define TELEMETRY_IBUS
|
||||
#define USE_RX_MSP
|
||||
#define USE_SERIALRX_JETIEXBUS
|
||||
#define VTX_COMMON
|
||||
#define VTX_CONTROL
|
||||
#define VTX_SMARTAUDIO
|
||||
#define VTX_TRAMP
|
||||
|
|
|
@ -22,4 +22,7 @@
|
|||
// Targets with built-in vtx do not need external vtx
|
||||
#if defined(VTX) || defined(USE_RTC6705)
|
||||
# undef VTX_CONTROL
|
||||
# undef VTX_COMMON
|
||||
# undef VTX_SMARTAUDIO
|
||||
# undef VTX_TRAMP
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue