mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Minor cleanups to allow CJMCU to build again.
This commit is contained in:
parent
f77a762b48
commit
fa18940087
3 changed files with 6 additions and 4 deletions
2
Makefile
2
Makefile
|
@ -395,8 +395,6 @@ CJMCU_SRC = \
|
||||||
drivers/system_stm32f10x.c \
|
drivers/system_stm32f10x.c \
|
||||||
drivers/timer.c \
|
drivers/timer.c \
|
||||||
drivers/timer_stm32f10x.c \
|
drivers/timer_stm32f10x.c \
|
||||||
blackbox/blackbox.c \
|
|
||||||
blackbox/blackbox_io.c \
|
|
||||||
hardware_revision.c \
|
hardware_revision.c \
|
||||||
$(COMMON_SRC)
|
$(COMMON_SRC)
|
||||||
|
|
||||||
|
|
|
@ -85,8 +85,10 @@ typedef struct master_t {
|
||||||
uint8_t current_profile_index;
|
uint8_t current_profile_index;
|
||||||
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
|
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
|
||||||
|
|
||||||
|
#ifdef BLACKBOX
|
||||||
uint8_t blackbox_rate_num;
|
uint8_t blackbox_rate_num;
|
||||||
uint8_t blackbox_rate_denom;
|
uint8_t blackbox_rate_denom;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t magic_ef; // magic number, should be 0xEF
|
uint8_t magic_ef; // magic number, should be 0xEF
|
||||||
uint8_t chk; // XOR checksum
|
uint8_t chk; // XOR checksum
|
||||||
|
|
|
@ -163,7 +163,7 @@ const clicmd_t cmdTable[] = {
|
||||||
{ "color", "configure colors", cliColor },
|
{ "color", "configure colors", cliColor },
|
||||||
#endif
|
#endif
|
||||||
{ "defaults", "reset to defaults and reboot", cliDefaults },
|
{ "defaults", "reset to defaults and reboot", cliDefaults },
|
||||||
{ "dump", "print configurable settings in a pastable form", cliDump },
|
{ "dump", "dump configuration", cliDump },
|
||||||
{ "exit", "", cliExit },
|
{ "exit", "", cliExit },
|
||||||
{ "feature", "list or -val or val", cliFeature },
|
{ "feature", "list or -val or val", cliFeature },
|
||||||
{ "get", "get variable value", cliGet },
|
{ "get", "get variable value", cliGet },
|
||||||
|
@ -249,7 +249,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[1], 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[1], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
#if (SERIAL_PORT_COUNT > 2)
|
#if (SERIAL_PORT_COUNT > 2)
|
||||||
{ "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[2], 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[2], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
#if !defined(CC3D)
|
#if (SERIAL_PORT_COUNT > 3)
|
||||||
{ "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[3], 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[3], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
#if (SERIAL_PORT_COUNT > 4)
|
#if (SERIAL_PORT_COUNT > 4)
|
||||||
{ "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[4], 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[4], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
|
@ -408,8 +408,10 @@ const clivalue_t valueTable[] = {
|
||||||
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
|
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
|
||||||
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
|
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
|
||||||
|
|
||||||
|
#ifdef BLACKBOX
|
||||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
|
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
|
||||||
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
|
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue