mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
Preparation for conversion to parameter groups 9
This commit is contained in:
parent
5507924b5a
commit
e8d0cd1eec
7 changed files with 38 additions and 15 deletions
|
@ -55,25 +55,38 @@
|
|||
#define PG_NAVIGATION_CONFIG 34 // structs OK
|
||||
#define PG_ACCELEROMETER_CONFIG 35 // no accelerometerConfig_t in betaflight
|
||||
#define PG_RATE_PROFILE_SELECTION 36 // part of profile in betaflight
|
||||
#define PG_ADJUSTMENT_PROFILE 37 // array needs to be made into struct
|
||||
//#define PG_ADJUSTMENT_PROFILE 37 // array needs to be made into struct
|
||||
#define PG_ADJUSTMENT_RANGE_CONFIG 37
|
||||
#define PG_BAROMETER_CONFIG 38 // structs OK
|
||||
#define PG_THROTTLE_CORRECTION_CONFIG 39
|
||||
#define PG_COMPASS_CONFIGURATION 40 // structs OK
|
||||
#define PG_MODE_ACTIVATION_PROFILE 41 // array needs to be made into struct
|
||||
#define PG_SERVO_PROFILE 42
|
||||
#define PG_FAILSAFE_CHANNEL_CONFIG 43 // structs OK
|
||||
#define PG_CHANNEL_RANGE_CONFIG 44 // structs OK
|
||||
//#define PG_SERVO_PROFILE 42
|
||||
#define PG_SERVO_PARAMS 42
|
||||
//#define PG_FAILSAFE_CHANNEL_CONFIG 43 // structs OK
|
||||
#define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
|
||||
//#define PG_CHANNEL_RANGE_CONFIG 44 // structs OK
|
||||
#define PG_RX_CHANNEL_RANGE_CONFIG 44
|
||||
#define PG_MODE_COLOR_CONFIG 45 // part of led strip, structs OK
|
||||
#define PG_SPECIAL_COLOR_CONFIG 46 // part of led strip, structs OK
|
||||
#define PG_PILOT_CONFIG 47 // does not exist in betaflight
|
||||
#define PG_MSP_SERVER_CONFIG 48 // does not exist in betaflight
|
||||
#define PG_VOLTAGE_METER_CONFIG 49 // Cleanflight has voltageMeterConfig_t, betaflight has batteryConfig_t
|
||||
#define PG_AMPERAGE_METER_CONFIG 50 // Cleanflight has amperageMeterConfig_t, betaflight has batteryConfig_t
|
||||
#define PG_SERVO_CONFIG 52
|
||||
|
||||
// Driver configuration
|
||||
#define PG_DRIVER_PWM_RX_CONFIG 100 // does not exist in betaflight
|
||||
#define PG_DRIVER_FLASHCHIP_CONFIG 101 // does not exist in betaflight
|
||||
|
||||
// betaflight specific parameter group ids start at 500
|
||||
#define PG_BETAFLIGHT_START 500
|
||||
#define PG_MODE_ACTIVATION_OPERATOR_CONFIG 500
|
||||
#define PG_OSD_CONFIG 501
|
||||
#define PG_BEEPER_CONFIG 5002
|
||||
#define PG_BETAFLIGHT_END 1002
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
#define PG_OSD_FONT_CONFIG 2047
|
||||
#define PG_OSD_VIDEO_CONFIG 2046
|
||||
|
|
|
@ -208,7 +208,7 @@ static bool m25p16_readIdentification()
|
|||
* Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with
|
||||
* m25p16_getGeometry().
|
||||
*/
|
||||
bool m25p16_init(flashConfig_t *flashConfig)
|
||||
bool m25p16_init(const flashConfig_t *flashConfig)
|
||||
{
|
||||
/*
|
||||
if we have already detected a flash device we can simply exit
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#define M25P16_PAGESIZE 256
|
||||
|
||||
bool m25p16_init(flashConfig_t *flashConfig);
|
||||
bool m25p16_init(const flashConfig_t *flashConfig);
|
||||
|
||||
void m25p16_eraseSector(uint32_t address);
|
||||
void m25p16_eraseCompletely();
|
||||
|
|
|
@ -1567,10 +1567,9 @@ static void cliRxFailsafe(char *cmdline)
|
|||
channel = atoi(ptr++);
|
||||
if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
|
||||
|
||||
rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxConfig()->failsafe_channel_configurations[channel];
|
||||
rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxConfigMutable()->failsafe_channel_configurations[channel];
|
||||
|
||||
uint16_t value;
|
||||
rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
|
||||
const rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
|
||||
rxFailsafeChannelMode_e mode = channelFailsafeConfig->mode;
|
||||
bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
|
||||
|
||||
|
@ -1596,7 +1595,7 @@ static void cliRxFailsafe(char *cmdline)
|
|||
cliShowParseError();
|
||||
return;
|
||||
}
|
||||
value = atoi(ptr);
|
||||
uint16_t value = atoi(ptr);
|
||||
value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
|
||||
if (value > MAX_RXFAIL_RANGE_STEP) {
|
||||
cliPrint("Value out of range\r\n");
|
||||
|
@ -2004,7 +2003,7 @@ static void printMotorMix(uint8_t dumpMask, const motorMixer_t *customMotorMixer
|
|||
char buf2[8];
|
||||
char buf3[8];
|
||||
for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
if (customMotorMixer(i)->throttle == 0.0f)
|
||||
if (customMotorMixer[i].throttle == 0.0f)
|
||||
break;
|
||||
const float thr = customMotorMixer[i].throttle;
|
||||
const float roll = customMotorMixer[i].roll;
|
||||
|
|
|
@ -22,6 +22,11 @@
|
|||
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/flash.h"
|
||||
#include "drivers/rx_pwm.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#if FLASH_SIZE <= 128
|
||||
#define MAX_PROFILE_COUNT 2
|
||||
#else
|
||||
|
@ -67,6 +72,11 @@ typedef struct systemConfig_s {
|
|||
} systemConfig_t;
|
||||
|
||||
PG_DECLARE(systemConfig_t, systemConfig);
|
||||
PG_DECLARE(adcConfig_t, adcConfig);
|
||||
PG_DECLARE(beeperDevConfig_t, beeperDevConfig);
|
||||
PG_DECLARE(flashConfig_t, flashConfig);
|
||||
PG_DECLARE(ppmConfig_t, ppmConfig);
|
||||
PG_DECLARE(pwmConfig_t, pwmConfig);
|
||||
|
||||
/*typedef struct beeperConfig_s {
|
||||
uint32_t beeper_off_flags;
|
||||
|
|
|
@ -364,9 +364,9 @@ void init(void)
|
|||
|
||||
#ifdef USE_ADC
|
||||
/* these can be removed from features! */
|
||||
adcConfig()->vbat.enabled = feature(FEATURE_VBAT);
|
||||
adcConfig()->currentMeter.enabled = feature(FEATURE_CURRENT_METER);
|
||||
adcConfig()->rssi.enabled = feature(FEATURE_RSSI_ADC);
|
||||
adcConfigMutable()->vbat.enabled = feature(FEATURE_VBAT);
|
||||
adcConfigMutable()->currentMeter.enabled = feature(FEATURE_CURRENT_METER);
|
||||
adcConfigMutable()->rssi.enabled = feature(FEATURE_RSSI_ADC);
|
||||
adcInit(adcConfig());
|
||||
#endif
|
||||
|
||||
|
|
|
@ -163,7 +163,8 @@ typedef struct controlRateConfig_s {
|
|||
uint16_t tpa_breakpoint; // Breakpoint where TPA is activated
|
||||
} controlRateConfig_t;
|
||||
|
||||
//!!TODO PG_DECLARE_ARRAY(controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles);
|
||||
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
|
||||
PG_DECLARE_ARRAY(controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles);
|
||||
|
||||
extern int16_t rcCommand[4];
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue