mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Removed a number of static config pointers
This commit is contained in:
parent
a3951a3340
commit
5851b21e4a
26 changed files with 67 additions and 173 deletions
|
@ -904,16 +904,12 @@ void activateConfig(void)
|
||||||
¤tProfile->pidProfile
|
¤tProfile->pidProfile
|
||||||
);
|
);
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
|
||||||
telemetryUseConfig(&masterConfig.telemetryConfig);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsUseProfile(&masterConfig.gpsProfile);
|
gpsUseProfile(&masterConfig.gpsProfile);
|
||||||
gpsUsePIDs(¤tProfile->pidProfile);
|
gpsUsePIDs(¤tProfile->pidProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
useFailsafeConfig(&masterConfig.failsafeConfig);
|
failsafeReset();
|
||||||
setAccelerationTrims(&accelerometerConfigMutable()->accZero);
|
setAccelerationTrims(&accelerometerConfigMutable()->accZero);
|
||||||
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
|
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
|
||||||
|
|
||||||
|
@ -942,10 +938,6 @@ void activateConfig(void)
|
||||||
&masterConfig.rcControlsConfig,
|
&masterConfig.rcControlsConfig,
|
||||||
&masterConfig.motorConfig
|
&masterConfig.motorConfig
|
||||||
);
|
);
|
||||||
|
|
||||||
#ifdef BARO
|
|
||||||
useBarometerConfig(&masterConfig.barometerConfig);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void validateAndFixConfig(void)
|
void validateAndFixConfig(void)
|
||||||
|
|
|
@ -259,16 +259,16 @@ void init(void)
|
||||||
timerInit(); // timer must be initialized before any channel is allocated
|
timerInit(); // timer must be initialized before any channel is allocated
|
||||||
|
|
||||||
#if defined(AVOID_UART1_FOR_PWM_PPM)
|
#if defined(AVOID_UART1_FOR_PWM_PPM)
|
||||||
serialInit(serialConfig(), feature(FEATURE_SOFTSERIAL),
|
serialInit(feature(FEATURE_SOFTSERIAL),
|
||||||
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
|
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
|
||||||
#elif defined(AVOID_UART2_FOR_PWM_PPM)
|
#elif defined(AVOID_UART2_FOR_PWM_PPM)
|
||||||
serialInit(serialConfig(), feature(FEATURE_SOFTSERIAL),
|
serialInit(feature(FEATURE_SOFTSERIAL),
|
||||||
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
|
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
|
||||||
#elif defined(AVOID_UART3_FOR_PWM_PPM)
|
#elif defined(AVOID_UART3_FOR_PWM_PPM)
|
||||||
serialInit(serialConfig(), feature(FEATURE_SOFTSERIAL),
|
serialInit(feature(FEATURE_SOFTSERIAL),
|
||||||
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE);
|
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE);
|
||||||
#else
|
#else
|
||||||
serialInit(serialConfig(), feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
serialInit(feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
mixerInit(mixerConfig()->mixerMode, masterConfig.customMotorMixer);
|
mixerInit(mixerConfig()->mixerMode, masterConfig.customMotorMixer);
|
||||||
|
@ -443,7 +443,7 @@ void init(void)
|
||||||
cliInit(serialConfig());
|
cliInit(serialConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
failsafeInit(rxConfig(), flight3DConfig()->deadband3d_throttle);
|
failsafeInit(flight3DConfig()->deadband3d_throttle);
|
||||||
|
|
||||||
rxInit(rxConfig(), modeActivationProfile()->modeActivationConditions);
|
rxInit(rxConfig(), modeActivationProfile()->modeActivationConditions);
|
||||||
|
|
||||||
|
|
|
@ -204,7 +204,7 @@ static void taskTelemetry(timeUs_t currentTimeUs)
|
||||||
telemetryCheckState();
|
telemetryCheckState();
|
||||||
|
|
||||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||||
telemetryProcess(currentTimeUs, rxConfig(), flight3DConfig()->deadband3d_throttle);
|
telemetryProcess(currentTimeUs);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -43,9 +43,9 @@
|
||||||
/*
|
/*
|
||||||
* Usage:
|
* Usage:
|
||||||
*
|
*
|
||||||
* failsafeInit() and useFailsafeConfig() must be called before the other methods are used.
|
* failsafeInit() and resetFailsafe() must be called before the other methods are used.
|
||||||
*
|
*
|
||||||
* failsafeInit() and useFailsafeConfig() can be called in any order.
|
* failsafeInit() and resetFailsafe() can be called in any order.
|
||||||
* failsafeInit() should only be called once.
|
* failsafeInit() should only be called once.
|
||||||
*
|
*
|
||||||
* enable() should be called after system initialisation.
|
* enable() should be called after system initialisation.
|
||||||
|
@ -53,16 +53,14 @@
|
||||||
|
|
||||||
static failsafeState_t failsafeState;
|
static failsafeState_t failsafeState;
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROPUS
|
|
||||||
static const failsafeConfig_t *failsafeConfig;
|
|
||||||
static const rxConfig_t *rxConfig;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static uint16_t deadband3dThrottle; // default throttle deadband from MIDRC
|
static uint16_t deadband3dThrottle; // default throttle deadband from MIDRC
|
||||||
|
|
||||||
static void failsafeReset(void)
|
/*
|
||||||
|
* Should called when the failsafe config needs to be changed - e.g. a different profile has been selected.
|
||||||
|
*/
|
||||||
|
void failsafeReset(void)
|
||||||
{
|
{
|
||||||
failsafeState.rxDataFailurePeriod = PERIOD_RXDATA_FAILURE + failsafeConfig->failsafe_delay * MILLIS_PER_TENTH_SECOND;
|
failsafeState.rxDataFailurePeriod = PERIOD_RXDATA_FAILURE + failsafeConfig()->failsafe_delay * MILLIS_PER_TENTH_SECOND;
|
||||||
failsafeState.validRxDataReceivedAt = 0;
|
failsafeState.validRxDataReceivedAt = 0;
|
||||||
failsafeState.validRxDataFailedAt = 0;
|
failsafeState.validRxDataFailedAt = 0;
|
||||||
failsafeState.throttleLowPeriod = 0;
|
failsafeState.throttleLowPeriod = 0;
|
||||||
|
@ -73,27 +71,8 @@ static void failsafeReset(void)
|
||||||
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
|
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
void failsafeInit(uint16_t deadband3d_throttle)
|
||||||
* Should called when the failsafe config needs to be changed - e.g. a different profile has been selected.
|
|
||||||
*/
|
|
||||||
void useFailsafeConfig(const failsafeConfig_t *failsafeConfigToUse)
|
|
||||||
{
|
{
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
(void)(failsafeConfigToUse);
|
|
||||||
#else
|
|
||||||
failsafeConfig = failsafeConfigToUse;
|
|
||||||
#endif
|
|
||||||
failsafeReset();
|
|
||||||
}
|
|
||||||
|
|
||||||
void failsafeInit(const rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle)
|
|
||||||
{
|
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
(void)(intialRxConfig);
|
|
||||||
#else
|
|
||||||
rxConfig = intialRxConfig;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
deadband3dThrottle = deadband3d_throttle;
|
deadband3dThrottle = deadband3d_throttle;
|
||||||
failsafeState.events = 0;
|
failsafeState.events = 0;
|
||||||
failsafeState.monitoring = false;
|
failsafeState.monitoring = false;
|
||||||
|
@ -131,7 +110,7 @@ static void failsafeActivate(void)
|
||||||
failsafeState.active = true;
|
failsafeState.active = true;
|
||||||
failsafeState.phase = FAILSAFE_LANDING;
|
failsafeState.phase = FAILSAFE_LANDING;
|
||||||
ENABLE_FLIGHT_MODE(FAILSAFE_MODE);
|
ENABLE_FLIGHT_MODE(FAILSAFE_MODE);
|
||||||
failsafeState.landingShouldBeFinishedAt = millis() + failsafeConfig->failsafe_off_delay * MILLIS_PER_TENTH_SECOND;
|
failsafeState.landingShouldBeFinishedAt = millis() + failsafeConfig()->failsafe_off_delay * MILLIS_PER_TENTH_SECOND;
|
||||||
|
|
||||||
failsafeState.events++;
|
failsafeState.events++;
|
||||||
}
|
}
|
||||||
|
@ -139,9 +118,9 @@ static void failsafeActivate(void)
|
||||||
static void failsafeApplyControlInput(void)
|
static void failsafeApplyControlInput(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < 3; i++) {
|
for (int i = 0; i < 3; i++) {
|
||||||
rcData[i] = rxConfig->midrc;
|
rcData[i] = rxConfig()->midrc;
|
||||||
}
|
}
|
||||||
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
|
rcData[THROTTLE] = failsafeConfig()->failsafe_throttle;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool failsafeIsReceivingRxData(void)
|
bool failsafeIsReceivingRxData(void)
|
||||||
|
@ -201,11 +180,11 @@ void failsafeUpdateState(void)
|
||||||
case FAILSAFE_IDLE:
|
case FAILSAFE_IDLE:
|
||||||
if (armed) {
|
if (armed) {
|
||||||
// Track throttle command below minimum time
|
// Track throttle command below minimum time
|
||||||
if (THROTTLE_HIGH == calculateThrottleStatus(rxConfig, deadband3dThrottle)) {
|
if (THROTTLE_HIGH == calculateThrottleStatus(rxConfig(), deadband3dThrottle)) {
|
||||||
failsafeState.throttleLowPeriod = millis() + failsafeConfig->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
|
failsafeState.throttleLowPeriod = millis() + failsafeConfig()->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
|
||||||
}
|
}
|
||||||
// Kill switch logic (must be independent of receivingRxData to skip PERIOD_RXDATA_FAILURE delay before disarming)
|
// Kill switch logic (must be independent of receivingRxData to skip PERIOD_RXDATA_FAILURE delay before disarming)
|
||||||
if (failsafeSwitchIsOn && failsafeConfig->failsafe_kill_switch) {
|
if (failsafeSwitchIsOn && failsafeConfig()->failsafe_kill_switch) {
|
||||||
// KillswitchEvent: failsafe switch is configured as KILL switch and is switched ON
|
// KillswitchEvent: failsafe switch is configured as KILL switch and is switched ON
|
||||||
failsafeActivate();
|
failsafeActivate();
|
||||||
failsafeState.phase = FAILSAFE_LANDED; // skip auto-landing procedure
|
failsafeState.phase = FAILSAFE_LANDED; // skip auto-landing procedure
|
||||||
|
@ -238,7 +217,7 @@ void failsafeUpdateState(void)
|
||||||
if (receivingRxData) {
|
if (receivingRxData) {
|
||||||
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
|
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
|
||||||
} else {
|
} else {
|
||||||
switch (failsafeConfig->failsafe_procedure) {
|
switch (failsafeConfig()->failsafe_procedure) {
|
||||||
default:
|
default:
|
||||||
case FAILSAFE_PROCEDURE_AUTO_LANDING:
|
case FAILSAFE_PROCEDURE_AUTO_LANDING:
|
||||||
// Stabilize, and set Throttle to specified level
|
// Stabilize, and set Throttle to specified level
|
||||||
|
@ -300,7 +279,7 @@ void failsafeUpdateState(void)
|
||||||
// Entering IDLE with the requirement that throttle first must be at min_check for failsafe_throttle_low_delay period.
|
// Entering IDLE with the requirement that throttle first must be at min_check for failsafe_throttle_low_delay period.
|
||||||
// This is to prevent that JustDisarm is activated on the next iteration.
|
// This is to prevent that JustDisarm is activated on the next iteration.
|
||||||
// Because that would have the effect of shutting down failsafe handling on intermittent connections.
|
// Because that would have the effect of shutting down failsafe handling on intermittent connections.
|
||||||
failsafeState.throttleLowPeriod = millis() + failsafeConfig->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
|
failsafeState.throttleLowPeriod = millis() + failsafeConfig()->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
|
||||||
failsafeState.phase = FAILSAFE_IDLE;
|
failsafeState.phase = FAILSAFE_IDLE;
|
||||||
failsafeState.active = false;
|
failsafeState.active = false;
|
||||||
DISABLE_FLIGHT_MODE(FAILSAFE_MODE);
|
DISABLE_FLIGHT_MODE(FAILSAFE_MODE);
|
||||||
|
|
|
@ -74,9 +74,8 @@ typedef struct failsafeState_s {
|
||||||
failsafeRxLinkState_e rxLinkState;
|
failsafeRxLinkState_e rxLinkState;
|
||||||
} failsafeState_t;
|
} failsafeState_t;
|
||||||
|
|
||||||
struct rxConfig_s;
|
void failsafeInit(uint16_t deadband3d_throttle);
|
||||||
void failsafeInit(const struct rxConfig_s *intialRxConfig, uint16_t deadband3d_throttle);
|
void failsafeReset(void);
|
||||||
void useFailsafeConfig(const failsafeConfig_t *failsafeConfigToUse);
|
|
||||||
|
|
||||||
void failsafeStartMonitoring(void);
|
void failsafeStartMonitoring(void);
|
||||||
void failsafeUpdateState(void);
|
void failsafeUpdateState(void);
|
||||||
|
|
|
@ -54,7 +54,6 @@
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static const serialConfig_t *serialConfig;
|
|
||||||
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
|
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
|
||||||
|
|
||||||
const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
||||||
|
@ -396,16 +395,12 @@ void closeSerialPort(serialPort_t *serialPort)
|
||||||
serialPortUsage->serialPort = NULL;
|
serialPortUsage->serialPort = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialInit(const serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
|
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
|
||||||
{
|
{
|
||||||
uint8_t index;
|
|
||||||
|
|
||||||
serialConfig = initialSerialConfig;
|
|
||||||
|
|
||||||
serialPortCount = SERIAL_PORT_COUNT;
|
serialPortCount = SERIAL_PORT_COUNT;
|
||||||
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
||||||
|
|
||||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||||
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
|
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
|
||||||
|
|
||||||
if (serialPortToDisable != SERIAL_PORT_NONE) {
|
if (serialPortToDisable != SERIAL_PORT_NONE) {
|
||||||
|
@ -471,7 +466,7 @@ void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar)
|
||||||
cliEnter(serialPort);
|
cliEnter(serialPort);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
if (receivedChar == serialConfig->reboot_character) {
|
if (receivedChar == serialConfig()->reboot_character) {
|
||||||
systemResetToBootloader();
|
systemResetToBootloader();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -488,8 +483,7 @@ static void nopConsumer(uint8_t data)
|
||||||
arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
|
arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
|
||||||
for specialized data processing.
|
for specialized data processing.
|
||||||
*/
|
*/
|
||||||
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
|
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
|
||||||
*leftC, serialConsumer *rightC)
|
|
||||||
{
|
{
|
||||||
waitForSerialPortToFinishTransmitting(left);
|
waitForSerialPortToFinishTransmitting(left);
|
||||||
waitForSerialPortToFinishTransmitting(right);
|
waitForSerialPortToFinishTransmitting(right);
|
||||||
|
|
|
@ -122,7 +122,7 @@ typedef void serialConsumer(uint8_t);
|
||||||
//
|
//
|
||||||
// configuration
|
// configuration
|
||||||
//
|
//
|
||||||
void serialInit(const serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||||
uint8_t serialGetAvailablePortCount(void);
|
uint8_t serialGetAvailablePortCount(void);
|
||||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
||||||
|
|
|
@ -407,10 +407,8 @@ static uint16_t jetiExBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uin
|
||||||
-----------------------------------------------
|
-----------------------------------------------
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void initJetiExBusTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
void initJetiExBusTelemetry(void)
|
||||||
{
|
{
|
||||||
UNUSED(initialTelemetryConfig);
|
|
||||||
|
|
||||||
// Init Ex Bus Frame header
|
// Init Ex Bus Frame header
|
||||||
jetiExBusTelemetryFrame[EXBUS_HEADER_SYNC] = 0x3B; // Startbytes
|
jetiExBusTelemetryFrame[EXBUS_HEADER_SYNC] = 0x3B; // Startbytes
|
||||||
jetiExBusTelemetryFrame[EXBUS_HEADER_REQ] = 0x01;
|
jetiExBusTelemetryFrame[EXBUS_HEADER_REQ] = 0x01;
|
||||||
|
@ -427,7 +425,6 @@ void initJetiExBusTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
||||||
jetiExTelemetryFrame[EXTEL_HEADER_RES] = 0x00; // reserved, by default 0x00
|
jetiExTelemetryFrame[EXTEL_HEADER_RES] = 0x00; // reserved, by default 0x00
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void createExTelemetrieTextMessage(uint8_t *exMessage, uint8_t messageID, const exBusSensor_t *sensor)
|
void createExTelemetrieTextMessage(uint8_t *exMessage, uint8_t messageID, const exBusSensor_t *sensor)
|
||||||
{
|
{
|
||||||
uint8_t labelLength = strlen(sensor->label);
|
uint8_t labelLength = strlen(sensor->label);
|
||||||
|
|
|
@ -246,13 +246,13 @@ retry:
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroSamplingInverval)
|
bool accInit(uint32_t gyroSamplingInverval)
|
||||||
{
|
{
|
||||||
memset(&acc, 0, sizeof(acc));
|
memset(&acc, 0, sizeof(acc));
|
||||||
// copy over the common gyro mpu settings
|
// copy over the common gyro mpu settings
|
||||||
acc.dev.mpuConfiguration = gyro.dev.mpuConfiguration;
|
acc.dev.mpuConfiguration = gyro.dev.mpuConfiguration;
|
||||||
acc.dev.mpuDetectionResult = gyro.dev.mpuDetectionResult;
|
acc.dev.mpuDetectionResult = gyro.dev.mpuDetectionResult;
|
||||||
if (!accDetect(&acc.dev, accelerometerConfig->acc_hardware)) {
|
if (!accDetect(&acc.dev, accelerometerConfig()->acc_hardware)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
acc.dev.acc_1G = 256; // set default
|
acc.dev.acc_1G = 256; // set default
|
||||||
|
|
|
@ -69,7 +69,7 @@ typedef struct accelerometerConfig_s {
|
||||||
|
|
||||||
PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
|
PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
|
||||||
|
|
||||||
bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroTargetLooptime);
|
bool accInit(uint32_t gyroTargetLooptime);
|
||||||
bool isAccelerationCalibrationComplete(void);
|
bool isAccelerationCalibrationComplete(void);
|
||||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
|
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
|
||||||
|
|
|
@ -54,10 +54,6 @@ static int32_t baroGroundAltitude = 0;
|
||||||
static int32_t baroGroundPressure = 0;
|
static int32_t baroGroundPressure = 0;
|
||||||
static uint32_t baroPressureSum = 0;
|
static uint32_t baroPressureSum = 0;
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
|
||||||
static const barometerConfig_t *barometerConfig;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||||
{
|
{
|
||||||
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
||||||
|
@ -124,15 +120,6 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void useBarometerConfig(const barometerConfig_t *barometerConfigToUse)
|
|
||||||
{
|
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
(void)(barometerConfigToUse);
|
|
||||||
#else
|
|
||||||
barometerConfig = barometerConfigToUse;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
bool isBaroCalibrationComplete(void)
|
bool isBaroCalibrationComplete(void)
|
||||||
{
|
{
|
||||||
return calibratingB == 0;
|
return calibratingB == 0;
|
||||||
|
|
|
@ -49,7 +49,6 @@ typedef struct baro_s {
|
||||||
extern baro_t baro;
|
extern baro_t baro;
|
||||||
|
|
||||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse);
|
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse);
|
||||||
void useBarometerConfig(const barometerConfig_t *barometerConfigToUse);
|
|
||||||
bool isBaroCalibrationComplete(void);
|
bool isBaroCalibrationComplete(void);
|
||||||
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||||
uint32_t baroUpdate(void);
|
uint32_t baroUpdate(void);
|
||||||
|
|
|
@ -146,12 +146,12 @@ retry:
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void compassInit(const compassConfig_t *compassConfig)
|
void compassInit(void)
|
||||||
{
|
{
|
||||||
// initialize and calibration. turn on led during mag calibration (calibration routine blinks it)
|
// initialize and calibration. turn on led during mag calibration (calibration routine blinks it)
|
||||||
// calculate magnetic declination
|
// calculate magnetic declination
|
||||||
const int16_t deg = compassConfig->mag_declination / 100;
|
const int16_t deg = compassConfig()->mag_declination / 100;
|
||||||
const int16_t min = compassConfig->mag_declination % 100;
|
const int16_t min = compassConfig()->mag_declination % 100;
|
||||||
mag.magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
|
mag.magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
|
||||||
LED1_ON;
|
LED1_ON;
|
||||||
mag.dev.init();
|
mag.dev.init();
|
||||||
|
|
|
@ -50,7 +50,7 @@ typedef struct compassConfig_s {
|
||||||
PG_DECLARE(compassConfig_t, compassConfig);
|
PG_DECLARE(compassConfig_t, compassConfig);
|
||||||
|
|
||||||
bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse);
|
bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse);
|
||||||
void compassInit(const compassConfig_t *compassConfig);
|
void compassInit(void);
|
||||||
union flightDynamicsTrims_u;
|
union flightDynamicsTrims_u;
|
||||||
void compassUpdate(uint32_t currentTime, union flightDynamicsTrims_u *magZero);
|
void compassUpdate(uint32_t currentTime, union flightDynamicsTrims_u *magZero);
|
||||||
|
|
||||||
|
|
|
@ -61,12 +61,12 @@ bool sensorsAutodetect(void)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
accInit(accelerometerConfig(), gyro.targetLooptime);
|
accInit(gyro.targetLooptime);
|
||||||
|
|
||||||
mag.magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
|
mag.magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
if (compassDetect(&mag.dev, compassConfig()->mag_hardware)) {
|
if (compassDetect(&mag.dev, compassConfig()->mag_hardware)) {
|
||||||
compassInit(compassConfig());
|
compassInit();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -74,9 +74,6 @@ static serialPortConfig_t *portConfig;
|
||||||
#define FRSKY_BAUDRATE 9600
|
#define FRSKY_BAUDRATE 9600
|
||||||
#define FRSKY_INITIAL_PORT_MODE MODE_TX
|
#define FRSKY_INITIAL_PORT_MODE MODE_TX
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
|
||||||
static const telemetryConfig_t *telemetryConfig;
|
|
||||||
#endif
|
|
||||||
static bool frskyTelemetryEnabled = false;
|
static bool frskyTelemetryEnabled = false;
|
||||||
static portSharing_e frskyPortSharing;
|
static portSharing_e frskyPortSharing;
|
||||||
|
|
||||||
|
@ -457,13 +454,8 @@ static void sendHeading(void)
|
||||||
serialize16(0);
|
serialize16(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void initFrSkyTelemetry(const telemetryConfig_t *initialTelemetryConfig)
|
void initFrSkyTelemetry(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
UNUSED(initialTelemetryConfig);
|
|
||||||
#else
|
|
||||||
telemetryConfig = initialTelemetryConfig;
|
|
||||||
#endif
|
|
||||||
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_FRSKY);
|
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_FRSKY);
|
||||||
frskyPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_FRSKY);
|
frskyPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_FRSKY);
|
||||||
}
|
}
|
||||||
|
@ -515,7 +507,7 @@ void checkFrSkyTelemetryState(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleFrSkyTelemetry(const rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
void handleFrSkyTelemetry(void)
|
||||||
{
|
{
|
||||||
if (!frskyTelemetryEnabled) {
|
if (!frskyTelemetryEnabled) {
|
||||||
return;
|
return;
|
||||||
|
@ -546,7 +538,7 @@ void handleFrSkyTelemetry(const rxConfig_t *rxConfig, uint16_t deadband3d_thrott
|
||||||
|
|
||||||
if ((cycleNum % 8) == 0) { // Sent every 1s
|
if ((cycleNum % 8) == 0) { // Sent every 1s
|
||||||
sendTemperature1();
|
sendTemperature1();
|
||||||
sendThrottleOrBatterySizeAsRpm(rxConfig, deadband3d_throttle);
|
sendThrottleOrBatterySizeAsRpm(rxConfig(), flight3DConfig()->deadband3d_throttle);
|
||||||
|
|
||||||
if ((feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) && batteryCellCount > 0) {
|
if ((feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) && batteryCellCount > 0) {
|
||||||
sendVoltage();
|
sendVoltage();
|
||||||
|
|
|
@ -22,12 +22,10 @@ typedef enum {
|
||||||
FRSKY_VFAS_PRECISION_HIGH
|
FRSKY_VFAS_PRECISION_HIGH
|
||||||
} frskyVFasPrecision_e;
|
} frskyVFasPrecision_e;
|
||||||
|
|
||||||
struct rxConfig_s;
|
void handleFrSkyTelemetry(void);
|
||||||
void handleFrSkyTelemetry(const struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
|
||||||
void checkFrSkyTelemetryState(void);
|
void checkFrSkyTelemetryState(void);
|
||||||
|
|
||||||
struct telemetryConfig_s;
|
void initFrSkyTelemetry(void);
|
||||||
void initFrSkyTelemetry(const struct telemetryConfig_s *telemetryConfig);
|
|
||||||
void configureFrSkyTelemetryPort(void);
|
void configureFrSkyTelemetryPort(void);
|
||||||
void freeFrSkyTelemetryPort(void);
|
void freeFrSkyTelemetryPort(void);
|
||||||
|
|
||||||
|
|
|
@ -112,9 +112,6 @@ static uint8_t hottMsgCrc;
|
||||||
static serialPort_t *hottPort = NULL;
|
static serialPort_t *hottPort = NULL;
|
||||||
static serialPortConfig_t *portConfig;
|
static serialPortConfig_t *portConfig;
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
|
||||||
static const telemetryConfig_t *telemetryConfig;
|
|
||||||
#endif
|
|
||||||
static bool hottTelemetryEnabled = false;
|
static bool hottTelemetryEnabled = false;
|
||||||
static portSharing_e hottPortSharing;
|
static portSharing_e hottPortSharing;
|
||||||
|
|
||||||
|
@ -295,13 +292,8 @@ void freeHoTTTelemetryPort(void)
|
||||||
hottTelemetryEnabled = false;
|
hottTelemetryEnabled = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void initHoTTTelemetry(const telemetryConfig_t *initialTelemetryConfig)
|
void initHoTTTelemetry(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
UNUSED(initialTelemetryConfig);
|
|
||||||
#else
|
|
||||||
telemetryConfig = initialTelemetryConfig;
|
|
||||||
#endif
|
|
||||||
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_HOTT);
|
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_HOTT);
|
||||||
hottPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_HOTT);
|
hottPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_HOTT);
|
||||||
|
|
||||||
|
|
|
@ -490,7 +490,7 @@ typedef struct HOTT_AIRESC_MSG_s {
|
||||||
void handleHoTTTelemetry(timeUs_t currentTimeUs);
|
void handleHoTTTelemetry(timeUs_t currentTimeUs);
|
||||||
void checkHoTTTelemetryState(void);
|
void checkHoTTTelemetryState(void);
|
||||||
|
|
||||||
void initHoTTTelemetry(const telemetryConfig_t *telemetryConfig);
|
void initHoTTTelemetry(void);
|
||||||
void configureHoTTTelemetryPort(void);
|
void configureHoTTTelemetryPort(void);
|
||||||
void freeHoTTTelemetryPort(void);
|
void freeHoTTTelemetryPort(void);
|
||||||
|
|
||||||
|
|
|
@ -17,7 +17,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
struct telemetryConfig_s;
|
void initJetiExBusTelemetry(void);
|
||||||
void initJetiExBusTelemetry(struct telemetryConfig_s *initialTelemetryConfig);
|
|
||||||
void checkJetiExBusTelemetryState(void);
|
void checkJetiExBusTelemetryState(void);
|
||||||
void handleJetiExBusTelemetry(void);
|
void handleJetiExBusTelemetry(void);
|
||||||
|
|
|
@ -81,9 +81,6 @@
|
||||||
|
|
||||||
static serialPort_t *ltmPort;
|
static serialPort_t *ltmPort;
|
||||||
static serialPortConfig_t *portConfig;
|
static serialPortConfig_t *portConfig;
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
|
||||||
static const telemetryConfig_t *telemetryConfig;
|
|
||||||
#endif
|
|
||||||
static bool ltmEnabled;
|
static bool ltmEnabled;
|
||||||
static portSharing_e ltmPortSharing;
|
static portSharing_e ltmPortSharing;
|
||||||
static uint8_t ltm_crc;
|
static uint8_t ltm_crc;
|
||||||
|
@ -271,13 +268,8 @@ void freeLtmTelemetryPort(void)
|
||||||
ltmEnabled = false;
|
ltmEnabled = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void initLtmTelemetry(const telemetryConfig_t *initialTelemetryConfig)
|
void initLtmTelemetry(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
UNUSED(initialTelemetryConfig);
|
|
||||||
#else
|
|
||||||
telemetryConfig = initialTelemetryConfig;
|
|
||||||
#endif
|
|
||||||
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_LTM);
|
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_LTM);
|
||||||
ltmPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_LTM);
|
ltmPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_LTM);
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,8 +19,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
struct telemetryConfig_s;
|
void initLtmTelemetry(void);
|
||||||
void initLtmTelemetry(const struct telemetryConfig_s *initialTelemetryConfig);
|
|
||||||
void handleLtmTelemetry(void);
|
void handleLtmTelemetry(void);
|
||||||
void checkLtmTelemetryState(void);
|
void checkLtmTelemetryState(void);
|
||||||
|
|
||||||
|
|
|
@ -150,9 +150,6 @@ const uint16_t frSkyDataIdTable[] = {
|
||||||
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
|
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
|
||||||
static serialPortConfig_t *portConfig;
|
static serialPortConfig_t *portConfig;
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
|
||||||
static const telemetryConfig_t *telemetryConfig;
|
|
||||||
#endif
|
|
||||||
static bool smartPortTelemetryEnabled = false;
|
static bool smartPortTelemetryEnabled = false;
|
||||||
static portSharing_e smartPortPortSharing;
|
static portSharing_e smartPortPortSharing;
|
||||||
|
|
||||||
|
@ -306,13 +303,8 @@ static void smartPortSendPackage(uint16_t id, uint32_t val)
|
||||||
smartPortSendPackageEx(FSSP_DATA_FRAME,payload);
|
smartPortSendPackageEx(FSSP_DATA_FRAME,payload);
|
||||||
}
|
}
|
||||||
|
|
||||||
void initSmartPortTelemetry(const telemetryConfig_t *initialTelemetryConfig)
|
void initSmartPortTelemetry(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
UNUSED(initialTelemetryConfig);
|
|
||||||
#else
|
|
||||||
telemetryConfig = initialTelemetryConfig;
|
|
||||||
#endif
|
|
||||||
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_SMARTPORT);
|
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_SMARTPORT);
|
||||||
smartPortPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_SMARTPORT);
|
smartPortPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_SMARTPORT);
|
||||||
}
|
}
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
void initSmartPortTelemetry(const telemetryConfig_t *);
|
void initSmartPortTelemetry(void);
|
||||||
|
|
||||||
void handleSmartPortTelemetry(void);
|
void handleSmartPortTelemetry(void);
|
||||||
void checkSmartPortTelemetryState(void);
|
void checkSmartPortTelemetryState(void);
|
||||||
|
|
|
@ -53,35 +53,23 @@
|
||||||
#include "telemetry/srxl.h"
|
#include "telemetry/srxl.h"
|
||||||
#include "telemetry/ibus.h"
|
#include "telemetry/ibus.h"
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
|
||||||
static telemetryConfig_t *telemetryConfig;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void telemetryUseConfig(telemetryConfig_t *telemetryConfigToUse)
|
|
||||||
{
|
|
||||||
#ifdef USE_PARAMETER_GROUPS
|
|
||||||
UNUSED(telemetryConfigToUse);
|
|
||||||
#else
|
|
||||||
telemetryConfig = telemetryConfigToUse;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void telemetryInit(void)
|
void telemetryInit(void)
|
||||||
{
|
{
|
||||||
#ifdef TELEMETRY_FRSKY
|
#ifdef TELEMETRY_FRSKY
|
||||||
initFrSkyTelemetry(telemetryConfig());
|
initFrSkyTelemetry();
|
||||||
#endif
|
#endif
|
||||||
#ifdef TELEMETRY_HOTT
|
#ifdef TELEMETRY_HOTT
|
||||||
initHoTTTelemetry(telemetryConfig());
|
initHoTTTelemetry();
|
||||||
#endif
|
#endif
|
||||||
#ifdef TELEMETRY_SMARTPORT
|
#ifdef TELEMETRY_SMARTPORT
|
||||||
initSmartPortTelemetry(telemetryConfig());
|
initSmartPortTelemetry();
|
||||||
#endif
|
#endif
|
||||||
#ifdef TELEMETRY_LTM
|
#ifdef TELEMETRY_LTM
|
||||||
initLtmTelemetry(telemetryConfig());
|
initLtmTelemetry();
|
||||||
#endif
|
#endif
|
||||||
#ifdef TELEMETRY_JETIEXBUS
|
#ifdef TELEMETRY_JETIEXBUS
|
||||||
initJetiExBusTelemetry(telemetryConfig());
|
initJetiExBusTelemetry();
|
||||||
#endif
|
#endif
|
||||||
#ifdef TELEMETRY_MAVLINK
|
#ifdef TELEMETRY_MAVLINK
|
||||||
initMAVLinkTelemetry();
|
initMAVLinkTelemetry();
|
||||||
|
@ -151,13 +139,10 @@ void telemetryCheckState(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void telemetryProcess(uint32_t currentTime, const rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
void telemetryProcess(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
#ifdef TELEMETRY_FRSKY
|
#ifdef TELEMETRY_FRSKY
|
||||||
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
handleFrSkyTelemetry();
|
||||||
#else
|
|
||||||
UNUSED(rxConfig);
|
|
||||||
UNUSED(deadband3d_throttle);
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef TELEMETRY_HOTT
|
#ifdef TELEMETRY_HOTT
|
||||||
handleHoTTTelemetry(currentTime);
|
handleHoTTTelemetry(currentTime);
|
||||||
|
|
|
@ -38,11 +38,11 @@ typedef enum {
|
||||||
} frskyUnit_e;
|
} frskyUnit_e;
|
||||||
|
|
||||||
typedef struct telemetryConfig_s {
|
typedef struct telemetryConfig_s {
|
||||||
|
float gpsNoFixLatitude;
|
||||||
|
float gpsNoFixLongitude;
|
||||||
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
|
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
|
||||||
uint8_t telemetry_inversion; // also shared with smartport inversion
|
uint8_t telemetry_inversion; // also shared with smartport inversion
|
||||||
uint8_t sportHalfDuplex;
|
uint8_t sportHalfDuplex;
|
||||||
float gpsNoFixLatitude;
|
|
||||||
float gpsNoFixLongitude;
|
|
||||||
frskyGpsCoordFormat_e frsky_coordinate_format;
|
frskyGpsCoordFormat_e frsky_coordinate_format;
|
||||||
frskyUnit_e frsky_unit;
|
frskyUnit_e frsky_unit;
|
||||||
uint8_t frsky_vfas_precision;
|
uint8_t frsky_vfas_precision;
|
||||||
|
@ -54,18 +54,16 @@ typedef struct telemetryConfig_s {
|
||||||
|
|
||||||
PG_DECLARE(telemetryConfig_t, telemetryConfig);
|
PG_DECLARE(telemetryConfig_t, telemetryConfig);
|
||||||
|
|
||||||
void telemetryInit(void);
|
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
|
||||||
bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
|
|
||||||
extern serialPort_t *telemetrySharedPort;
|
extern serialPort_t *telemetrySharedPort;
|
||||||
|
|
||||||
|
void telemetryInit(void);
|
||||||
|
bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
|
||||||
|
|
||||||
void telemetryCheckState(void);
|
void telemetryCheckState(void);
|
||||||
struct rxConfig_s;
|
void telemetryProcess(uint32_t currentTime);
|
||||||
void telemetryProcess(uint32_t currentTime, const struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
|
||||||
|
|
||||||
bool telemetryDetermineEnabledState(portSharing_e portSharing);
|
bool telemetryDetermineEnabledState(portSharing_e portSharing);
|
||||||
|
|
||||||
void telemetryUseConfig(telemetryConfig_t *telemetryConfig);
|
|
||||||
|
|
||||||
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
|
|
||||||
|
|
||||||
void releaseSharedTelemetryPorts(void);
|
void releaseSharedTelemetryPorts(void);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue