Merge pull request #2288 from martinbudden/bf_pg_preparation3
Preparation for conversion to parameter groups 3
This commit is contained in:
commit
80700c2158
|
@ -140,6 +140,7 @@ extern const uint8_t __pg_resetdata_end[];
|
|||
|
||||
#endif // USE_PARAMETER_GROUPS
|
||||
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
// Register system config
|
||||
#define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \
|
||||
_type _name ## _System; \
|
||||
|
@ -242,6 +243,29 @@ extern const uint8_t __pg_resetdata_end[];
|
|||
__VA_ARGS__ \
|
||||
} \
|
||||
/**/
|
||||
#else
|
||||
#define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \
|
||||
_type _name ## _System
|
||||
|
||||
#define PG_REGISTER(_type, _name, _pgn, _version) \
|
||||
PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.ptr = 0}) \
|
||||
/**/
|
||||
|
||||
#define PG_REGISTER_WITH_RESET_FN(_type, _name, _pgn, _version) \
|
||||
extern void pgResetFn_ ## _name(_type *); \
|
||||
PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.fn = (pgResetFunc*)&pgResetFn_ ## _name }) \
|
||||
/**/
|
||||
|
||||
#define PG_REGISTER_WITH_RESET_TEMPLATE(_type, _name, _pgn, _version) \
|
||||
extern const _type pgResetTemplate_ ## _name; \
|
||||
PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.ptr = (void*)&pgResetTemplate_ ## _name}) \
|
||||
/**/
|
||||
#define PG_RESET_TEMPLATE(_type, _name, ...) \
|
||||
const _type pgResetTemplate_ ## _name PG_RESETDATA_ATTRIBUTES = { \
|
||||
__VA_ARGS__ \
|
||||
} \
|
||||
/**/
|
||||
#endif
|
||||
|
||||
const pgRegistry_t* pgFind(pgn_t pgn);
|
||||
|
||||
|
|
|
@ -896,26 +896,16 @@ void activateConfig(void)
|
|||
¤tProfile->pidProfile
|
||||
);
|
||||
|
||||
#ifdef TELEMETRY
|
||||
telemetryUseConfig(&masterConfig.telemetryConfig);
|
||||
#endif
|
||||
|
||||
#ifdef GPS
|
||||
gpsUseProfile(&masterConfig.gpsProfile);
|
||||
gpsUsePIDs(¤tProfile->pidProfile);
|
||||
#endif
|
||||
|
||||
useFailsafeConfig(&masterConfig.failsafeConfig);
|
||||
failsafeReset();
|
||||
setAccelerationTrims(&accelerometerConfigMutable()->accZero);
|
||||
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
|
||||
|
||||
mixerUseConfigs(
|
||||
&masterConfig.flight3DConfig,
|
||||
&masterConfig.motorConfig,
|
||||
&masterConfig.mixerConfig,
|
||||
&masterConfig.airplaneConfig,
|
||||
&masterConfig.rxConfig
|
||||
);
|
||||
mixerUseConfigs(&masterConfig.airplaneConfig);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.gimbalConfig);
|
||||
|
@ -934,10 +924,6 @@ void activateConfig(void)
|
|||
&masterConfig.rcControlsConfig,
|
||||
&masterConfig.motorConfig
|
||||
);
|
||||
|
||||
#ifdef BARO
|
||||
useBarometerConfig(&masterConfig.barometerConfig);
|
||||
#endif
|
||||
}
|
||||
|
||||
void validateAndFixConfig(void)
|
||||
|
|
|
@ -259,16 +259,16 @@ void init(void)
|
|||
timerInit(); // timer must be initialized before any channel is allocated
|
||||
|
||||
#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);
|
||||
#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);
|
||||
#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);
|
||||
#else
|
||||
serialInit(serialConfig(), feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
||||
serialInit(feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
||||
#endif
|
||||
|
||||
mixerInit(mixerConfig()->mixerMode, masterConfig.customMotorMixer);
|
||||
|
@ -403,12 +403,7 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
const sonarConfig_t *sonarConfig = sonarConfig();
|
||||
#else
|
||||
const void *sonarConfig = NULL;
|
||||
#endif
|
||||
if (!sensorsAutodetect(gyroConfig(), accelerometerConfig(), compassConfig(), barometerConfig(), sonarConfig)) {
|
||||
if (!sensorsAutodetect()) {
|
||||
// if gyro was not detected due to whatever reason, we give up now.
|
||||
failureMode(FAILURE_MISSING_ACC);
|
||||
}
|
||||
|
@ -448,7 +443,7 @@ void init(void)
|
|||
cliInit(serialConfig());
|
||||
#endif
|
||||
|
||||
failsafeInit(rxConfig(), flight3DConfig()->deadband3d_throttle);
|
||||
failsafeInit(flight3DConfig()->deadband3d_throttle);
|
||||
|
||||
rxInit(rxConfig(), modeActivationProfile()->modeActivationConditions);
|
||||
|
||||
|
@ -556,7 +551,7 @@ void init(void)
|
|||
// Now that everything has powered up the voltage and cell count be determined.
|
||||
|
||||
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
|
||||
batteryInit(batteryConfig());
|
||||
batteryInit();
|
||||
|
||||
#ifdef USE_DASHBOARD
|
||||
if (feature(FEATURE_DASHBOARD)) {
|
||||
|
|
|
@ -204,7 +204,7 @@ static void taskTelemetry(timeUs_t currentTimeUs)
|
|||
telemetryCheckState();
|
||||
|
||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||
telemetryProcess(currentTimeUs, rxConfig(), flight3DConfig()->deadband3d_throttle);
|
||||
telemetryProcess(currentTimeUs);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -43,9 +43,9 @@
|
|||
/*
|
||||
* 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.
|
||||
*
|
||||
* enable() should be called after system initialisation.
|
||||
|
@ -53,16 +53,14 @@
|
|||
|
||||
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 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.validRxDataFailedAt = 0;
|
||||
failsafeState.throttleLowPeriod = 0;
|
||||
|
@ -73,27 +71,8 @@ static void failsafeReset(void)
|
|||
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
|
||||
}
|
||||
|
||||
/*
|
||||
* Should called when the failsafe config needs to be changed - e.g. a different profile has been selected.
|
||||
*/
|
||||
void useFailsafeConfig(const failsafeConfig_t *failsafeConfigToUse)
|
||||
void failsafeInit(uint16_t deadband3d_throttle)
|
||||
{
|
||||
#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;
|
||||
failsafeState.events = 0;
|
||||
failsafeState.monitoring = false;
|
||||
|
@ -131,7 +110,7 @@ static void failsafeActivate(void)
|
|||
failsafeState.active = true;
|
||||
failsafeState.phase = FAILSAFE_LANDING;
|
||||
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++;
|
||||
}
|
||||
|
@ -139,9 +118,9 @@ static void failsafeActivate(void)
|
|||
static void failsafeApplyControlInput(void)
|
||||
{
|
||||
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)
|
||||
|
@ -201,11 +180,11 @@ void failsafeUpdateState(void)
|
|||
case FAILSAFE_IDLE:
|
||||
if (armed) {
|
||||
// Track throttle command below minimum time
|
||||
if (THROTTLE_HIGH == calculateThrottleStatus(rxConfig, deadband3dThrottle)) {
|
||||
failsafeState.throttleLowPeriod = millis() + failsafeConfig->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
|
||||
if (THROTTLE_HIGH == calculateThrottleStatus(rxConfig(), deadband3dThrottle)) {
|
||||
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)
|
||||
if (failsafeSwitchIsOn && failsafeConfig->failsafe_kill_switch) {
|
||||
if (failsafeSwitchIsOn && failsafeConfig()->failsafe_kill_switch) {
|
||||
// KillswitchEvent: failsafe switch is configured as KILL switch and is switched ON
|
||||
failsafeActivate();
|
||||
failsafeState.phase = FAILSAFE_LANDED; // skip auto-landing procedure
|
||||
|
@ -238,7 +217,7 @@ void failsafeUpdateState(void)
|
|||
if (receivingRxData) {
|
||||
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
|
||||
} else {
|
||||
switch (failsafeConfig->failsafe_procedure) {
|
||||
switch (failsafeConfig()->failsafe_procedure) {
|
||||
default:
|
||||
case FAILSAFE_PROCEDURE_AUTO_LANDING:
|
||||
// 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.
|
||||
// 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.
|
||||
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.active = false;
|
||||
DISABLE_FLIGHT_MODE(FAILSAFE_MODE);
|
||||
|
|
|
@ -74,9 +74,8 @@ typedef struct failsafeState_s {
|
|||
failsafeRxLinkState_e rxLinkState;
|
||||
} failsafeState_t;
|
||||
|
||||
struct rxConfig_s;
|
||||
void failsafeInit(const struct rxConfig_s *intialRxConfig, uint16_t deadband3d_throttle);
|
||||
void useFailsafeConfig(const failsafeConfig_t *failsafeConfigToUse);
|
||||
void failsafeInit(uint16_t deadband3d_throttle);
|
||||
void failsafeReset(void);
|
||||
|
||||
void failsafeStartMonitoring(void);
|
||||
void failsafeUpdateState(void);
|
||||
|
|
|
@ -63,12 +63,6 @@ int16_t motor[MAX_SUPPORTED_MOTORS];
|
|||
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
static airplaneConfig_t *airplaneConfig;
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const mixerConfig_t *mixerConfig;
|
||||
static const flight3DConfig_t *flight3DConfig;
|
||||
static const motorConfig_t *motorConfig;
|
||||
const rxConfig_t *rxConfig;
|
||||
#endif
|
||||
|
||||
mixerMode_e currentMixerMode;
|
||||
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
|
||||
|
@ -297,24 +291,8 @@ void initEscEndpoints(void) {
|
|||
rcCommandThrottleRange3dHigh = PWM_RANGE_MAX - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
||||
}
|
||||
|
||||
void mixerUseConfigs(
|
||||
flight3DConfig_t *flight3DConfigToUse,
|
||||
motorConfig_t *motorConfigToUse,
|
||||
mixerConfig_t *mixerConfigToUse,
|
||||
airplaneConfig_t *airplaneConfigToUse,
|
||||
rxConfig_t *rxConfigToUse)
|
||||
void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse)
|
||||
{
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
(void)(flight3DConfigToUse);
|
||||
(void)(motorConfigToUse);
|
||||
(void)(mixerConfigToUse);
|
||||
(void)(rxConfigToUse);
|
||||
#else
|
||||
flight3DConfig = flight3DConfigToUse;
|
||||
motorConfig = motorConfigToUse;
|
||||
mixerConfig = mixerConfigToUse;
|
||||
rxConfig = rxConfigToUse;
|
||||
#endif
|
||||
airplaneConfig = airplaneConfigToUse;
|
||||
}
|
||||
|
||||
|
@ -494,7 +472,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
}
|
||||
|
||||
// Calculate voltage compensation
|
||||
const float vbatCompensationFactor = (batteryConfig && pidProfile->vbatPidCompensation) ? calculateVbatPidCompensation() : 1.0f;
|
||||
const float vbatCompensationFactor = pidProfile->vbatPidCompensation ? calculateVbatPidCompensation() : 1.0f;
|
||||
|
||||
// Find roll/pitch/yaw desired output
|
||||
float motorMix[MAX_SUPPORTED_MOTORS];
|
||||
|
|
|
@ -141,12 +141,7 @@ struct rxConfig_s;
|
|||
uint8_t getMotorCount();
|
||||
float getMotorMixRange();
|
||||
|
||||
void mixerUseConfigs(
|
||||
flight3DConfig_t *flight3DConfigToUse,
|
||||
motorConfig_t *motorConfigToUse,
|
||||
mixerConfig_t *mixerConfigToUse,
|
||||
airplaneConfig_t *airplaneConfigToUse,
|
||||
struct rxConfig_s *rxConfigToUse);
|
||||
void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse);
|
||||
|
||||
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers);
|
||||
|
|
|
@ -54,7 +54,6 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#endif
|
||||
|
||||
static const serialConfig_t *serialConfig;
|
||||
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
|
||||
|
||||
const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
||||
|
@ -396,16 +395,12 @@ void closeSerialPort(serialPort_t *serialPort)
|
|||
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;
|
||||
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];
|
||||
|
||||
if (serialPortToDisable != SERIAL_PORT_NONE) {
|
||||
|
@ -471,7 +466,7 @@ void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar)
|
|||
cliEnter(serialPort);
|
||||
}
|
||||
#endif
|
||||
if (receivedChar == serialConfig->reboot_character) {
|
||||
if (receivedChar == serialConfig()->reboot_character) {
|
||||
systemResetToBootloader();
|
||||
}
|
||||
}
|
||||
|
@ -488,8 +483,7 @@ static void nopConsumer(uint8_t data)
|
|||
arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
|
||||
for specialized data processing.
|
||||
*/
|
||||
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
|
||||
*leftC, serialConsumer *rightC)
|
||||
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
|
||||
{
|
||||
waitForSerialPortToFinishTransmitting(left);
|
||||
waitForSerialPortToFinishTransmitting(right);
|
||||
|
|
|
@ -122,7 +122,7 @@ typedef void serialConsumer(uint8_t);
|
|||
//
|
||||
// configuration
|
||||
//
|
||||
void serialInit(const serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||
uint8_t serialGetAvailablePortCount(void);
|
||||
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
|
||||
jetiExBusTelemetryFrame[EXBUS_HEADER_SYNC] = 0x3B; // Startbytes
|
||||
jetiExBusTelemetryFrame[EXBUS_HEADER_REQ] = 0x01;
|
||||
|
@ -427,7 +425,6 @@ void initJetiExBusTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
|||
jetiExTelemetryFrame[EXTEL_HEADER_RES] = 0x00; // reserved, by default 0x00
|
||||
}
|
||||
|
||||
|
||||
void createExTelemetrieTextMessage(uint8_t *exMessage, uint8_t messageID, const exBusSensor_t *sensor)
|
||||
{
|
||||
uint8_t labelLength = strlen(sensor->label);
|
||||
|
|
|
@ -246,13 +246,13 @@ retry:
|
|||
return true;
|
||||
}
|
||||
|
||||
bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroSamplingInverval)
|
||||
bool accInit(uint32_t gyroSamplingInverval)
|
||||
{
|
||||
memset(&acc, 0, sizeof(acc));
|
||||
// copy over the common gyro mpu settings
|
||||
acc.dev.mpuConfiguration = gyro.dev.mpuConfiguration;
|
||||
acc.dev.mpuDetectionResult = gyro.dev.mpuDetectionResult;
|
||||
if (!accDetect(&acc.dev, accelerometerConfig->acc_hardware)) {
|
||||
if (!accDetect(&acc.dev, accelerometerConfig()->acc_hardware)) {
|
||||
return false;
|
||||
}
|
||||
acc.dev.acc_1G = 256; // set default
|
||||
|
|
|
@ -69,7 +69,7 @@ typedef struct accelerometerConfig_s {
|
|||
|
||||
PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
|
||||
|
||||
bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroTargetLooptime);
|
||||
bool accInit(uint32_t gyroTargetLooptime);
|
||||
bool isAccelerationCalibrationComplete(void);
|
||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
|
||||
|
|
|
@ -54,10 +54,6 @@ static int32_t baroGroundAltitude = 0;
|
|||
static int32_t baroGroundPressure = 0;
|
||||
static uint32_t baroPressureSum = 0;
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const barometerConfig_t *barometerConfig;
|
||||
#endif
|
||||
|
||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||
{
|
||||
// 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;
|
||||
}
|
||||
|
||||
void useBarometerConfig(const barometerConfig_t *barometerConfigToUse)
|
||||
{
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
(void)(barometerConfigToUse);
|
||||
#else
|
||||
barometerConfig = barometerConfigToUse;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool isBaroCalibrationComplete(void)
|
||||
{
|
||||
return calibratingB == 0;
|
||||
|
|
|
@ -49,7 +49,6 @@ typedef struct baro_s {
|
|||
extern baro_t baro;
|
||||
|
||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse);
|
||||
void useBarometerConfig(const barometerConfig_t *barometerConfigToUse);
|
||||
bool isBaroCalibrationComplete(void);
|
||||
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||
uint32_t baroUpdate(void);
|
||||
|
|
|
@ -68,10 +68,6 @@ int32_t amperageLatest = 0; // most recent value
|
|||
|
||||
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
const batteryConfig_t *batteryConfig;
|
||||
#endif
|
||||
|
||||
static batteryState_e vBatState;
|
||||
static batteryState_e consumptionState;
|
||||
|
||||
|
@ -213,13 +209,8 @@ const char * getBatteryStateString(void)
|
|||
return batteryStateStrings[getBatteryState()];
|
||||
}
|
||||
|
||||
void batteryInit(const batteryConfig_t *initialBatteryConfig)
|
||||
void batteryInit(void)
|
||||
{
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
(void)initialBatteryConfig;
|
||||
#else
|
||||
batteryConfig = initialBatteryConfig;
|
||||
#endif
|
||||
vBatState = BATTERY_NOT_PRESENT;
|
||||
consumptionState = BATTERY_OK;
|
||||
batteryCellCount = 0;
|
||||
|
|
|
@ -87,7 +87,7 @@ extern const batteryConfig_t *batteryConfig;
|
|||
batteryState_e getBatteryState(void);
|
||||
const char * getBatteryStateString(void);
|
||||
void updateBattery(void);
|
||||
void batteryInit(const batteryConfig_t *initialBatteryConfig);
|
||||
void batteryInit(void);
|
||||
|
||||
struct rxConfig_s;
|
||||
void updateCurrentMeter(int32_t lastUpdateAt, const struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||
|
|
|
@ -146,12 +146,12 @@ retry:
|
|||
return true;
|
||||
}
|
||||
|
||||
void compassInit(const compassConfig_t *compassConfig)
|
||||
void compassInit(void)
|
||||
{
|
||||
// initialize and calibration. turn on led during mag calibration (calibration routine blinks it)
|
||||
// calculate magnetic declination
|
||||
const int16_t deg = compassConfig->mag_declination / 100;
|
||||
const int16_t min = compassConfig->mag_declination % 100;
|
||||
const int16_t deg = 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
|
||||
LED1_ON;
|
||||
mag.dev.init();
|
||||
|
|
|
@ -50,7 +50,7 @@ typedef struct compassConfig_s {
|
|||
PG_DECLARE(compassConfig_t, compassConfig);
|
||||
|
||||
bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse);
|
||||
void compassInit(const compassConfig_t *compassConfig);
|
||||
void compassInit(void);
|
||||
union flightDynamicsTrims_u;
|
||||
void compassUpdate(uint32_t currentTime, union flightDynamicsTrims_u *magZero);
|
||||
|
||||
|
|
|
@ -72,9 +72,6 @@ gyro_t gyro; // gyro access functions
|
|||
static int32_t gyroADC[XYZ_AXIS_COUNT];
|
||||
|
||||
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const gyroConfig_t *gyroConfig;
|
||||
#endif
|
||||
static uint16_t calibratingG = 0;
|
||||
|
||||
static filterApplyFnPtr softLpfFilterApplyFn;
|
||||
|
@ -86,6 +83,29 @@ static void *notchFilter2[3];
|
|||
|
||||
#define DEBUG_GYRO_CALIBRATION 3
|
||||
|
||||
#ifdef STM32F10X
|
||||
#define GYRO_SYNC_DENOM_DEFAULT 8
|
||||
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
|
||||
#define GYRO_SYNC_DENOM_DEFAULT 1
|
||||
#else
|
||||
#define GYRO_SYNC_DENOM_DEFAULT 4
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
|
||||
.gyro_lpf = GYRO_LPF_256HZ,
|
||||
.gyro_sync_denom = GYRO_SYNC_DENOM_DEFAULT,
|
||||
.gyro_soft_lpf_type = FILTER_PT1,
|
||||
.gyro_soft_lpf_hz = 90,
|
||||
.gyro_soft_notch_hz_1 = 400,
|
||||
.gyro_soft_notch_cutoff_1 = 300,
|
||||
.gyro_soft_notch_hz_2 = 200,
|
||||
.gyro_soft_notch_cutoff_2 = 100,
|
||||
.gyro_align = ALIGN_DEFAULT,
|
||||
.gyroMovementCalibrationThreshold = 32
|
||||
);
|
||||
|
||||
static const extiConfig_t *selectMPUIntExtiConfig(void)
|
||||
{
|
||||
#if defined(MPU_INT_EXTI)
|
||||
|
@ -236,13 +256,8 @@ static bool gyroDetect(gyroDev_t *dev)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool gyroInit(const gyroConfig_t *gyroConfigToUse)
|
||||
bool gyroInit(void)
|
||||
{
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
(void)(gyroConfigToUse);
|
||||
#else
|
||||
gyroConfig = gyroConfigToUse;
|
||||
#endif
|
||||
memset(&gyro, 0, sizeof(gyro));
|
||||
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689)
|
||||
gyro.dev.mpuIntExtiConfig = selectMPUIntExtiConfig();
|
||||
|
@ -257,8 +272,7 @@ bool gyroInit(const gyroConfig_t *gyroConfigToUse)
|
|||
switch (detectedSensors[SENSOR_INDEX_GYRO]) {
|
||||
default:
|
||||
// gyro does not support 32kHz
|
||||
// cast away constness, legitimate as this is cross-validation
|
||||
((gyroConfig_t*)gyroConfig)->gyro_use_32khz = false;
|
||||
gyroConfigMutable()->gyro_use_32khz = false;
|
||||
break;
|
||||
case GYRO_MPU6500:
|
||||
case GYRO_MPU9250:
|
||||
|
|
|
@ -63,7 +63,7 @@ typedef struct gyroConfig_s {
|
|||
PG_DECLARE(gyroConfig_t, gyroConfig);
|
||||
|
||||
void gyroSetCalibrationCycles(void);
|
||||
bool gyroInit(const gyroConfig_t *gyroConfigToUse);
|
||||
bool gyroInit(void);
|
||||
void gyroInitFilters(void);
|
||||
void gyroUpdate(void);
|
||||
bool isGyroCalibrationComplete(void);
|
||||
|
|
|
@ -24,6 +24,8 @@
|
|||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -52,50 +54,40 @@ static bool sonarDetect(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
|
||||
const accelerometerConfig_t *accelerometerConfig,
|
||||
const compassConfig_t *compassConfig,
|
||||
const barometerConfig_t *barometerConfig,
|
||||
const sonarConfig_t *sonarConfig)
|
||||
bool sensorsAutodetect(void)
|
||||
{
|
||||
// gyro must be initialised before accelerometer
|
||||
if (!gyroInit(gyroConfig)) {
|
||||
if (!gyroInit()) {
|
||||
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.
|
||||
#ifdef MAG
|
||||
if (compassDetect(&mag.dev, compassConfig->mag_hardware)) {
|
||||
compassInit(compassConfig);
|
||||
if (compassDetect(&mag.dev, compassConfig()->mag_hardware)) {
|
||||
compassInit();
|
||||
}
|
||||
#else
|
||||
UNUSED(compassConfig);
|
||||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
baroDetect(&baro.dev, barometerConfig->baro_hardware);
|
||||
#else
|
||||
UNUSED(barometerConfig);
|
||||
baroDetect(&baro.dev, barometerConfig()->baro_hardware);
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
if (sonarDetect()) {
|
||||
sonarInit(sonarConfig);
|
||||
sonarInit(sonarConfig());
|
||||
}
|
||||
#else
|
||||
UNUSED(sonarConfig);
|
||||
#endif
|
||||
|
||||
if (gyroConfig->gyro_align != ALIGN_DEFAULT) {
|
||||
gyro.dev.gyroAlign = gyroConfig->gyro_align;
|
||||
if (gyroConfig()->gyro_align != ALIGN_DEFAULT) {
|
||||
gyro.dev.gyroAlign = gyroConfig()->gyro_align;
|
||||
}
|
||||
if (accelerometerConfig->acc_align != ALIGN_DEFAULT) {
|
||||
acc.dev.accAlign = accelerometerConfig->acc_align;
|
||||
if (accelerometerConfig()->acc_align != ALIGN_DEFAULT) {
|
||||
acc.dev.accAlign = accelerometerConfig()->acc_align;
|
||||
}
|
||||
if (compassConfig->mag_align != ALIGN_DEFAULT) {
|
||||
mag.dev.magAlign = compassConfig->mag_align;
|
||||
if (compassConfig()->mag_align != ALIGN_DEFAULT) {
|
||||
mag.dev.magAlign = compassConfig()->mag_align;
|
||||
}
|
||||
|
||||
return true;
|
||||
|
|
|
@ -17,8 +17,4 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
|
||||
const accelerometerConfig_t *accConfig,
|
||||
const compassConfig_t *compassConfig,
|
||||
const barometerConfig_t *baroConfig,
|
||||
const sonarConfig_t *sonarConfig);
|
||||
bool sensorsAutodetect(void);
|
||||
|
|
|
@ -74,9 +74,6 @@ static serialPortConfig_t *portConfig;
|
|||
#define FRSKY_BAUDRATE 9600
|
||||
#define FRSKY_INITIAL_PORT_MODE MODE_TX
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const telemetryConfig_t *telemetryConfig;
|
||||
#endif
|
||||
static bool frskyTelemetryEnabled = false;
|
||||
static portSharing_e frskyPortSharing;
|
||||
|
||||
|
@ -457,13 +454,8 @@ static void sendHeading(void)
|
|||
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);
|
||||
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) {
|
||||
return;
|
||||
|
@ -546,7 +538,7 @@ void handleFrSkyTelemetry(const rxConfig_t *rxConfig, uint16_t deadband3d_thrott
|
|||
|
||||
if ((cycleNum % 8) == 0) { // Sent every 1s
|
||||
sendTemperature1();
|
||||
sendThrottleOrBatterySizeAsRpm(rxConfig, deadband3d_throttle);
|
||||
sendThrottleOrBatterySizeAsRpm(rxConfig(), flight3DConfig()->deadband3d_throttle);
|
||||
|
||||
if ((feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) && batteryCellCount > 0) {
|
||||
sendVoltage();
|
||||
|
|
|
@ -22,12 +22,10 @@ typedef enum {
|
|||
FRSKY_VFAS_PRECISION_HIGH
|
||||
} frskyVFasPrecision_e;
|
||||
|
||||
struct rxConfig_s;
|
||||
void handleFrSkyTelemetry(const struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||
void handleFrSkyTelemetry(void);
|
||||
void checkFrSkyTelemetryState(void);
|
||||
|
||||
struct telemetryConfig_s;
|
||||
void initFrSkyTelemetry(const struct telemetryConfig_s *telemetryConfig);
|
||||
void initFrSkyTelemetry(void);
|
||||
void configureFrSkyTelemetryPort(void);
|
||||
void freeFrSkyTelemetryPort(void);
|
||||
|
||||
|
|
|
@ -112,9 +112,6 @@ static uint8_t hottMsgCrc;
|
|||
static serialPort_t *hottPort = NULL;
|
||||
static serialPortConfig_t *portConfig;
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const telemetryConfig_t *telemetryConfig;
|
||||
#endif
|
||||
static bool hottTelemetryEnabled = false;
|
||||
static portSharing_e hottPortSharing;
|
||||
|
||||
|
@ -295,13 +292,8 @@ void freeHoTTTelemetryPort(void)
|
|||
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);
|
||||
hottPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_HOTT);
|
||||
|
||||
|
|
|
@ -490,7 +490,7 @@ typedef struct HOTT_AIRESC_MSG_s {
|
|||
void handleHoTTTelemetry(timeUs_t currentTimeUs);
|
||||
void checkHoTTTelemetryState(void);
|
||||
|
||||
void initHoTTTelemetry(const telemetryConfig_t *telemetryConfig);
|
||||
void initHoTTTelemetry(void);
|
||||
void configureHoTTTelemetryPort(void);
|
||||
void freeHoTTTelemetryPort(void);
|
||||
|
||||
|
|
|
@ -17,7 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
struct telemetryConfig_s;
|
||||
void initJetiExBusTelemetry(struct telemetryConfig_s *initialTelemetryConfig);
|
||||
void initJetiExBusTelemetry(void);
|
||||
void checkJetiExBusTelemetryState(void);
|
||||
void handleJetiExBusTelemetry(void);
|
||||
|
|
|
@ -81,9 +81,6 @@
|
|||
|
||||
static serialPort_t *ltmPort;
|
||||
static serialPortConfig_t *portConfig;
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const telemetryConfig_t *telemetryConfig;
|
||||
#endif
|
||||
static bool ltmEnabled;
|
||||
static portSharing_e ltmPortSharing;
|
||||
static uint8_t ltm_crc;
|
||||
|
@ -271,13 +268,8 @@ void freeLtmTelemetryPort(void)
|
|||
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);
|
||||
ltmPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_LTM);
|
||||
}
|
||||
|
|
|
@ -19,8 +19,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
struct telemetryConfig_s;
|
||||
void initLtmTelemetry(const struct telemetryConfig_s *initialTelemetryConfig);
|
||||
void initLtmTelemetry(void);
|
||||
void handleLtmTelemetry(void);
|
||||
void checkLtmTelemetryState(void);
|
||||
|
||||
|
|
|
@ -150,9 +150,6 @@ const uint16_t frSkyDataIdTable[] = {
|
|||
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
|
||||
static serialPortConfig_t *portConfig;
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const telemetryConfig_t *telemetryConfig;
|
||||
#endif
|
||||
static bool smartPortTelemetryEnabled = false;
|
||||
static portSharing_e smartPortPortSharing;
|
||||
|
||||
|
@ -306,13 +303,8 @@ static void smartPortSendPackage(uint16_t id, uint32_t val)
|
|||
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);
|
||||
smartPortPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_SMARTPORT);
|
||||
}
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void initSmartPortTelemetry(const telemetryConfig_t *);
|
||||
void initSmartPortTelemetry(void);
|
||||
|
||||
void handleSmartPortTelemetry(void);
|
||||
void checkSmartPortTelemetryState(void);
|
||||
|
|
|
@ -53,35 +53,23 @@
|
|||
#include "telemetry/srxl.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)
|
||||
{
|
||||
#ifdef TELEMETRY_FRSKY
|
||||
initFrSkyTelemetry(telemetryConfig());
|
||||
initFrSkyTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_HOTT
|
||||
initHoTTTelemetry(telemetryConfig());
|
||||
initHoTTTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_SMARTPORT
|
||||
initSmartPortTelemetry(telemetryConfig());
|
||||
initSmartPortTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_LTM
|
||||
initLtmTelemetry(telemetryConfig());
|
||||
initLtmTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_JETIEXBUS
|
||||
initJetiExBusTelemetry(telemetryConfig());
|
||||
initJetiExBusTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_MAVLINK
|
||||
initMAVLinkTelemetry();
|
||||
|
@ -151,13 +139,10 @@ void telemetryCheckState(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
void telemetryProcess(uint32_t currentTime, const rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
void telemetryProcess(uint32_t currentTime)
|
||||
{
|
||||
#ifdef TELEMETRY_FRSKY
|
||||
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
||||
#else
|
||||
UNUSED(rxConfig);
|
||||
UNUSED(deadband3d_throttle);
|
||||
handleFrSkyTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_HOTT
|
||||
handleHoTTTelemetry(currentTime);
|
||||
|
|
|
@ -38,11 +38,11 @@ typedef enum {
|
|||
} frskyUnit_e;
|
||||
|
||||
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_inversion; // also shared with smartport inversion
|
||||
uint8_t sportHalfDuplex;
|
||||
float gpsNoFixLatitude;
|
||||
float gpsNoFixLongitude;
|
||||
frskyGpsCoordFormat_e frsky_coordinate_format;
|
||||
frskyUnit_e frsky_unit;
|
||||
uint8_t frsky_vfas_precision;
|
||||
|
@ -54,18 +54,16 @@ typedef struct telemetryConfig_s {
|
|||
|
||||
PG_DECLARE(telemetryConfig_t, telemetryConfig);
|
||||
|
||||
void telemetryInit(void);
|
||||
bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
|
||||
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
|
||||
|
||||
extern serialPort_t *telemetrySharedPort;
|
||||
|
||||
void telemetryInit(void);
|
||||
bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
|
||||
|
||||
void telemetryCheckState(void);
|
||||
struct rxConfig_s;
|
||||
void telemetryProcess(uint32_t currentTime, const struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||
void telemetryProcess(uint32_t currentTime);
|
||||
|
||||
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);
|
||||
|
|
Loading…
Reference in New Issue