Preparation for conversion to parameter groups
This commit is contained in:
parent
9828b7c444
commit
e41d6a3b5b
|
@ -914,7 +914,7 @@ void activateConfig(void)
|
|||
#endif
|
||||
|
||||
useFailsafeConfig(&masterConfig.failsafeConfig);
|
||||
setAccelerationTrims(&accelerometerConfig()->accZero);
|
||||
setAccelerationTrims(&accelerometerConfigMutable()->accZero);
|
||||
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
|
||||
|
||||
mixerUseConfigs(
|
||||
|
@ -1083,13 +1083,13 @@ void validateAndFixGyroConfig(void)
|
|||
samplingTime = 0.00003125;
|
||||
// F1 and F3 can't handle high sample speed.
|
||||
#if defined(STM32F1)
|
||||
gyroConfig()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
|
||||
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
|
||||
#elif defined(STM32F3)
|
||||
gyroConfig()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
#endif
|
||||
} else {
|
||||
#if defined(STM32F1)
|
||||
gyroConfig()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -1511,9 +1511,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
#else
|
||||
motorConfigMutable()->motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_BRUSHED);
|
||||
#endif
|
||||
motorConfig()->motorPwmRate = sbufReadU16(src);
|
||||
motorConfigMutable()->motorPwmRate = sbufReadU16(src);
|
||||
if (sbufBytesRemaining(src) >= 2) {
|
||||
motorConfig()->digitalIdleOffsetPercent = sbufReadU16(src) / 100.0f;
|
||||
motorConfigMutable()->digitalIdleOffsetPercent = sbufReadU16(src) / 100.0f;
|
||||
}
|
||||
if (sbufBytesRemaining(src)) {
|
||||
gyroConfigMutable()->gyro_use_32khz = sbufReadU8(src);
|
||||
|
@ -1525,7 +1525,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
validateAndFixGyroConfig();
|
||||
|
||||
if (sbufBytesRemaining(src)) {
|
||||
motorConfig()->motorPwmInversion = sbufReadU8(src);
|
||||
motorConfigMutable()->motorPwmInversion = sbufReadU8(src);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -1812,7 +1812,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
rxConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
|
||||
}
|
||||
if (dataSize > 22) {
|
||||
rxConfig()->fpvCamAngleDegrees = sbufReadU8(src);
|
||||
rxConfigMutable()->fpvCamAngleDegrees = sbufReadU8(src);
|
||||
}
|
||||
break;
|
||||
|
||||
|
|
|
@ -59,6 +59,8 @@ typedef struct throttleCorrectionConfig_s {
|
|||
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
||||
} throttleCorrectionConfig_t;
|
||||
|
||||
PG_DECLARE(throttleCorrectionConfig_t, throttleCorrectionConfig);
|
||||
|
||||
typedef struct imuConfig_s {
|
||||
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
|
||||
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
|
||||
|
|
|
@ -45,7 +45,8 @@
|
|||
#endif
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "fc/cli.h" // for cliEnter()
|
||||
|
||||
#include "fc/cli.h"
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
|
@ -53,7 +54,7 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#endif
|
||||
|
||||
static serialConfig_t *serialConfig;
|
||||
static const serialConfig_t *serialConfig;
|
||||
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
|
||||
|
||||
const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
||||
|
@ -160,7 +161,7 @@ serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
|
|||
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
|
||||
{
|
||||
while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[findSerialPortConfigState.lastIndex++];
|
||||
serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++];
|
||||
|
||||
if (candidate->functionMask & function) {
|
||||
return candidate;
|
||||
|
@ -173,7 +174,7 @@ typedef struct findSharedSerialPortState_s {
|
|||
uint8_t lastIndex;
|
||||
} findSharedSerialPortState_t;
|
||||
|
||||
portSharing_e determinePortSharing(serialPortConfig_t *portConfig, serialPortFunction_e function)
|
||||
portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
|
||||
{
|
||||
if (!portConfig || (portConfig->functionMask & function) == 0) {
|
||||
return PORTSHARING_UNUSED;
|
||||
|
@ -181,7 +182,7 @@ portSharing_e determinePortSharing(serialPortConfig_t *portConfig, serialPortFun
|
|||
return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
|
||||
}
|
||||
|
||||
bool isSerialPortShared(serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
||||
bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
||||
{
|
||||
return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
|
||||
}
|
||||
|
@ -198,10 +199,10 @@ serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e s
|
|||
serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
||||
{
|
||||
while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[findSharedSerialPortState.lastIndex++];
|
||||
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSharedSerialPortState.lastIndex++];
|
||||
|
||||
if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
|
||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
|
||||
const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
|
||||
if (!serialPortUsage) {
|
||||
continue;
|
||||
}
|
||||
|
@ -218,7 +219,7 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction
|
|||
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
|
||||
#endif
|
||||
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
|
||||
bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
|
||||
{
|
||||
UNUSED(serialConfigToCheck);
|
||||
/*
|
||||
|
@ -232,9 +233,8 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
|
|||
*/
|
||||
uint8_t mspPortCount = 0;
|
||||
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
|
||||
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
|
||||
|
||||
if (portConfig->functionMask & FUNCTION_MSP) {
|
||||
mspPortCount++;
|
||||
|
@ -268,9 +268,8 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
|
|||
|
||||
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
|
||||
{
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[index];
|
||||
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
|
||||
if (candidate->identifier == identifier) {
|
||||
return candidate;
|
||||
}
|
||||
|
@ -397,7 +396,7 @@ void closeSerialPort(serialPort_t *serialPort)
|
|||
serialPortUsage->serialPort = NULL;
|
||||
}
|
||||
|
||||
void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
|
||||
void serialInit(const serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
|
||||
{
|
||||
uint8_t index;
|
||||
|
||||
|
|
|
@ -17,6 +17,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
|
@ -119,18 +122,18 @@ typedef void serialConsumer(uint8_t);
|
|||
//
|
||||
// configuration
|
||||
//
|
||||
void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||
void serialInit(const serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||
uint8_t serialGetAvailablePortCount(void);
|
||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
||||
bool isSerialConfigValid(const serialConfig_t *serialConfig);
|
||||
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
|
||||
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
|
||||
|
||||
portSharing_e determinePortSharing(serialPortConfig_t *portConfig, serialPortFunction_e function);
|
||||
bool isSerialPortShared(serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);
|
||||
portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function);
|
||||
bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);
|
||||
|
||||
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier);
|
||||
int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier);
|
||||
|
|
|
@ -69,7 +69,7 @@ int32_t amperageLatest = 0; // most recent value
|
|||
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
batteryConfig_t *batteryConfig;
|
||||
const batteryConfig_t *batteryConfig;
|
||||
#endif
|
||||
|
||||
static batteryState_e vBatState;
|
||||
|
@ -213,7 +213,7 @@ const char * getBatteryStateString(void)
|
|||
return batteryStateStrings[getBatteryState()];
|
||||
}
|
||||
|
||||
void batteryInit(batteryConfig_t *initialBatteryConfig)
|
||||
void batteryInit(const batteryConfig_t *initialBatteryConfig)
|
||||
{
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
(void)initialBatteryConfig;
|
||||
|
|
|
@ -81,13 +81,13 @@ extern int32_t amperageLatest;
|
|||
extern int32_t amperage;
|
||||
extern int32_t mAhDrawn;
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
extern batteryConfig_t *batteryConfig;
|
||||
extern const batteryConfig_t *batteryConfig;
|
||||
#endif
|
||||
|
||||
batteryState_e getBatteryState(void);
|
||||
const char * getBatteryStateString(void);
|
||||
void updateBattery(void);
|
||||
void batteryInit(batteryConfig_t *initialBatteryConfig);
|
||||
void batteryInit(const batteryConfig_t *initialBatteryConfig);
|
||||
|
||||
struct rxConfig_s;
|
||||
void updateCurrentMeter(int32_t lastUpdateAt, const struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#define BARO
|
||||
|
||||
extern "C" {
|
||||
#include "platform.h""
|
||||
#include "platform.h"
|
||||
#include "target.h"
|
||||
#include "drivers/display.h"
|
||||
#include "cms/cms.h"
|
||||
|
|
|
@ -56,8 +56,6 @@
|
|||
|
||||
#define SERIAL_PORT_COUNT 8
|
||||
|
||||
#define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 6
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "TEST"
|
||||
|
||||
#define LED_STRIP_TIMER 1
|
||||
|
|
|
@ -306,7 +306,7 @@ serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;}
|
|||
bool telemetryDetermineEnabledState(portSharing_e) {return true;}
|
||||
bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return true;}
|
||||
|
||||
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
|
||||
portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
|
||||
|
||||
uint8_t batteryCapacityRemainingPercentage(void) {return 67;}
|
||||
uint8_t calculateBatteryCapacityRemainingPercentage(void) {return 67;}
|
||||
|
|
|
@ -252,7 +252,7 @@ bool telemetryDetermineEnabledState(portSharing_e)
|
|||
return true;
|
||||
}
|
||||
|
||||
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e)
|
||||
portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e)
|
||||
{
|
||||
return PORTSHARING_NOT_SHARED;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue