1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Rebased on to master

This commit is contained in:
jflyper 2017-06-19 19:43:18 +09:00
commit 8e2ebcf026
120 changed files with 1018 additions and 851 deletions

View file

@ -665,6 +665,7 @@ COMMON_SRC = \
build/version.c \ build/version.c \
$(TARGET_DIR_SRC) \ $(TARGET_DIR_SRC) \
main.c \ main.c \
common/bitarray.c \
common/encoding.c \ common/encoding.c \
common/filter.c \ common/filter.c \
common/maths.c \ common/maths.c \
@ -736,6 +737,7 @@ FC_SRC = \
fc/fc_rc.c \ fc/fc_rc.c \
fc/rc_adjustments.c \ fc/rc_adjustments.c \
fc/rc_controls.c \ fc/rc_controls.c \
fc/rc_modes.c \
fc/cli.c \ fc/cli.c \
fc/settings.c \ fc/settings.c \
flight/altitude.c \ flight/altitude.c \
@ -1016,7 +1018,8 @@ STM32F7xx_COMMON_SRC = \
drivers/serial_uart_stm32f7xx.c \ drivers/serial_uart_stm32f7xx.c \
drivers/serial_uart_hal.c drivers/serial_uart_hal.c
F7EXCLUDES = drivers/bus_spi.c \ F7EXCLUDES = \
drivers/bus_spi.c \
drivers/bus_i2c.c \ drivers/bus_i2c.c \
drivers/timer.c \ drivers/timer.c \
drivers/serial_uart.c drivers/serial_uart.c

View file

@ -47,6 +47,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
@ -325,7 +326,7 @@ typedef struct blackboxSlowState_s {
extern uint16_t motorOutputHigh, motorOutputLow; extern uint16_t motorOutputHigh, motorOutputLow;
//From rc_controls.c //From rc_controls.c
extern uint32_t rcModeActivationMask; extern boxBitmask_t rcModeActivationMask;
static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
@ -753,7 +754,7 @@ static void writeSlowFrame(void)
*/ */
static void loadSlowState(blackboxSlowState_t *slow) static void loadSlowState(blackboxSlowState_t *slow)
{ {
slow->flightModeFlags = rcModeActivationMask; //was flightModeFlags; memcpy(&slow->flightModeFlags, &rcModeActivationMask, sizeof(slow->flightModeFlags)); //was flightModeFlags;
slow->stateFlags = stateFlags; slow->stateFlags = stateFlags;
slow->failsafePhase = failsafePhase(); slow->failsafePhase = failsafePhase();
slow->rxSignalReceived = rxIsReceivingSignal(); slow->rxSignalReceived = rxIsReceivingSignal();
@ -861,7 +862,7 @@ static void blackboxStart(void)
*/ */
blackboxBuildConditionCache(); blackboxBuildConditionCache();
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(modeActivationConditions(0), BOXBLACKBOX); blackboxModeActivationConditionPresent = isModeActivationConditionPresent(BOXBLACKBOX);
blackboxResetIterationTimers(); blackboxResetIterationTimers();
@ -870,7 +871,7 @@ static void blackboxStart(void)
* it finally plays the beep for this arming event. * it finally plays the beep for this arming event.
*/ */
blackboxLastArmingBeep = getArmingBeepTimeMicros(); blackboxLastArmingBeep = getArmingBeepTimeMicros();
blackboxLastFlightModeFlags = rcModeActivationMask; // record startup status memcpy(&blackboxLastFlightModeFlags, &rcModeActivationMask, sizeof(blackboxLastFlightModeFlags)); // record startup status
blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE); blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
} }
@ -1383,10 +1384,10 @@ static void blackboxCheckAndLogFlightMode(void)
flightLogEvent_flightMode_t eventData; // Add new data for current flight mode flags flightLogEvent_flightMode_t eventData; // Add new data for current flight mode flags
// Use != so that we can still detect a change if the counter wraps // Use != so that we can still detect a change if the counter wraps
if (rcModeActivationMask != blackboxLastFlightModeFlags) { if (memcmp(&rcModeActivationMask, &blackboxLastFlightModeFlags, sizeof(blackboxLastFlightModeFlags))) {
eventData.lastFlags = blackboxLastFlightModeFlags; eventData.lastFlags = blackboxLastFlightModeFlags;
blackboxLastFlightModeFlags = rcModeActivationMask; memcpy(&blackboxLastFlightModeFlags, &rcModeActivationMask, sizeof(blackboxLastFlightModeFlags));
eventData.flags = rcModeActivationMask; memcpy(&eventData.flags, &rcModeActivationMask, sizeof(eventData.flags));
blackboxLogEvent(FLIGHT_LOG_EVENT_FLIGHTMODE, (flightLogEventData_t *) &eventData); blackboxLogEvent(FLIGHT_LOG_EVENT_FLIGHTMODE, (flightLogEventData_t *) &eventData);
} }

View file

@ -0,0 +1,39 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdbool.h>
#include "bitarray.h"
#define BITARRAY_BIT_OP(array, bit, op) ((array)[(bit) / (sizeof((array)[0]) * 8)] op (1 << ((bit) % (sizeof((array)[0]) * 8))))
bool bitArrayGet(const void *array, unsigned bit)
{
return BITARRAY_BIT_OP((uint32_t*)array, bit, &);
}
void bitArraySet(void *array, unsigned bit)
{
BITARRAY_BIT_OP((uint32_t*)array, bit, |=);
}
void bitArrayClr(void *array, unsigned bit)
{
BITARRAY_BIT_OP((uint32_t*)array, bit, &=~);
}

View file

@ -0,0 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
bool bitArrayGet(const void *array, unsigned bit);
void bitArraySet(void *array, unsigned bit);
void bitArrayClr(void *array, unsigned bit);

View file

@ -20,6 +20,8 @@
#include <stddef.h> #include <stddef.h>
#include <stdint.h> #include <stdint.h>
#define NOOP do {} while (0)
#define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0])) #define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0]))
#define ARRAYEND(x) (&(x)[ARRAYLEN(x)]) #define ARRAYEND(x) (&(x)[ARRAYLEN(x)])

View file

@ -38,10 +38,7 @@ static uint16_t eepromConfigSize;
typedef enum { typedef enum {
CR_CLASSICATION_SYSTEM = 0, CR_CLASSICATION_SYSTEM = 0,
CR_CLASSICATION_PROFILE1 = 1, CR_CLASSICATION_PROFILE_LAST = CR_CLASSICATION_SYSTEM,
CR_CLASSICATION_PROFILE2 = 2,
CR_CLASSICATION_PROFILE3 = 3,
CR_CLASSICATION_PROFILE_LAST = CR_CLASSICATION_PROFILE3,
} configRecordFlags_e; } configRecordFlags_e;
#define CR_CLASSIFICATION_MASK (0x3) #define CR_CLASSIFICATION_MASK (0x3)
@ -178,23 +175,12 @@ static const configRecord_t *findEEPROM(const pgRegistry_t *reg, configRecordFla
bool loadEEPROM(void) bool loadEEPROM(void)
{ {
PG_FOREACH(reg) { PG_FOREACH(reg) {
configRecordFlags_e cls_start, cls_end; const configRecord_t *rec = findEEPROM(reg, CR_CLASSICATION_SYSTEM);
if (pgIsSystem(reg)) {
cls_start = CR_CLASSICATION_SYSTEM;
cls_end = CR_CLASSICATION_SYSTEM;
} else {
cls_start = CR_CLASSICATION_PROFILE1;
cls_end = CR_CLASSICATION_PROFILE_LAST;
}
for (configRecordFlags_e cls = cls_start; cls <= cls_end; cls++) {
int profileIndex = cls - cls_start;
const configRecord_t *rec = findEEPROM(reg, cls);
if (rec) { if (rec) {
// config from EEPROM is available, use it to initialize PG. pgLoad will handle version mismatch // config from EEPROM is available, use it to initialize PG. pgLoad will handle version mismatch
pgLoad(reg, profileIndex, rec->pg, rec->size - offsetof(configRecord_t, pg), rec->version); pgLoad(reg, rec->pg, rec->size - offsetof(configRecord_t, pg), rec->version);
} else { } else {
pgReset(reg, profileIndex); pgReset(reg);
}
} }
} }
return true; return true;
@ -225,25 +211,11 @@ static bool writeSettingsToEEPROM(void)
.flags = 0 .flags = 0
}; };
if (pgIsSystem(reg)) {
// write the only instance
record.flags |= CR_CLASSICATION_SYSTEM; record.flags |= CR_CLASSICATION_SYSTEM;
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record)); config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
crc = crc16_ccitt_update(crc, (uint8_t *)&record, sizeof(record)); crc = crc16_ccitt_update(crc, (uint8_t *)&record, sizeof(record));
config_streamer_write(&streamer, reg->address, regSize); config_streamer_write(&streamer, reg->address, regSize);
crc = crc16_ccitt_update(crc, reg->address, regSize); crc = crc16_ccitt_update(crc, reg->address, regSize);
} else {
// write one instance for each profile
for (uint8_t profileIndex = 0; profileIndex < PG_PROFILE_COUNT; profileIndex++) {
record.flags = 0;
record.flags |= ((profileIndex + 1) & CR_CLASSIFICATION_MASK);
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
crc = crc16_ccitt_update(crc, (uint8_t *)&record, sizeof(record));
const uint8_t *address = reg->address + (regSize * profileIndex);
config_streamer_write(&streamer, address, regSize);
crc = crc16_ccitt_update(crc, address, regSize);
}
}
} }
configFooter_t footer = { configFooter_t footer = {

View file

@ -34,15 +34,9 @@ const pgRegistry_t* pgFind(pgn_t pgn)
return NULL; return NULL;
} }
static uint8_t *pgOffset(const pgRegistry_t* reg, uint8_t profileIndex) static uint8_t *pgOffset(const pgRegistry_t* reg)
{ {
const uint16_t regSize = pgSize(reg); return reg->address;
uint8_t *base = reg->address;
if (!pgIsSystem(reg)) {
base += (regSize * profileIndex);
}
return base;
} }
static void pgResetInstance(const pgRegistry_t *reg, uint8_t *base) static void pgResetInstance(const pgRegistry_t *reg, uint8_t *base)
@ -59,18 +53,9 @@ static void pgResetInstance(const pgRegistry_t *reg, uint8_t *base)
} }
} }
void pgReset(const pgRegistry_t* reg, int profileIndex) void pgReset(const pgRegistry_t* reg)
{ {
pgResetInstance(reg, pgOffset(reg, profileIndex)); pgResetInstance(reg, pgOffset(reg));
}
void pgResetCurrent(const pgRegistry_t *reg)
{
if (pgIsSystem(reg)) {
pgResetInstance(reg, reg->address);
} else {
pgResetInstance(reg, *reg->ptr);
}
} }
bool pgResetCopy(void *copy, pgn_t pgn) bool pgResetCopy(void *copy, pgn_t pgn)
@ -83,44 +68,26 @@ bool pgResetCopy(void *copy, pgn_t pgn)
return false; return false;
} }
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version) void pgLoad(const pgRegistry_t* reg, const void *from, int size, int version)
{ {
pgResetInstance(reg, pgOffset(reg, profileIndex)); pgResetInstance(reg, pgOffset(reg));
// restore only matching version, keep defaults otherwise // restore only matching version, keep defaults otherwise
if (version == pgVersion(reg)) { if (version == pgVersion(reg)) {
const int take = MIN(size, pgSize(reg)); const int take = MIN(size, pgSize(reg));
memcpy(pgOffset(reg, profileIndex), from, take); memcpy(pgOffset(reg), from, take);
} }
} }
int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex) int pgStore(const pgRegistry_t* reg, void *to, int size)
{ {
const int take = MIN(size, pgSize(reg)); const int take = MIN(size, pgSize(reg));
memcpy(to, pgOffset(reg, profileIndex), take); memcpy(to, pgOffset(reg), take);
return take; return take;
} }
void pgResetAll()
void pgResetAll(int profileCount)
{ {
PG_FOREACH(reg) { PG_FOREACH(reg) {
if (pgIsSystem(reg)) { pgReset(reg);
pgReset(reg, 0);
} else {
// reset one instance for each profile
for (int profileIndex = 0; profileIndex < profileCount; profileIndex++) {
pgReset(reg, profileIndex);
}
}
}
}
void pgActivateProfile(int profileIndex)
{
PG_FOREACH(reg) {
if (!pgIsSystem(reg)) {
uint8_t *ptr = pgOffset(reg, profileIndex);
*(reg->ptr) = ptr;
}
} }
} }

View file

@ -34,14 +34,9 @@ typedef enum {
PGR_PGN_MASK = 0x0fff, PGR_PGN_MASK = 0x0fff,
PGR_PGN_VERSION_MASK = 0xf000, PGR_PGN_VERSION_MASK = 0xf000,
PGR_SIZE_MASK = 0x0fff, PGR_SIZE_MASK = 0x0fff,
PGR_SIZE_SYSTEM_FLAG = 0x0000, // documentary PGR_SIZE_SYSTEM_FLAG = 0x0000 // documentary
PGR_SIZE_PROFILE_FLAG = 0x8000 // start using flags from the top bit down
} pgRegistryInternal_e; } pgRegistryInternal_e;
enum {
PG_PROFILE_COUNT = 3
};
// function that resets a single parameter group instance // function that resets a single parameter group instance
typedef void (pgResetFunc)(void * /* base */, int /* size */); typedef void (pgResetFunc)(void * /* base */, int /* size */);
@ -60,8 +55,6 @@ typedef struct pgRegistry_s {
static inline uint16_t pgN(const pgRegistry_t* reg) {return reg->pgn & PGR_PGN_MASK;} static inline uint16_t pgN(const pgRegistry_t* reg) {return reg->pgn & PGR_PGN_MASK;}
static inline uint8_t pgVersion(const pgRegistry_t* reg) {return (uint8_t)(reg->pgn >> 12);} static inline uint8_t pgVersion(const pgRegistry_t* reg) {return (uint8_t)(reg->pgn >> 12);}
static inline uint16_t pgSize(const pgRegistry_t* reg) {return reg->size & PGR_SIZE_MASK;} static inline uint16_t pgSize(const pgRegistry_t* reg) {return reg->size & PGR_SIZE_MASK;}
static inline uint16_t pgIsSystem(const pgRegistry_t* reg) {return (reg->size & PGR_SIZE_PROFILE_FLAG) == 0;}
static inline uint16_t pgIsProfile(const pgRegistry_t* reg) {return (reg->size & PGR_SIZE_PROFILE_FLAG) == PGR_SIZE_PROFILE_FLAG;}
#define PG_PACKED __attribute__((packed)) #define PG_PACKED __attribute__((packed))
@ -89,19 +82,11 @@ extern const uint8_t __pg_resetdata_end[];
#define PG_FOREACH(_name) \ #define PG_FOREACH(_name) \
for (const pgRegistry_t *(_name) = __pg_registry_start; (_name) < __pg_registry_end; _name++) for (const pgRegistry_t *(_name) = __pg_registry_start; (_name) < __pg_registry_end; _name++)
#define PG_FOREACH_PROFILE(_name) \
PG_FOREACH(_name) \
if(pgIsSystem(_name)) \
continue; \
else \
/**/
// Reset configuration to default (by name) // Reset configuration to default (by name)
// Only current profile is reset for profile based configs #define PG_RESET(_name) \
#define PG_RESET_CURRENT(_name) \
do { \ do { \
extern const pgRegistry_t _name ##_Registry; \ extern const pgRegistry_t _name ##_Registry; \
pgResetCurrent(&_name ## _Registry); \ pgReset(&_name ## _Registry); \
} while(0) \ } while(0) \
/**/ /**/
@ -124,15 +109,6 @@ extern const uint8_t __pg_resetdata_end[];
struct _dummy \ struct _dummy \
/**/ /**/
// Declare profile config
#define PG_DECLARE_PROFILE(_type, _name) \
extern _type *_name ## _ProfileCurrent; \
static inline const _type* _name(void) { return _name ## _ProfileCurrent; } \
static inline _type* _name ## Mutable(void) { return _name ## _ProfileCurrent; } \
struct _dummy \
/**/
// Register system config // Register system config
#define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \ #define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \
_type _name ## _System; \ _type _name ## _System; \
@ -195,43 +171,6 @@ extern const uint8_t __pg_resetdata_end[];
/**/ /**/
#endif #endif
#ifdef UNIT_TEST
# define _PG_PROFILE_CURRENT_DECL(_type, _name) \
_type *_name ## _ProfileCurrent = &_name ## _Storage[0];
#else
# define _PG_PROFILE_CURRENT_DECL(_type, _name) \
_type *_name ## _ProfileCurrent;
#endif
// register profile config
#define PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, _reset) \
STATIC_UNIT_TESTED _type _name ## _Storage[PG_PROFILE_COUNT]; \
_PG_PROFILE_CURRENT_DECL(_type, _name) \
extern const pgRegistry_t _name ## _Registry; \
const pgRegistry_t _name ## _Registry PG_REGISTER_ATTRIBUTES = { \
.pgn = _pgn | (_version << 12), \
.size = sizeof(_type) | PGR_SIZE_PROFILE_FLAG, \
.address = (uint8_t*)&_name ## _Storage, \
.ptr = (uint8_t **)&_name ## _ProfileCurrent, \
_reset, \
} \
/**/
#define PG_REGISTER_PROFILE(_type, _name, _pgn, _version) \
PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, .reset = {.ptr = 0}) \
/**/
#define PG_REGISTER_PROFILE_WITH_RESET_FN(_type, _name, _pgn, _version) \
extern void pgResetFn_ ## _name(_type *); \
PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, .reset = {.fn = (pgResetFunc*)&pgResetFn_ ## _name}) \
/**/
#define PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(_type, _name, _pgn, _version) \
extern const _type pgResetTemplate_ ## _name; \
PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, .reset = {.ptr = (void*)&pgResetTemplate_ ## _name}) \
/**/
// Emit reset defaults for config. // Emit reset defaults for config.
// Config must be registered with PG_REGISTER_<xxx>_WITH_RESET_TEMPLATE macro // Config must be registered with PG_REGISTER_<xxx>_WITH_RESET_TEMPLATE macro
#define PG_RESET_TEMPLATE(_type, _name, ...) \ #define PG_RESET_TEMPLATE(_type, _name, ...) \
@ -245,10 +184,8 @@ extern const uint8_t __pg_resetdata_end[];
const pgRegistry_t* pgFind(pgn_t pgn); const pgRegistry_t* pgFind(pgn_t pgn);
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version); void pgLoad(const pgRegistry_t* reg, const void *from, int size, int version);
int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex); int pgStore(const pgRegistry_t* reg, void *to, int size);
void pgResetAll(int profileCount); void pgResetAll();
void pgResetCurrent(const pgRegistry_t *reg);
bool pgResetCopy(void *copy, pgn_t pgn); bool pgResetCopy(void *copy, pgn_t pgn);
void pgReset(const pgRegistry_t* reg, int profileIndex); void pgReset(const pgRegistry_t* reg);
void pgActivateProfile(int profileIndex);

View file

@ -17,24 +17,49 @@
#include "platform.h" #include "platform.h"
#include "config/parameter_group_ids.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "light_led.h" #include "light_led.h"
static IO_t leds[LED_NUMBER]; PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
static uint8_t ledPolarity = 0;
static IO_t leds[STATUS_LED_NUMBER];
static uint8_t ledInversion = 0;
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
{
#ifdef LED0_PIN
statusLedConfig->ioTags[0] = IO_TAG(LED0_PIN);
#endif
#ifdef LED1_PIN
statusLedConfig->ioTags[1] = IO_TAG(LED1_PIN);
#endif
#ifdef LED2_PIN
statusLedConfig->ioTags[2] = IO_TAG(LED2_PIN);
#endif
statusLedConfig->inversion = 0
#ifdef LED0_INVERTED
| BIT(0)
#endif
#ifdef LED1_INVERTED
| BIT(1)
#endif
#ifdef LED2_INVERTED
| BIT(2)
#endif
;
}
void ledInit(const statusLedConfig_t *statusLedConfig) void ledInit(const statusLedConfig_t *statusLedConfig)
{ {
LED0_OFF; ledInversion = statusLedConfig->inversion;
LED1_OFF; for (int i = 0; i < STATUS_LED_NUMBER; i++) {
LED2_OFF; if (statusLedConfig->ioTags[i]) {
leds[i] = IOGetByTag(statusLedConfig->ioTags[i]);
ledPolarity = statusLedConfig->polarity;
for (int i = 0; i < LED_NUMBER; i++) {
if (statusLedConfig->ledTags[i]) {
leds[i] = IOGetByTag(statusLedConfig->ledTags[i]);
IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i)); IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
IOConfigGPIO(leds[i], IOCFG_OUT_PP); IOConfigGPIO(leds[i], IOCFG_OUT_PP);
} else { } else {
@ -54,6 +79,6 @@ void ledToggle(int led)
void ledSet(int led, bool on) void ledSet(int led, bool on)
{ {
const bool inverted = (1 << (led)) & ledPolarity; const bool inverted = (1 << (led)) & ledInversion;
IOWrite(leds[led], on ? inverted : !inverted); IOWrite(leds[led], on ? inverted : !inverted);
} }

View file

@ -19,47 +19,48 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "drivers/io_types.h" #include "drivers/io_types.h"
#include "common/utils.h"
#define LED_NUMBER 3 #define STATUS_LED_NUMBER 3
typedef struct statusLedConfig_s { typedef struct statusLedConfig_s {
ioTag_t ledTags[LED_NUMBER]; ioTag_t ioTags[STATUS_LED_NUMBER];
uint8_t polarity; uint8_t inversion;
} statusLedConfig_t; } statusLedConfig_t;
PG_DECLARE(statusLedConfig_t, statusLedConfig); PG_DECLARE(statusLedConfig_t, statusLedConfig);
// Helpful macros // Helpful macros
#ifdef LED0 #if defined(UNIT_TEST) || defined(USE_FAKE_LED)
# define LED0_TOGGLE ledToggle(0)
# define LED0_OFF ledSet(0, false)
# define LED0_ON ledSet(0, true)
#else
# define LED0_TOGGLE do {} while(0)
# define LED0_OFF do {} while(0)
# define LED0_ON do {} while(0)
#endif
#ifdef LED1 #define LED0_TOGGLE NOOP
# define LED1_TOGGLE ledToggle(1) #define LED0_OFF NOOP
# define LED1_OFF ledSet(1, false) #define LED0_ON NOOP
# define LED1_ON ledSet(1, true)
#else #define LED1_TOGGLE NOOP
# define LED1_TOGGLE do {} while(0) #define LED1_OFF NOOP
# define LED1_OFF do {} while(0) #define LED1_ON NOOP
# define LED1_ON do {} while(0)
#endif #define LED2_TOGGLE NOOP
#define LED2_OFF NOOP
#define LED2_ON NOOP
#ifdef LED2
# define LED2_TOGGLE ledToggle(2)
# define LED2_OFF ledSet(2, false)
# define LED2_ON ledSet(2, true)
#else #else
# define LED2_TOGGLE do {} while(0)
# define LED2_OFF do {} while(0) #define LED0_TOGGLE ledToggle(0)
# define LED2_ON do {} while(0) #define LED0_OFF ledSet(0, false)
#endif #define LED0_ON ledSet(0, true)
#define LED1_TOGGLE ledToggle(1)
#define LED1_OFF ledSet(1, false)
#define LED1_ON ledSet(1, true)
#define LED2_TOGGLE ledToggle(2)
#define LED2_OFF ledSet(2, false)
#define LED2_ON ledSet(2, true)
void ledInit(const statusLedConfig_t *statusLedConfig); void ledInit(const statusLedConfig_t *statusLedConfig);
void ledToggle(int led); void ledToggle(int led);
void ledSet(int led, bool state); void ledSet(int led, bool state);
#endif

View file

@ -158,7 +158,9 @@ static void pwmWriteMultiShot(uint8_t index, uint16_t value)
void pwmWriteMotor(uint8_t index, uint16_t value) void pwmWriteMotor(uint8_t index, uint16_t value)
{ {
if (pwmMotorsEnabled) {
pwmWritePtr(index, value); pwmWritePtr(index, value);
}
} }
void pwmShutdownPulsesForAllMotors(uint8_t motorCount) void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
@ -245,11 +247,16 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
idlePulse = 0; idlePulse = 0;
break; break;
#ifdef USE_DSHOT #ifdef USE_DSHOT
case PWM_TYPE_PROSHOT1000:
pwmWritePtr = pwmWriteProShot;
pwmCompleteWritePtr = pwmCompleteDigitalMotorUpdate;
isDigital = true;
break;
case PWM_TYPE_DSHOT1200: case PWM_TYPE_DSHOT1200:
case PWM_TYPE_DSHOT600: case PWM_TYPE_DSHOT600:
case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT300:
case PWM_TYPE_DSHOT150: case PWM_TYPE_DSHOT150:
pwmWritePtr = pwmWriteDigital; pwmWritePtr = pwmWriteDshot;
pwmCompleteWritePtr = pwmCompleteDigitalMotorUpdate; pwmCompleteWritePtr = pwmCompleteDigitalMotorUpdate;
isDigital = true; isDigital = true;
break; break;
@ -320,6 +327,8 @@ pwmOutputPort_t *pwmGetMotors(void)
uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType) uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
{ {
switch (pwmProtocolType) { switch (pwmProtocolType) {
case(PWM_TYPE_PROSHOT1000):
return MOTOR_PROSHOT1000_MHZ * 1000000;
case(PWM_TYPE_DSHOT1200): case(PWM_TYPE_DSHOT1200):
return MOTOR_DSHOT1200_MHZ * 1000000; return MOTOR_DSHOT1200_MHZ * 1000000;
case(PWM_TYPE_DSHOT600): case(PWM_TYPE_DSHOT600):
@ -338,11 +347,21 @@ void pwmWriteDshotCommand(uint8_t index, uint8_t command)
motorDmaOutput_t *const motor = getMotorDmaOutput(index); motorDmaOutput_t *const motor = getMotorDmaOutput(index);
unsigned repeats; unsigned repeats;
if ((DSHOT_CMD_SPIN_ONE_WAY >= 7 && DSHOT_CMD_3D_MODE_ON <= 10) || DSHOT_CMD_SAVE_SETTINGS == 12 || (DSHOT_CMD_ROTATE_NORMAL >= 20 && DSHOT_CMD_ROTATE_REVERSE <= 21) ) { switch (command) {
case DSHOT_CMD_SPIN_DIRECTION_1:
case DSHOT_CMD_SPIN_DIRECTION_2:
case DSHOT_CMD_3D_MODE_OFF:
case DSHOT_CMD_3D_MODE_ON:
case DSHOT_CMD_SAVE_SETTINGS:
case DSHOT_CMD_SPIN_DIRECTION_NORMAL:
case DSHOT_CMD_SPIN_DIRECTION_REVERSED:
repeats = 10; repeats = 10;
} else { break;
default:
repeats = 1; repeats = 1;
break;
} }
for (; repeats; repeats--) { for (; repeats; repeats--) {
motor->requestTelemetry = true; motor->requestTelemetry = true;
pwmWritePtr(index, command); pwmWritePtr(index, command);

View file

@ -36,14 +36,14 @@ typedef enum {
DSHOT_CMD_BEEP4, DSHOT_CMD_BEEP4,
DSHOT_CMD_BEEP5, DSHOT_CMD_BEEP5,
DSHOT_CMD_ESC_INFO, DSHOT_CMD_ESC_INFO,
DSHOT_CMD_SPIN_ONE_WAY, DSHOT_CMD_SPIN_DIRECTION_1,
DSHOT_CMD_SPIN_OTHER_WAY, DSHOT_CMD_SPIN_DIRECTION_2,
DSHOT_CMD_3D_MODE_OFF, DSHOT_CMD_3D_MODE_OFF,
DSHOT_CMD_3D_MODE_ON, DSHOT_CMD_3D_MODE_ON,
DSHOT_CMD_SETTINGS_REQUEST, DSHOT_CMD_SETTINGS_REQUEST,
DSHOT_CMD_SAVE_SETTINGS, DSHOT_CMD_SAVE_SETTINGS,
DSHOT_CMD_ROTATE_NORMAL = 20, //Blheli_S only command DSHOT_CMD_SPIN_DIRECTION_NORMAL = 20, //Blheli_S only command
DSHOT_CMD_ROTATE_REVERSE = 21, //Blheli_S only command DSHOT_CMD_SPIN_DIRECTION_REVERSED = 21, //Blheli_S only command
DSHOT_CMD_MAX = 47 DSHOT_CMD_MAX = 47
} dshotCommands_e; } dshotCommands_e;
@ -59,6 +59,7 @@ typedef enum {
PWM_TYPE_DSHOT300, PWM_TYPE_DSHOT300,
PWM_TYPE_DSHOT600, PWM_TYPE_DSHOT600,
PWM_TYPE_DSHOT1200, PWM_TYPE_DSHOT1200,
PWM_TYPE_PROSHOT1000,
#endif #endif
PWM_TYPE_MAX PWM_TYPE_MAX
} motorPwmProtocolTypes_e; } motorPwmProtocolTypes_e;
@ -76,6 +77,11 @@ typedef enum {
#define MOTOR_BIT_0 7 #define MOTOR_BIT_0 7
#define MOTOR_BIT_1 14 #define MOTOR_BIT_1 14
#define MOTOR_BITLENGTH 19 #define MOTOR_BITLENGTH 19
#define MOTOR_PROSHOT1000_MHZ 24
#define PROSHOT_BASE_SYMBOL 24 // 1uS
#define PROSHOT_BIT_WIDTH 3
#define MOTOR_NIBBLE_LENGTH_PROSHOT 96 // 4uS
#endif #endif
#if defined(STM32F40_41xxx) // must be multiples of timer clock #if defined(STM32F40_41xxx) // must be multiples of timer clock
@ -95,7 +101,8 @@ typedef enum {
#define PWM_BRUSHED_TIMER_MHZ 24 #define PWM_BRUSHED_TIMER_MHZ 24
#endif #endif
#define MOTOR_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */ #define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
#define PROSHOT_DMA_BUFFER_SIZE 6/* resolution + frame reset (2us) */
typedef struct { typedef struct {
TIM_TypeDef *timer; TIM_TypeDef *timer;
@ -109,9 +116,9 @@ typedef struct {
uint16_t timerDmaSource; uint16_t timerDmaSource;
volatile bool requestTelemetry; volatile bool requestTelemetry;
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) #if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
uint32_t dmaBuffer[MOTOR_DMA_BUFFER_SIZE]; uint32_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE];
#else #else
uint8_t dmaBuffer[MOTOR_DMA_BUFFER_SIZE]; uint8_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE];
#endif #endif
#if defined(STM32F7) #if defined(STM32F7)
TIM_HandleTypeDef TimHandle; TIM_HandleTypeDef TimHandle;
@ -160,7 +167,8 @@ void pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIn
#ifdef USE_DSHOT #ifdef USE_DSHOT
uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType); uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType);
void pwmWriteDshotCommand(uint8_t index, uint8_t command); void pwmWriteDshotCommand(uint8_t index, uint8_t command);
void pwmWriteDigital(uint8_t index, uint16_t value); void pwmWriteProShot(uint8_t index, uint16_t value);
void pwmWriteDshot(uint8_t index, uint16_t value);
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output); void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output);
void pwmCompleteDigitalMotorUpdate(uint8_t motorCount); void pwmCompleteDigitalMotorUpdate(uint8_t motorCount);
#endif #endif

View file

@ -54,13 +54,8 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
return dmaMotorTimerCount-1; return dmaMotorTimerCount-1;
} }
void pwmWriteDigital(uint8_t index, uint16_t value) void pwmWriteDshot(uint8_t index, uint16_t value)
{ {
if (!pwmMotorsEnabled) {
return;
}
motorDmaOutput_t * const motor = &dmaMotors[index]; motorDmaOutput_t * const motor = &dmaMotors[index];
if (!motor->timerHardware || !motor->timerHardware->dmaRef) { if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
@ -86,7 +81,39 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
packet <<= 1; packet <<= 1;
} }
DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, MOTOR_DMA_BUFFER_SIZE); DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, DSHOT_DMA_BUFFER_SIZE);
DMA_Cmd(motor->timerHardware->dmaRef, ENABLE);
}
void pwmWriteProShot(uint8_t index, uint16_t value)
{
motorDmaOutput_t * const motor = &dmaMotors[index];
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
return;
}
uint16_t packet = (value << 1) | (motor->requestTelemetry ? 1 : 0);
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row
// compute checksum
int csum = 0;
int csum_data = packet;
for (int i = 0; i < 3; i++) {
csum ^= csum_data; // xor data by nibbles
csum_data >>= 4;
}
csum &= 0xf;
// append checksum
packet = (packet << 4) | csum;
// generate pulses for Proshot
for (int i = 0; i < 4; i++) {
motor->dmaBuffer[i] = PROSHOT_BASE_SYMBOL + ((packet & 0xF000) >> 12) * PROSHOT_BIT_WIDTH; // Most significant nibble first
packet <<= 4; // Shift 4 bits
}
DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, PROSHOT_DMA_BUFFER_SIZE);
DMA_Cmd(motor->timerHardware->dmaRef, ENABLE); DMA_Cmd(motor->timerHardware->dmaRef, ENABLE);
} }
@ -139,7 +166,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
TIM_Cmd(timer, DISABLE); TIM_Cmd(timer, DISABLE);
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((timerClock(timer) / getDshotHz(pwmProtocolType)) - 1); TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((timerClock(timer) / getDshotHz(pwmProtocolType)) - 1);
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH; TIM_TimeBaseStructure.TIM_Period = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0; TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
@ -205,7 +232,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
#endif #endif
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
DMA_InitStructure.DMA_BufferSize = MOTOR_DMA_BUFFER_SIZE; DMA_InitStructure.DMA_BufferSize = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;

View file

@ -49,12 +49,8 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
return dmaMotorTimerCount - 1; return dmaMotorTimerCount - 1;
} }
void pwmWriteDigital(uint8_t index, uint16_t value) void pwmWriteDshot(uint8_t index, uint16_t value)
{ {
if (!pwmMotorsEnabled) {
return;
}
motorDmaOutput_t * const motor = &dmaMotors[index]; motorDmaOutput_t * const motor = &dmaMotors[index];
if (!motor->timerHardware || !motor->timerHardware->dmaRef) { if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
@ -81,12 +77,53 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
} }
if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) { if (HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, DSHOT_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */ /* Starting PWM generation Error */
return; return;
} }
} else { } else {
if (HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) { if (HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, DSHOT_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
}
}
void pwmWriteProShot(uint8_t index, uint16_t value)
{
motorDmaOutput_t * const motor = &dmaMotors[index];
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
return;
}
uint16_t packet = (value << 1) | (motor->requestTelemetry ? 1 : 0);
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row
// compute checksum
int csum = 0;
int csum_data = packet;
for (int i = 0; i < 3; i++) {
csum ^= csum_data; // xor data by nibbles
csum_data >>= 4;
}
csum &= 0xf;
// append checksum
packet = (packet << 4) | csum;
// generate pulses for Proshot
for (int i = 0; i < 4; i++) {
motor->dmaBuffer[i] = PROSHOT_BASE_SYMBOL + ((packet & 0xF000) >> 12) * PROSHOT_BIT_WIDTH; // Most significant nibble first
packet <<= 4; // Shift 4 bits
}
if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, PROSHOT_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
} else {
if (HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, PROSHOT_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */ /* Starting PWM generation Error */
return; return;
} }
@ -122,8 +159,8 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
RCC_ClockCmd(timerRCC(timer), ENABLE); RCC_ClockCmd(timerRCC(timer), ENABLE);
motor->TimHandle.Instance = timerHardware->tim; motor->TimHandle.Instance = timerHardware->tim;
motor->TimHandle.Init.Prescaler = (timerClock(timer) / getDshotHz(pwmProtocolType)) - 1;; motor->TimHandle.Init.Prescaler = (timerClock(timer) / getDshotHz(pwmProtocolType)) - 1;
motor->TimHandle.Init.Period = MOTOR_BITLENGTH; motor->TimHandle.Init.Period = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
motor->TimHandle.Init.RepetitionCounter = 0; motor->TimHandle.Init.RepetitionCounter = 0;
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;

View file

@ -74,6 +74,7 @@ extern uint8_t __config_end;
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/vcd.h" #include "drivers/vcd.h"
#include "drivers/light_led.h"
#include "fc/settings.h" #include "fc/settings.h"
#include "fc/cli.h" #include "fc/cli.h"
@ -2755,6 +2756,7 @@ const cliResourceValue_t resourceTable[] = {
{ OWNER_I2C_SCL, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagScl[0]), I2CDEV_COUNT }, { OWNER_I2C_SCL, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagScl[0]), I2CDEV_COUNT },
{ OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT }, { OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT },
#endif #endif
{ OWNER_LED, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, ioTags[0]), STATUS_LED_NUMBER },
#ifdef USE_SPEKTRUM_BIND #ifdef USE_SPEKTRUM_BIND
{ OWNER_RX_BIND, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_pin_override_ioTag), 0 }, { OWNER_RX_BIND, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_pin_override_ioTag), 0 },
{ OWNER_RX_BIND_PLUG, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_plug_ioTag), 0 }, { OWNER_RX_BIND_PLUG, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_plug_ioTag), 0 },
@ -2982,12 +2984,8 @@ static void backupConfigs(void)
{ {
// make copies of configs to do differencing // make copies of configs to do differencing
PG_FOREACH(pg) { PG_FOREACH(pg) {
if (pgIsProfile(pg)) {
//memcpy(pg->copy, pg->address, pg->size * MAX_PROFILE_COUNT);
} else {
memcpy(pg->copy, pg->address, pg->size); memcpy(pg->copy, pg->address, pg->size);
} }
}
configIsInCopy = true; configIsInCopy = true;
} }
@ -2995,12 +2993,8 @@ static void backupConfigs(void)
static void restoreConfigs(void) static void restoreConfigs(void)
{ {
PG_FOREACH(pg) { PG_FOREACH(pg) {
if (pgIsProfile(pg)) {
//memcpy(pg->address, pg->copy, pg->size * MAX_PROFILE_COUNT);
} else {
memcpy(pg->address, pg->copy, pg->size); memcpy(pg->address, pg->copy, pg->size);
} }
}
configIsInCopy = false; configIsInCopy = false;
} }

View file

@ -148,7 +148,6 @@ PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
#ifdef USE_PPM #ifdef USE_PPM
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0); PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
#endif #endif
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
#ifdef USE_FLASHFS #ifdef USE_FLASHFS
PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
@ -255,35 +254,6 @@ void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
#define SECOND_PORT_INDEX 1 #define SECOND_PORT_INDEX 1
#endif #endif
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
{
for (int i = 0; i < LED_NUMBER; i++) {
statusLedConfig->ledTags[i] = IO_TAG_NONE;
}
#ifdef LED0
statusLedConfig->ledTags[0] = IO_TAG(LED0);
#endif
#ifdef LED1
statusLedConfig->ledTags[1] = IO_TAG(LED1);
#endif
#ifdef LED2
statusLedConfig->ledTags[2] = IO_TAG(LED2);
#endif
statusLedConfig->polarity = 0
#ifdef LED0_INVERTED
| BIT(0)
#endif
#ifdef LED1_INVERTED
| BIT(1)
#endif
#ifdef LED2_INVERTED
| BIT(2)
#endif
;
}
#ifndef USE_OSD_SLAVE #ifndef USE_OSD_SLAVE
uint8_t getCurrentPidProfileIndex(void) uint8_t getCurrentPidProfileIndex(void)
{ {
@ -312,14 +282,12 @@ uint16_t getCurrentMinthrottle(void)
void resetConfigs(void) void resetConfigs(void)
{ {
pgResetAll(MAX_PROFILE_COUNT); pgResetAll();
#if defined(TARGET_CONFIG) #if defined(TARGET_CONFIG)
targetConfiguration(); targetConfiguration();
#endif #endif
pgActivateProfile(0);
#ifndef USE_OSD_SLAVE #ifndef USE_OSD_SLAVE
setPidProfile(0); setPidProfile(0);
setControlRateProfile(0); setControlRateProfile(0);
@ -337,7 +305,7 @@ void activateConfig(void)
resetAdjustmentStates(); resetAdjustmentStates();
useRcControlsConfig(modeActivationConditions(0), currentPidProfile); useRcControlsConfig(currentPidProfile);
useAdjustmentConfig(currentPidProfile); useAdjustmentConfig(currentPidProfile);
#ifdef GPS #ifdef GPS

View file

@ -207,16 +207,17 @@ void mwArm(void)
} }
if (!ARMING_FLAG(PREVENT_ARMING)) { if (!ARMING_FLAG(PREVENT_ARMING)) {
#ifdef USE_DSHOT #ifdef USE_DSHOT
//TODO: Use BOXDSHOTREVERSE here
if (!feature(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) { if (!feature(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) {
reverseMotors = false; reverseMotors = false;
for (unsigned index = 0; index < getMotorCount(); index++) { for (unsigned index = 0; index < getMotorCount(); index++) {
pwmWriteDshotCommand(index, DSHOT_CMD_ROTATE_NORMAL); pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_NORMAL);
} }
} }
if (!feature(FEATURE_3D) && IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) { if (!feature(FEATURE_3D) && IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) {
reverseMotors = true; reverseMotors = true;
for (unsigned index = 0; index < getMotorCount(); index++) { for (unsigned index = 0; index < getMotorCount(); index++) {
pwmWriteDshotCommand(index, DSHOT_CMD_ROTATE_REVERSE); pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED);
} }
} }
#endif #endif

View file

@ -223,7 +223,9 @@ void init(void)
targetPreInit(); targetPreInit();
#endif #endif
#if !defined(UNIT_TEST) && !defined(USE_FAKE_LED)
ledInit(statusLedConfig()); ledInit(statusLedConfig());
#endif
LED2_ON; LED2_ON;
#ifdef USE_EXTI #ifdef USE_EXTI

View file

@ -29,6 +29,7 @@
#include "build/version.h" #include "build/version.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/bitarray.h"
#include "common/color.h" #include "common/color.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/streambuf.h" #include "common/streambuf.h"
@ -59,6 +60,8 @@
#include "fc/fc_msp.h" #include "fc/fc_msp.h"
#include "fc/fc_rc.h" #include "fc/fc_rc.h"
#include "fc/rc_adjustments.h" #include "fc/rc_adjustments.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/altitude.h" #include "flight/altitude.h"
@ -110,12 +113,13 @@
#endif #endif
#define STATIC_ASSERT(condition, name) \ #define STATIC_ASSERT(condition, name) \
typedef char assert_failed_ ## name [(condition) ? 1 : -1 ] typedef char assert_failed_ ## name [(condition) ? 1 : -1 ] __attribute__((unused))
static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller. static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#ifndef USE_OSD_SLAVE #ifndef USE_OSD_SLAVE
// permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM!
static const box_t boxes[CHECKBOX_ITEM_COUNT] = { static const box_t boxes[CHECKBOX_ITEM_COUNT] = {
{ BOXARM, "ARM", 0 }, { BOXARM, "ARM", 0 },
{ BOXANGLE, "ANGLE", 1 }, { BOXANGLE, "ANGLE", 1 },
@ -152,9 +156,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT] = {
}; };
// mask of enabled IDs, calculated on startup based on enabled features. boxId_e is used as bit index // mask of enabled IDs, calculated on startup based on enabled features. boxId_e is used as bit index
static uint32_t activeBoxIds;
// check that all boxId_e values fit static boxBitmask_t activeBoxIds;
STATIC_ASSERT(sizeof(activeBoxIds) * 8 >= CHECKBOX_ITEM_COUNT, CHECKBOX_ITEMS_wont_fit_in_activeBoxIds);
static const char pidnames[] = static const char pidnames[] =
"ROLL;" "ROLL;"
@ -276,23 +279,41 @@ const box_t *findBoxByPermanentId(uint8_t permanentId)
return NULL; return NULL;
} }
static void serializeBoxNamesReply(sbuf_t *dst) static bool activeBoxIdGet(boxId_e boxId)
{ {
for (boxId_e id = 0; id < CHECKBOX_ITEM_COUNT; id++) { if(boxId > sizeof(activeBoxIds) * 8)
if(activeBoxIds & (1 << id)) { return false;
const box_t *box = findBoxByBoxId(id); return bitArrayGet(&activeBoxIds, boxId);
sbufWriteString(dst, box->boxName);
sbufWriteU8(dst, ';');
}
}
} }
static void serializeBoxIdsReply(sbuf_t *dst)
// callcack for box serialization
typedef void serializeBoxFn(sbuf_t *dst, const box_t *box);
static void serializeBoxNameFn(sbuf_t *dst, const box_t *box)
{
sbufWriteString(dst, box->boxName);
sbufWriteU8(dst, ';');
}
static void serializeBoxPermanentIdFn(sbuf_t *dst, const box_t *box)
{ {
for (boxId_e id = 0; id < CHECKBOX_ITEM_COUNT; id++) {
if(activeBoxIds & (1 << id)) {
const box_t *box = findBoxByBoxId(id);
sbufWriteU8(dst, box->permanentId); sbufWriteU8(dst, box->permanentId);
}
// serialize 'page' of boxNames.
// Each page contains at most 32 boxes
static void serializeBoxReply(sbuf_t *dst, int page, serializeBoxFn *serializeBox)
{
unsigned boxIdx = 0;
unsigned pageStart = page * 32;
unsigned pageEnd = pageStart + 32;
for (boxId_e id = 0; id < CHECKBOX_ITEM_COUNT; id++) {
if (activeBoxIdGet(id)) {
if (boxIdx >= pageStart && boxIdx < pageEnd) {
(*serializeBox)(dst, findBoxByBoxId(id));
}
boxIdx++; // count active boxes
} }
} }
} }
@ -300,9 +321,11 @@ static void serializeBoxIdsReply(sbuf_t *dst)
void initActiveBoxIds(void) void initActiveBoxIds(void)
{ {
// calculate used boxes based on features and set corresponding activeBoxIds bits // calculate used boxes based on features and set corresponding activeBoxIds bits
uint32_t ena = 0; // temporary variable to collect result boxBitmask_t ena; // temporary variable to collect result
memset(&ena, 0, sizeof(ena));
// macro to enable boxId (BoxidMaskEnable). Reference to ena is hidden, local use only // macro to enable boxId (BoxidMaskEnable). Reference to ena is hidden, local use only
#define BME(boxId) do { ena |= (1 << (boxId)); } while(0) #define BME(boxId) do { bitArraySet(&ena, boxId); } while(0)
BME(BOXARM); BME(BOXARM);
if (!feature(FEATURE_AIRMODE)) { if (!feature(FEATURE_AIRMODE)) {
@ -370,6 +393,7 @@ void initActiveBoxIds(void)
BME(BOXFPVANGLEMIX); BME(BOXFPVANGLEMIX);
//TODO: Split this into BOX3DDISABLESWITCH and BOXDSHOTREVERSE
BME(BOX3DDISABLESWITCH); BME(BOX3DDISABLESWITCH);
if (feature(FEATURE_SERVO_TILT)) { if (feature(FEATURE_SERVO_TILT)) {
@ -398,63 +422,69 @@ void initActiveBoxIds(void)
#undef BME #undef BME
// check that all enabled IDs are in boxes array (check may be skipped when using findBoxById() functions) // check that all enabled IDs are in boxes array (check may be skipped when using findBoxById() functions)
for(boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++) for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++)
if((ena & (1 << boxId)) if (bitArrayGet(&ena, boxId)
&& findBoxByBoxId(boxId) == NULL) && findBoxByBoxId(boxId) == NULL)
ena &= ~ (1 << boxId); // this should not happen, but handle it gracefully bitArrayClr(&ena, boxId); // this should not happen, but handle it gracefully
activeBoxIds = ena; // set global variable activeBoxIds = ena; // set global variable
} }
static uint32_t packFlightModeFlags(void) // pack used flightModeFlags into supplied array
// returns number of bits used
static int packFlightModeFlags(boxBitmask_t *mspFlightModeFlags)
{ {
// Serialize the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES // Serialize the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES
memset(mspFlightModeFlags, 0, sizeof(boxBitmask_t));
uint32_t boxEnabledMask = 0; // enabled BOXes, bits indexed by boxId_e // enabled BOXes, bits indexed by boxId_e
boxBitmask_t boxEnabledMask;
memset(&boxEnabledMask, 0, sizeof(boxEnabledMask));
// enable BOXes dependent on FLIGHT_MODE, use mapping table (from runtime_config.h) // enable BOXes dependent on FLIGHT_MODE, use mapping table (from runtime_config.h)
// flightMode_boxId_map[HORIZON_MODE] == BOXHORIZON // flightMode_boxId_map[HORIZON_MODE] == BOXHORIZON
static const int8_t flightMode_boxId_map[] = FLIGHT_MODE_BOXID_MAP_INITIALIZER; static const int8_t flightMode_boxId_map[] = FLIGHT_MODE_BOXID_MAP_INITIALIZER;
flightModeFlags_e flightModeCopyMask = ~0; // only modes with bit set will be copied flightModeFlags_e flightModeCopyMask = ~0; // only modes with bit set will be copied
for(unsigned i = 0; i < ARRAYLEN(flightMode_boxId_map); i++) { for (unsigned i = 0; i < ARRAYLEN(flightMode_boxId_map); i++) {
if(flightMode_boxId_map[i] != -1 // boxId_e does exist for this FLIGHT_MODE if (flightMode_boxId_map[i] != -1 // boxId_e does exist for this FLIGHT_MODE
&& (flightModeCopyMask & (1 << i)) // this flightmode is copy is enabled && (flightModeCopyMask & (1 << i)) // this flightmode is copy is enabled
&& FLIGHT_MODE(1 << i)) { // this flightmode is active && FLIGHT_MODE(1 << i)) { // this flightmode is active
boxEnabledMask |= (1 << flightMode_boxId_map[i]); bitArraySet(&boxEnabledMask, flightMode_boxId_map[i]);
} }
} }
// enable BOXes dependent on rcMode bits, indexes are the same. // enable BOXes dependent on rcMode bits, indexes are the same.
// only subset of BOXes depend on rcMode, use mask to select them // only subset of BOXes depend on rcMode, use mask to select them
#define BM(x) (1 << (x)) #define BM(x) (1ULL << (x))
const uint32_t rcModeCopyMask = BM(BOXHEADADJ) | BM(BOXCAMSTAB) | BM(BOXCAMTRIG) | BM(BOXBEEPERON) // limited to 64 BOXes now to keep code simple
const uint64_t rcModeCopyMask = BM(BOXHEADADJ) | BM(BOXCAMSTAB) | BM(BOXCAMTRIG) | BM(BOXBEEPERON)
| BM(BOXLEDMAX) | BM(BOXLEDLOW) | BM(BOXLLIGHTS) | BM(BOXCALIB) | BM(BOXGOV) | BM(BOXOSD) | BM(BOXLEDMAX) | BM(BOXLEDLOW) | BM(BOXLLIGHTS) | BM(BOXCALIB) | BM(BOXGOV) | BM(BOXOSD)
| BM(BOXTELEMETRY) | BM(BOXGTUNE) | BM(BOXBLACKBOX) | BM(BOXBLACKBOXERASE) | BM(BOXAIRMODE) | BM(BOXTELEMETRY) | BM(BOXGTUNE) | BM(BOXBLACKBOX) | BM(BOXBLACKBOXERASE) | BM(BOXAIRMODE)
| BM(BOXANTIGRAVITY) | BM(BOXFPVANGLEMIX); | BM(BOXANTIGRAVITY) | BM(BOXFPVANGLEMIX);
for(unsigned i = 0; i < sizeof(rcModeCopyMask) * 8; i++) { STATIC_ASSERT(sizeof(rcModeCopyMask) * 8 >= CHECKBOX_ITEM_COUNT, copy_mask_too_small_for_boxes);
if((rcModeCopyMask & BM(i)) // mode copy is enabled for (unsigned i = 0; i < CHECKBOX_ITEM_COUNT; i++) {
if ((rcModeCopyMask & BM(i)) // mode copy is enabled
&& IS_RC_MODE_ACTIVE(i)) { // mode is active && IS_RC_MODE_ACTIVE(i)) { // mode is active
boxEnabledMask |= (1 << i); bitArraySet(&boxEnabledMask, i);
} }
} }
#undef BM #undef BM
// copy ARM state // copy ARM state
if(ARMING_FLAG(ARMED)) if (ARMING_FLAG(ARMED))
boxEnabledMask |= (1 << BOXARM); bitArraySet(&boxEnabledMask, BOXARM);
// map boxId_e enabled bits to MSP status indexes // map boxId_e enabled bits to MSP status indexes
// only active boxIds are sent in status over MSP, other bits are not counted // only active boxIds are sent in status over MSP, other bits are not counted
uint32_t mspBoxEnabledMask = 0;
unsigned mspBoxIdx = 0; // index of active boxId (matches sent permanentId and boxNames) unsigned mspBoxIdx = 0; // index of active boxId (matches sent permanentId and boxNames)
for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++) { for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++) {
if(activeBoxIds & (1 << boxId)) { if (activeBoxIdGet(boxId)) {
if (boxEnabledMask & (1 << boxId)) if (bitArrayGet(&boxEnabledMask, boxId))
mspBoxEnabledMask |= 1 << mspBoxIdx; // box is enabled bitArraySet(mspFlightModeFlags, mspBoxIdx); // box is enabled
mspBoxIdx++; // box is active, count it mspBoxIdx++; // box is active, count it
} }
} }
// return count of used bits
return mspBoxEnabledMask; return mspBoxIdx;
} }
static void serializeSDCardSummaryReply(sbuf_t *dst) static void serializeSDCardSummaryReply(sbuf_t *dst)
@ -829,20 +859,6 @@ static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostPro
switch (cmdMSP) { switch (cmdMSP) {
case MSP_STATUS_EX: case MSP_STATUS_EX:
sbufWriteU16(dst, getTaskDeltaTime(TASK_SERIAL));
#ifdef USE_I2C
sbufWriteU16(dst, i2cGetErrorCounter());
#else
sbufWriteU16(dst, 0);
#endif
sbufWriteU16(dst, 0); // sensors
sbufWriteU32(dst, 0); // flight modes
sbufWriteU8(dst, 0); // profile
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
sbufWriteU8(dst, 1); // max profiles
sbufWriteU8(dst, 0); // control rate profile
break;
case MSP_STATUS: case MSP_STATUS:
sbufWriteU16(dst, getTaskDeltaTime(TASK_SERIAL)); sbufWriteU16(dst, getTaskDeltaTime(TASK_SERIAL));
#ifdef USE_I2C #ifdef USE_I2C
@ -854,7 +870,12 @@ static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostPro
sbufWriteU32(dst, 0); // flight modes sbufWriteU32(dst, 0); // flight modes
sbufWriteU8(dst, 0); // profile sbufWriteU8(dst, 0); // profile
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100)); sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
if (cmdMSP == MSP_STATUS_EX) {
sbufWriteU8(dst, 1); // max profiles
sbufWriteU8(dst, 0); // control rate profile
} else {
sbufWriteU16(dst, 0); // gyro cycle time sbufWriteU16(dst, 0); // gyro cycle time
}
break; break;
default: default:
@ -871,6 +892,11 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
switch (cmdMSP) { switch (cmdMSP) {
case MSP_STATUS_EX: case MSP_STATUS_EX:
case MSP_STATUS:
{
boxBitmask_t flightModeFlags;
const int flagBits = packFlightModeFlags(&flightModeFlags);
sbufWriteU16(dst, getTaskDeltaTime(TASK_GYROPID)); sbufWriteU16(dst, getTaskDeltaTime(TASK_GYROPID));
#ifdef USE_I2C #ifdef USE_I2C
sbufWriteU16(dst, i2cGetErrorCounter()); sbufWriteU16(dst, i2cGetErrorCounter());
@ -878,25 +904,23 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
#endif #endif
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4);
sbufWriteU32(dst, packFlightModeFlags()); sbufWriteData(dst, &flightModeFlags, 4); // unconditional part of flags, first 32 bits
sbufWriteU8(dst, getCurrentPidProfileIndex()); sbufWriteU8(dst, getCurrentPidProfileIndex());
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100)); sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
if (cmdMSP == MSP_STATUS_EX) {
sbufWriteU8(dst, MAX_PROFILE_COUNT); sbufWriteU8(dst, MAX_PROFILE_COUNT);
sbufWriteU8(dst, getCurrentControlRateProfileIndex()); sbufWriteU8(dst, getCurrentControlRateProfileIndex());
break; } else { // MSP_STATUS
case MSP_STATUS:
sbufWriteU16(dst, getTaskDeltaTime(TASK_GYROPID));
#ifdef USE_I2C
sbufWriteU16(dst, i2cGetErrorCounter());
#else
sbufWriteU16(dst, 0);
#endif
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4);
sbufWriteU32(dst, packFlightModeFlags());
sbufWriteU8(dst, getCurrentPidProfileIndex());
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
sbufWriteU16(dst, 0); // gyro cycle time sbufWriteU16(dst, 0); // gyro cycle time
}
// write flightModeFlags header. Lowest 4 bits contain number of bytes that follow
// header is emited even when all bits fit into 32 bits to allow future extension
int byteCount = (flagBits - 32 + 7) / 8; // 32 already stored, round up
byteCount = constrain(byteCount, 0, 15); // limit to 16 bytes (128 bits)
sbufWriteU8(dst, byteCount);
sbufWriteData(dst, ((uint8_t*)&flightModeFlags) + 4, byteCount);
}
break; break;
case MSP_RAW_IMU: case MSP_RAW_IMU:
@ -1058,14 +1082,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
} }
break; break;
case MSP_BOXNAMES:
serializeBoxNamesReply(dst);
break;
case MSP_BOXIDS:
serializeBoxIdsReply(dst);
break;
case MSP_MOTOR_CONFIG: case MSP_MOTOR_CONFIG:
sbufWriteU16(dst, motorConfig()->minthrottle); sbufWriteU16(dst, motorConfig()->minthrottle);
sbufWriteU16(dst, motorConfig()->maxthrottle); sbufWriteU16(dst, motorConfig()->maxthrottle);
@ -1358,6 +1374,29 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
} }
return true; return true;
} }
static mspResult_e mspFcProcessOutCommandWithArg(uint8_t cmdMSP, sbuf_t *arg, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn)
{
UNUSED(mspPostProcessFn);
switch (cmdMSP) {
case MSP_BOXNAMES:
{
const int page = sbufBytesRemaining(arg) ? sbufReadU8(arg) : 0;
serializeBoxReply(dst, page, &serializeBoxNameFn);
}
break;
case MSP_BOXIDS:
{
const int page = sbufBytesRemaining(arg) ? sbufReadU8(arg) : 0;
serializeBoxReply(dst, page, &serializeBoxPermanentIdFn);
}
break;
default:
return MSP_RESULT_CMD_UNKNOWN;
}
return MSP_RESULT_ACK;
}
#endif #endif
#ifdef GPS #ifdef GPS
@ -1495,7 +1534,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
mac->range.startStep = sbufReadU8(src); mac->range.startStep = sbufReadU8(src);
mac->range.endStep = sbufReadU8(src); mac->range.endStep = sbufReadU8(src);
useRcControlsConfig(modeActivationConditions(0), currentPidProfile); useRcControlsConfig(currentPidProfile);
} else { } else {
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
} }
@ -2176,6 +2215,8 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
#ifndef USE_OSD_SLAVE #ifndef USE_OSD_SLAVE
} else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { } else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
ret = MSP_RESULT_ACK; ret = MSP_RESULT_ACK;
} else if ((ret = mspFcProcessOutCommandWithArg(cmdMSP, src, dst, mspPostProcessFn)) != MSP_RESULT_CMD_UNKNOWN) {
/* ret */;
#endif #endif
#ifdef USE_OSD_SLAVE #ifdef USE_OSD_SLAVE
} else if (mspOsdSlaveProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { } else if (mspOsdSlaveProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {

View file

@ -18,12 +18,12 @@
#pragma once #pragma once
#include "msp/msp.h" #include "msp/msp.h"
#include "rc_controls.h" #include "fc/rc_modes.h"
typedef struct box_e { typedef struct box_e {
const uint8_t boxId; // see boxId_e const uint8_t boxId; // see boxId_e
const char *boxName; // GUI-readable box name const char *boxName; // GUI-readable box name
const uint8_t permanentId; // const uint8_t permanentId; // permanent ID used to identify BOX. This ID is unique for one function, DO NOT REUSE IT
} box_t; } box_t;
const box_t *findBoxByBoxId(boxId_e boxId); const box_t *findBoxByBoxId(boxId_e boxId);

View file

@ -37,6 +37,7 @@
#include "fc/fc_core.h" #include "fc/fc_core.h"
#include "fc/fc_rc.h" #include "fc/fc_rc.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "rx/rx.h" #include "rx/rx.h"

View file

@ -88,7 +88,7 @@ static void blackboxLogInflightAdjustmentEventFloat(adjustmentFunction_e adjustm
} }
#endif #endif
static uint8_t adjustmentStateMask = 0; STATIC_UNIT_TESTED uint8_t adjustmentStateMask = 0;
#define MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex) adjustmentStateMask |= (1 << adjustmentIndex) #define MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex) adjustmentStateMask |= (1 << adjustmentIndex)
#define MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex) adjustmentStateMask &= ~(1 << adjustmentIndex) #define MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex) adjustmentStateMask &= ~(1 << adjustmentIndex)
@ -199,9 +199,9 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU
#define ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET 1 #define ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET 1
static adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT]; STATIC_UNIT_TESTED adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
static void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig) STATIC_UNIT_TESTED void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig)
{ {
adjustmentState_t *adjustmentState = &adjustmentStates[index]; adjustmentState_t *adjustmentState = &adjustmentStates[index];
@ -386,10 +386,7 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig)
continue; continue;
} }
const int32_t signedDiff = now - adjustmentState->timeoutAt; if (cmp32(now, adjustmentState->timeoutAt) >= 0) {
const bool canResetReadyStates = signedDiff >= 0L;
if (canResetReadyStates) {
adjustmentState->timeoutAt = now + RESET_FREQUENCY_2HZ; adjustmentState->timeoutAt = now + RESET_FREQUENCY_2HZ;
MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex); MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex);
} }

View file

@ -19,7 +19,7 @@
#include <stdbool.h> #include <stdbool.h>
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "fc/rc_controls.h" #include "fc/rc_modes.h"
typedef enum { typedef enum {
ADJUSTMENT_NONE = 0, ADJUSTMENT_NONE = 0,

View file

@ -65,8 +65,6 @@ static bool isUsingSticksToArm = true;
float rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW float rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e
PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 0);
PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
@ -85,15 +83,13 @@ PG_RESET_TEMPLATE(armingConfig_t, armingConfig,
.auto_disarm_delay = 5 .auto_disarm_delay = 5
); );
PG_REGISTER_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions, PG_MODE_ACTIVATION_PROFILE, 0); PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig,
bool isAirmodeActive(void) { .deadband3d_low = 1406,
return (IS_RC_MODE_ACTIVE(BOXAIRMODE) || feature(FEATURE_AIRMODE)); .deadband3d_high = 1514,
} .neutral3d = 1460,
.deadband3d_throttle = 50
bool isAntiGravityModeActive(void) { );
return (IS_RC_MODE_ACTIVE(BOXANTIGRAVITY) || feature(FEATURE_ANTI_GRAVITY));
}
bool isUsingSticksForArming(void) bool isUsingSticksForArming(void)
{ {
@ -308,51 +304,13 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
} }
bool isModeActivationConditionPresent(const modeActivationCondition_t *modeActivationConditions, boxId_e modeId)
{
uint8_t index;
for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
const modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index];
if (modeActivationCondition->modeId == modeId && IS_RANGE_USABLE(&modeActivationCondition->range)) {
return true;
}
}
return false;
}
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) {
if (!IS_RANGE_USABLE(range)) {
return false;
}
const uint16_t channelValue = constrain(rcData[auxChannelIndex + NON_AUX_CHANNEL_COUNT], CHANNEL_RANGE_MIN, CHANNEL_RANGE_MAX - 1);
return (channelValue >= 900 + (range->startStep * 25) &&
channelValue < 900 + (range->endStep * 25));
}
void updateActivatedModes(void)
{
rcModeActivationMask = 0;
for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(index);
if (isRangeActive(modeActivationCondition->auxChannelIndex, &modeActivationCondition->range)) {
ACTIVATE_RC_MODE(modeActivationCondition->modeId);
}
}
}
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc) { int32_t getRcStickDeflection(int32_t axis, uint16_t midrc) {
return MIN(ABS(rcData[axis] - midrc), 500); return MIN(ABS(rcData[axis] - midrc), 500);
} }
void useRcControlsConfig(const modeActivationCondition_t *modeActivationConditions, pidProfile_t *pidProfileToUse) void useRcControlsConfig(pidProfile_t *pidProfileToUse)
{ {
pidProfile = pidProfileToUse; pidProfile = pidProfileToUse;
isUsingSticksToArm = !isModeActivationConditionPresent(modeActivationConditions, BOXARM); isUsingSticksToArm = !isModeActivationConditionPresent(BOXARM);
} }

View file

@ -21,47 +21,6 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
typedef enum {
BOXARM = 0,
BOXANGLE,
BOXHORIZON,
BOXBARO,
BOXANTIGRAVITY,
BOXMAG,
BOXHEADFREE,
BOXHEADADJ,
BOXCAMSTAB,
BOXCAMTRIG,
BOXGPSHOME,
BOXGPSHOLD,
BOXPASSTHRU,
BOXBEEPERON,
BOXLEDMAX,
BOXLEDLOW,
BOXLLIGHTS,
BOXCALIB,
BOXGOV,
BOXOSD,
BOXTELEMETRY,
BOXGTUNE,
BOXSONAR,
BOXSERVO1,
BOXSERVO2,
BOXSERVO3,
BOXBLACKBOX,
BOXFAILSAFE,
BOXAIRMODE,
BOX3DDISABLESWITCH,
BOXFPVANGLEMIX,
BOXBLACKBOXERASE,
CHECKBOX_ITEM_COUNT
} boxId_e;
extern uint32_t rcModeActivationMask;
#define IS_RC_MODE_ACTIVE(modeId) ((1 << (modeId)) & rcModeActivationMask)
#define ACTIVATE_RC_MODE(modeId) (rcModeActivationMask |= (1 << modeId))
typedef enum rc_alias { typedef enum rc_alias {
ROLL = 0, ROLL = 0,
PITCH, PITCH,
@ -109,17 +68,6 @@ typedef enum {
#define THR_CE (3 << (2 * THROTTLE)) #define THR_CE (3 << (2 * THROTTLE))
#define THR_HI (2 << (2 * THROTTLE)) #define THR_HI (2 << (2 * THROTTLE))
#define MAX_MODE_ACTIVATION_CONDITION_COUNT 20
#define CHANNEL_RANGE_MIN 900
#define CHANNEL_RANGE_MAX 2100
#define MODE_STEP_TO_CHANNEL_VALUE(step) (CHANNEL_RANGE_MIN + 25 * step)
#define CHANNEL_VALUE_TO_STEP(channelValue) ((constrain(channelValue, CHANNEL_RANGE_MIN, CHANNEL_RANGE_MAX) - CHANNEL_RANGE_MIN) / 25)
#define MIN_MODE_RANGE_STEP 0
#define MAX_MODE_RANGE_STEP ((CHANNEL_RANGE_MAX - CHANNEL_RANGE_MIN) / 25)
// Roll/pitch rates are a proportion used for mixing, so it tops out at 1.0: // Roll/pitch rates are a proportion used for mixing, so it tops out at 1.0:
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 100 #define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 100
@ -128,29 +76,6 @@ typedef enum {
#define CONTROL_RATE_CONFIG_TPA_MAX 100 #define CONTROL_RATE_CONFIG_TPA_MAX 100
// steps are 25 apart
// a value of 0 corresponds to a channel value of 900 or less
// a value of 48 corresponds to a channel value of 2100 or more
// 48 steps between 900 and 1200
typedef struct channelRange_s {
uint8_t startStep;
uint8_t endStep;
} channelRange_t;
typedef struct modeActivationCondition_s {
boxId_e modeId;
uint8_t auxChannelIndex;
channelRange_t range;
} modeActivationCondition_t;
PG_DECLARE_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions);
typedef struct modeActivationProfile_s {
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
} modeActivationProfile_t;
#define IS_RANGE_USABLE(range) ((range)->startStep < (range)->endStep)
extern float rcCommand[4]; extern float rcCommand[4];
typedef struct rcControlsConfig_s { typedef struct rcControlsConfig_s {
@ -186,15 +111,9 @@ bool areSticksInApModePosition(uint16_t ap_mode);
throttleStatus_e calculateThrottleStatus(void); throttleStatus_e calculateThrottleStatus(void);
void processRcStickPositions(throttleStatus_e throttleStatus); void processRcStickPositions(throttleStatus_e throttleStatus);
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range);
void updateActivatedModes(void);
bool isAirmodeActive(void);
bool isAntiGravityModeActive(void);
bool isUsingSticksForArming(void); bool isUsingSticksForArming(void);
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc); int32_t getRcStickDeflection(int32_t axis, uint16_t midrc);
bool isModeActivationConditionPresent(const modeActivationCondition_t *modeActivationConditions, boxId_e modeId);
struct pidProfile_s; struct pidProfile_s;
void useRcControlsConfig(const modeActivationCondition_t *modeActivationConditions, struct pidProfile_s *pidProfileToUse); struct modeActivationCondition_s;
void useRcControlsConfig(struct pidProfile_s *pidProfileToUse);

101
src/main/fc/rc_modes.c Normal file
View file

@ -0,0 +1,101 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "rc_modes.h"
#include "common/bitarray.h"
#include "common/maths.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "rx/rx.h"
boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e
PG_REGISTER_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions,
PG_MODE_ACTIVATION_PROFILE, 0);
bool IS_RC_MODE_ACTIVE(boxId_e boxId)
{
return bitArrayGet(&rcModeActivationMask, boxId);
}
void rcModeUpdate(boxBitmask_t *newState)
{
rcModeActivationMask = *newState;
}
bool isAirmodeActive(void) {
return (IS_RC_MODE_ACTIVE(BOXAIRMODE) || feature(FEATURE_AIRMODE));
}
bool isAntiGravityModeActive(void) {
return (IS_RC_MODE_ACTIVE(BOXANTIGRAVITY) || feature(FEATURE_ANTI_GRAVITY));
}
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) {
if (!IS_RANGE_USABLE(range)) {
return false;
}
const uint16_t channelValue = constrain(rcData[auxChannelIndex + NON_AUX_CHANNEL_COUNT], CHANNEL_RANGE_MIN, CHANNEL_RANGE_MAX - 1);
return (channelValue >= 900 + (range->startStep * 25) &&
channelValue < 900 + (range->endStep * 25));
}
void updateActivatedModes(void)
{
boxBitmask_t newMask;
memset(&newMask, 0, sizeof(newMask));
for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(index);
if (isRangeActive(modeActivationCondition->auxChannelIndex, &modeActivationCondition->range)) {
boxId_e mode = modeActivationCondition->modeId;
if (mode < CHECKBOX_ITEM_COUNT)
bitArraySet(&newMask, mode);
}
}
rcModeUpdate(&newMask);
}
bool isModeActivationConditionPresent(boxId_e modeId)
{
uint8_t index;
for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(index);
if (modeActivationCondition->modeId == modeId && IS_RANGE_USABLE(&modeActivationCondition->range)) {
return true;
}
}
return false;
}

105
src/main/fc/rc_modes.h Normal file
View file

@ -0,0 +1,105 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdbool.h>
#include "config/parameter_group.h"
typedef enum {
BOXARM = 0,
BOXANGLE,
BOXHORIZON,
BOXBARO,
BOXANTIGRAVITY,
BOXMAG,
BOXHEADFREE,
BOXHEADADJ,
BOXCAMSTAB,
BOXCAMTRIG,
BOXGPSHOME,
BOXGPSHOLD,
BOXPASSTHRU,
BOXBEEPERON,
BOXLEDMAX,
BOXLEDLOW,
BOXLLIGHTS,
BOXCALIB,
BOXGOV,
BOXOSD,
BOXTELEMETRY,
BOXGTUNE,
BOXSONAR,
BOXSERVO1,
BOXSERVO2,
BOXSERVO3,
BOXBLACKBOX,
BOXFAILSAFE,
BOXAIRMODE,
BOX3DDISABLESWITCH,
BOXFPVANGLEMIX,
BOXBLACKBOXERASE,
CHECKBOX_ITEM_COUNT
} boxId_e;
// type to hold enough bits for CHECKBOX_ITEM_COUNT. Struct used for value-like behavior
typedef struct { uint32_t bits[(CHECKBOX_ITEM_COUNT + 31) / 32]; } boxBitmask_t;
#define MAX_MODE_ACTIVATION_CONDITION_COUNT 20
#define CHANNEL_RANGE_MIN 900
#define CHANNEL_RANGE_MAX 2100
#define MODE_STEP_TO_CHANNEL_VALUE(step) (CHANNEL_RANGE_MIN + 25 * step)
#define CHANNEL_VALUE_TO_STEP(channelValue) ((constrain(channelValue, CHANNEL_RANGE_MIN, CHANNEL_RANGE_MAX) - CHANNEL_RANGE_MIN) / 25)
#define MIN_MODE_RANGE_STEP 0
#define MAX_MODE_RANGE_STEP ((CHANNEL_RANGE_MAX - CHANNEL_RANGE_MIN) / 25)
// steps are 25 apart
// a value of 0 corresponds to a channel value of 900 or less
// a value of 48 corresponds to a channel value of 2100 or more
// 48 steps between 900 and 1200
typedef struct channelRange_s {
uint8_t startStep;
uint8_t endStep;
} channelRange_t;
typedef struct modeActivationCondition_s {
boxId_e modeId;
uint8_t auxChannelIndex;
channelRange_t range;
} modeActivationCondition_t;
PG_DECLARE_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions);
typedef struct modeActivationProfile_s {
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
} modeActivationProfile_t;
#define IS_RANGE_USABLE(range) ((range)->startStep < (range)->endStep)
bool IS_RC_MODE_ACTIVE(boxId_e boxId);
void rcModeUpdate(boxBitmask_t *newState);
bool isAirmodeActive(void);
bool isAntiGravityModeActive(void);
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range);
void updateActivatedModes(void);
bool isModeActivationConditionPresent(boxId_e modeId);

View file

@ -36,10 +36,13 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
#include "drivers/light_led.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
#include "fc/fc_core.h" #include "fc/fc_core.h"
#include "fc/rc_adjustments.h" #include "fc/rc_adjustments.h"
#include "fc/rc_controls.h"
#include "fc/settings.h" #include "fc/settings.h"
#include "flight/altitude.h" #include "flight/altitude.h"
@ -713,6 +716,7 @@ const clivalue_t valueTable[] = {
#ifdef USE_ESC_SENSOR #ifdef USE_ESC_SENSOR
{ "esc_sensor_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ESC_SENSOR_CONFIG, offsetof(escSensorConfig_t, halfDuplex) }, { "esc_sensor_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ESC_SENSOR_CONFIG, offsetof(escSensorConfig_t, halfDuplex) },
#endif #endif
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
}; };
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable); const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);

View file

@ -33,6 +33,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/altitude.h" #include "flight/altitude.h"

View file

@ -31,6 +31,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"

View file

@ -40,6 +40,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/fc_core.h" #include "fc/fc_core.h"
@ -52,16 +53,6 @@
#include "sensors/battery.h" #include "sensors/battery.h"
PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig,
.deadband3d_low = 1406,
.deadband3d_high = 1514,
.neutral3d = 1460,
.deadband3d_throttle = 50
);
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 0);
#ifndef TARGET_DEFAULT_MIXER #ifndef TARGET_DEFAULT_MIXER

View file

@ -37,7 +37,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/fc_core.h" #include "fc/fc_core.h"
#include "fc/rc_controls.h" #include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/imu.h" #include "flight/imu.h"

View file

@ -38,6 +38,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/imu.h" #include "flight/imu.h"

View file

@ -44,6 +44,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "fc/rc_controls.h" #include "fc/rc_modes.h"
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10 #define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10

View file

@ -23,7 +23,8 @@
typedef enum { typedef enum {
MSP_RESULT_ACK = 1, MSP_RESULT_ACK = 1,
MSP_RESULT_ERROR = -1, MSP_RESULT_ERROR = -1,
MSP_RESULT_NO_REPLY = 0 MSP_RESULT_NO_REPLY = 0,
MSP_RESULT_CMD_UNKNOWN = -2, // don't know how to process command, try next handler
} mspResult_e; } mspResult_e;
typedef enum { typedef enum {

View file

@ -41,6 +41,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
@ -297,6 +298,7 @@ void rxInit(void)
rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec; rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec;
// Initialize ARM switch to OFF position when arming via switch is defined // Initialize ARM switch to OFF position when arming via switch is defined
// TODO - move to rc_mode.c
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) { for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(i); const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(i);
if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) { if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) {

View file

@ -211,7 +211,6 @@ void currentMeterESCReadCombined(currentMeter_t *meter)
meter->amperageLatest = currentMeterESCState.amperage; meter->amperageLatest = currentMeterESCState.amperage;
meter->amperage = currentMeterESCState.amperage; meter->amperage = currentMeterESCState.amperage;
meter->mAhDrawn = currentMeterESCState.mAhDrawn; meter->mAhDrawn = currentMeterESCState.mAhDrawn;
currentMeterReset(meter);
} }
void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter) void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter)

View file

@ -21,7 +21,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB5 // Blue LED - PB5 #define LED0_PIN PB5 // Blue LED - PB5
#define BEEPER PA0 #define BEEPER PA0

View file

@ -22,8 +22,8 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define CONFIG_PREFER_ACC_ON #define CONFIG_PREFER_ACC_ON
#define LED0 PB3 #define LED0_PIN PB3
#define LED1 PB4 #define LED1_PIN PB4
#define BEEPER PA12 #define BEEPER PA12
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -22,8 +22,8 @@
#define BRUSHED_ESC_AUTODETECT #define BRUSHED_ESC_AUTODETECT
#define LED0 PB3 #define LED0_PIN PB3
#define LED1 PB4 #define LED1_PIN PB4
#define BEEPER PA12 #define BEEPER PA12

View file

@ -57,7 +57,7 @@ void targetConfiguration(void)
{ {
/* depending on revision ... depends on the LEDs to be utilised. */ /* depending on revision ... depends on the LEDs to be utilised. */
if (hardwareRevision == AFF3_REV_2) { if (hardwareRevision == AFF3_REV_2) {
statusLedConfigMutable()->polarity = 0 statusLedConfigMutable()->inversion = 0
#ifdef LED0_A_INVERTED #ifdef LED0_A_INVERTED
| BIT(0) | BIT(0)
#endif #endif
@ -69,17 +69,17 @@ void targetConfiguration(void)
#endif #endif
; ;
for (int i = 0; i < LED_NUMBER; i++) { for (int i = 0; i < STATUS_LED_NUMBER; i++) {
statusLedConfigMutable()->ledTags[i] = IO_TAG_NONE; statusLedConfigMutable()->ioTags[i] = IO_TAG_NONE;
} }
#ifdef LED0_A #ifdef LED0_A
statusLedConfigMutable()->ledTags[0] = IO_TAG(LED0_A); statusLedConfigMutable()->ioTags[0] = IO_TAG(LED0_A);
#endif #endif
#ifdef LED1_A #ifdef LED1_A
statusLedConfigMutable()->ledTags[1] = IO_TAG(LED1_A); statusLedConfigMutable()->ioTags[1] = IO_TAG(LED1_A);
#endif #endif
#ifdef LED2_A #ifdef LED2_A
statusLedConfigMutable()->ledTags[2] = IO_TAG(LED2_A); statusLedConfigMutable()->ioTags[2] = IO_TAG(LED2_A);
#endif #endif
} else { } else {
gyroConfigMutable()->gyro_sync_denom = 2; gyroConfigMutable()->gyro_sync_denom = 2;

View file

@ -28,8 +28,8 @@
#define BRUSHED_ESC_AUTODETECT #define BRUSHED_ESC_AUTODETECT
// LED's V1 // LED's V1
#define LED0 PB4 #define LED0_PIN PB4
#define LED1 PB5 #define LED1_PIN PB5
// LED's V2 // LED's V2
#define LED0_A PB8 #define LED0_A PB8

View file

@ -25,8 +25,8 @@
#define USBD_PRODUCT_STRING "AlienFlight F4" #define USBD_PRODUCT_STRING "AlienFlight F4"
#define LED0 PC12 #define LED0_PIN PC12
#define LED1 PD2 #define LED1_PIN PD2
#define BEEPER PC13 #define BEEPER PC13
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -25,8 +25,8 @@
#define USBD_PRODUCT_STRING "AlienFlightNG F7" #define USBD_PRODUCT_STRING "AlienFlightNG F7"
#define LED0 PC12 #define LED0_PIN PC12
#define LED1 PD2 #define LED1_PIN PD2
#define BEEPER PC13 #define BEEPER PC13
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -20,7 +20,7 @@
#define USBD_PRODUCT_STRING "BeeRotorF4" #define USBD_PRODUCT_STRING "BeeRotorF4"
#define LED0 PB4 #define LED0_PIN PB4
#define BEEPER PB3 #define BEEPER PB3
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -28,9 +28,9 @@
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define LED0 PB6 #define LED0_PIN PB6
#define LED1 PB5 #define LED1_PIN PB5
#define LED2 PB4 #define LED2_PIN PB4
#define BEEPER PC1 #define BEEPER PC1
#define BEEPER_OPT PB7 #define BEEPER_OPT PB7

View file

@ -17,7 +17,7 @@
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D #define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
#define LED0 PB3 #define LED0_PIN PB3
#define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO #define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO

View file

@ -24,9 +24,9 @@
#define STM32F3DISCOVERY #define STM32F3DISCOVERY
#endif #endif
#define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0_PIN PE8 // Blue LEDs - PE8/PE12
#define LED0_INVERTED #define LED0_INVERTED
#define LED1 PE10 // Orange LEDs - PE10/PE14 #define LED1_PIN PE10 // Orange LEDs - PE10/PE14
#define LED1_INVERTED #define LED1_INVERTED
#define BEEPER PE9 // Red LEDs - PE9/PE13 #define BEEPER PE9 // Red LEDs - PE9/PE13

View file

@ -21,9 +21,9 @@
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define TARGET_BUS_INIT #define TARGET_BUS_INIT
#define LED0 PC14 #define LED0_PIN PC14
#define LED1 PC13 #define LED1_PIN PC13
#define LED2 PC15 #define LED2_PIN PC15
#undef BEEPER #undef BEEPER

View file

@ -24,7 +24,7 @@
#endif #endif
#define LED0 PB5 #define LED0_PIN PB5
#define BEEPER PB4 #define BEEPER PB4
#define BEEPER_INVERTED #define BEEPER_INVERTED
#define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz #define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz

View file

@ -20,7 +20,7 @@
#define USBD_PRODUCT_STRING "CLRACINGF7" #define USBD_PRODUCT_STRING "CLRACINGF7"
#define LED0 PB0 #define LED0_PIN PB0
#define BEEPER PB4 #define BEEPER PB4
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -26,8 +26,8 @@
#define TARGET_XTAL_MHZ 16 #define TARGET_XTAL_MHZ 16
#define LED0 PC14 #define LED0_PIN PC14
#define LED1 PC13 #define LED1_PIN PC13
#define BEEPER PC5 #define BEEPER PC5

View file

@ -483,7 +483,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
mac->range.startStep = bstRead8(); mac->range.startStep = bstRead8();
mac->range.endStep = bstRead8(); mac->range.endStep = bstRead8();
useRcControlsConfig(modeActivationConditions(0), currentPidProfile); useRcControlsConfig(currentPidProfile);
} else { } else {
ret = BST_FAILED; ret = BST_FAILED;
} }

View file

@ -26,9 +26,9 @@
#undef USE_RX_MSP // never used. #undef USE_RX_MSP // never used.
#define LED0 PC15 #define LED0_PIN PC15
#define LED1 PC14 #define LED1_PIN PC14
#define LED2 PC13 #define LED2_PIN PC13
#define BEEPER PB13 #define BEEPER PB13
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -42,9 +42,9 @@
#define USED_TIMERS ( TIM_N(2) | TIM_N(4) ) #define USED_TIMERS ( TIM_N(2) | TIM_N(4) )
#endif #endif
#define LED0 PD2 #define LED0_PIN PD2
#define LED1 PC0 #define LED1_PIN PC0
#define LED2 PC3 #define LED2_PIN PC3
// Using STM32F405RG, 64 pin package (LQFP64) // Using STM32F405RG, 64 pin package (LQFP64)
// 16 pins per port, ports A, B, C, and also PD2 // 16 pins per port, ports A, B, C, and also PD2

View file

@ -22,11 +22,11 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
// tqfp48 pin 34 // tqfp48 pin 34
#define LED0 PA13 #define LED0_PIN PA13
// tqfp48 pin 37 // tqfp48 pin 37
#define LED1 PA14 #define LED1_PIN PA14
// tqfp48 pin 38 // tqfp48 pin 38
#define LED2 PA15 #define LED2_PIN PA15
#define BEEPER PB2 #define BEEPER PB2
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -22,9 +22,9 @@
#define USBD_PRODUCT_STRING "Elle0" #define USBD_PRODUCT_STRING "Elle0"
#define LED0 PA8 #define LED0_PIN PA8
#define LED1 PB4 #define LED1_PIN PB4
#define LED2 PC2 #define LED2_PIN PC2
// MPU9250 interrupt // MPU9250 interrupt
#define USE_EXTI #define USE_EXTI

View file

@ -20,9 +20,9 @@
#define USBD_PRODUCT_STRING "Swift-Flyer F4BY" #define USBD_PRODUCT_STRING "Swift-Flyer F4BY"
#define LED0 PE3 // Blue LED #define LED0_PIN PE3 // Blue LED
#define LED1 PE2 // Red LED #define LED1_PIN PE2 // Red LED
#define LED2 PE1 // Blue LED #define LED2_PIN PE1 // Blue LED
#define BEEPER PE5 #define BEEPER PE5

View file

@ -19,8 +19,8 @@
#define TARGET_BOARD_IDENTIFIER "FORT" #define TARGET_BOARD_IDENTIFIER "FORT"
#define USBD_PRODUCT_STRING "FortiniF4" #define USBD_PRODUCT_STRING "FortiniF4"
/*--------------LED----------------*/ /*--------------LED----------------*/
#define LED0 PB5 #define LED0_PIN PB5
#define LED1 PB6 #define LED1_PIN PB6
#define LED_STRIP #define LED_STRIP
/*---------------------------------*/ /*---------------------------------*/

View file

@ -32,8 +32,8 @@
#define TARGET_CONFIG #define TARGET_CONFIG
#define BRUSHED_ESC_AUTODETECT #define BRUSHED_ESC_AUTODETECT
#define LED0 PB9 #define LED0_PIN PB9
#define LED1 PB5 #define LED1_PIN PB5
#define BEEPER PA0 #define BEEPER PA0
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -19,8 +19,8 @@
#define TARGET_BOARD_IDENTIFIER "PIK4" #define TARGET_BOARD_IDENTIFIER "PIK4"
#define USBD_PRODUCT_STRING "PikoF4" #define USBD_PRODUCT_STRING "PikoF4"
/*--------------LED----------------*/ /*--------------LED----------------*/
#define LED0 PA15 #define LED0_PIN PA15
#define LED1 PB6 #define LED1_PIN PB6
#define LED_STRIP #define LED_STRIP
/*---------------------------------*/ /*---------------------------------*/

View file

@ -21,8 +21,8 @@
#define USBD_PRODUCT_STRING "FishDroneF4" #define USBD_PRODUCT_STRING "FishDroneF4"
#define LED0 PC13 #define LED0_PIN PC13
#define LED1 PC14 #define LED1_PIN PC14
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -21,7 +21,7 @@
#define TARGET_CONFIG #define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -19,7 +19,7 @@
#define USBD_PRODUCT_STRING "FRSKYF4" #define USBD_PRODUCT_STRING "FRSKYF4"
#define TARGET_CONFIG #define TARGET_CONFIG
#define LED0 PB5 #define LED0_PIN PB5
#define BEEPER PB4 #define BEEPER PB4
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -28,7 +28,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define CONFIG_PREFER_ACC_ON #define CONFIG_PREFER_ACC_ON
#define LED0 PC14 #define LED0_PIN PC14
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -25,8 +25,8 @@
#define USBD_PRODUCT_STRING "FuryF4" #define USBD_PRODUCT_STRING "FuryF4"
#endif #endif
#define LED0 PB5 #define LED0_PIN PB5
#define LED1 PB4 #define LED1_PIN PB4
#define BEEPER PA8 #define BEEPER PA8
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -21,8 +21,8 @@
#define USBD_PRODUCT_STRING "FuryF7" #define USBD_PRODUCT_STRING "FuryF7"
#define LED0 PB5 #define LED0_PIN PB5
#define LED1 PB4 #define LED1_PIN PB4
#define BEEPER PD10 #define BEEPER PD10
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -21,7 +21,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB7 #define LED0_PIN PB7
#define BEEPER PC15 #define BEEPER PC15

View file

@ -21,7 +21,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#define USE_EXTI #define USE_EXTI
#define MPU_INT_EXTI PC13 #define MPU_INT_EXTI PC13

View file

@ -21,7 +21,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -20,9 +20,9 @@
#define USBD_PRODUCT_STRING "KakuteF4-V1" #define USBD_PRODUCT_STRING "KakuteF4-V1"
#define LED0 PB5 #define LED0_PIN PB5
#define LED1 PB4 #define LED1_PIN PB4
#define LED2 PB6 #define LED2_PIN PB6
#define BEEPER PC9 #define BEEPER PC9
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -29,7 +29,7 @@
#define ESCSERIAL_TIMER_TX_HARDWARE 6 #define ESCSERIAL_TIMER_TX_HARDWARE 6
#define REMAP_TIM17_DMA #define REMAP_TIM17_DMA
#define LED0 PB1 #define LED0_PIN PB1
#define BEEPER PB13 #define BEEPER PB13
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -32,11 +32,11 @@
#endif #endif
#if defined(PLUMF4) || defined(KIWIF4V2) #if defined(PLUMF4) || defined(KIWIF4V2)
#define LED0 PB4 #define LED0_PIN PB4
#else #else
#define LED0 PB5 #define LED0_PIN PB5
#define LED1 PB4 #define LED1_PIN PB4
#endif #endif
#define BEEPER PA8 #define BEEPER PA8

View file

@ -27,8 +27,8 @@
#define TARGET_CONFIG #define TARGET_CONFIG
#define TARGET_PREINIT #define TARGET_PREINIT
#define LED0 PA14 // Red LED #define LED0_PIN PA14 // Red LED
#define LED1 PA13 // Green LED #define LED1_PIN PA13 // Green LED
#define BEEPER PC1 #define BEEPER PC1

View file

@ -17,7 +17,7 @@
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC #define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
#define LED0 PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15
// MPU6000 interrupts // MPU6000 interrupts

View file

@ -26,10 +26,10 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PC15 #define LED0_PIN PC15
#define LED1 PC14 #define LED1_PIN PC14
#ifndef LUXV2_RACE #ifndef LUXV2_RACE
#define LED2 PC13 #define LED2_PIN PC13
#endif #endif
#ifdef LUXV2_RACE #ifdef LUXV2_RACE

View file

@ -22,8 +22,8 @@
#define USBD_PRODUCT_STRING "MatekF4" #define USBD_PRODUCT_STRING "MatekF4"
#define LED0 PB9 #define LED0_PIN PB9
#define LED1 PA14 #define LED1_PIN PA14
#define BEEPER PC13 #define BEEPER PC13
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -19,8 +19,8 @@
#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY #define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY
#define LED0 PB3 #define LED0_PIN PB3
#define LED1 PB4 #define LED1_PIN PB4
#define BEEPER PA12 #define BEEPER PA12

View file

@ -22,8 +22,8 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define TARGET_CONFIG #define TARGET_CONFIG
#define LED0 PB5 // Blue LEDs - PB5 #define LED0_PIN PB5 // Blue LEDs - PB5
//#define LED1 PB9 // Green LEDs - PB9 //#define LED1_PIN PB9 // Green LEDs - PB9
#define BEEPER PA0 #define BEEPER PA0
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -27,6 +27,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
#include "fc/rc_modes.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"

View file

@ -22,7 +22,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -26,8 +26,8 @@
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define LED0 PB3 #define LED0_PIN PB3
#define LED1 PB4 #define LED1_PIN PB4
#define BEEPER PA12 #define BEEPER PA12

View file

@ -24,9 +24,9 @@
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define LED0 PB6 #define LED0_PIN PB6
#define LED1 PB5 #define LED1_PIN PB5
#define LED2 PB4 #define LED2_PIN PB4
#define BEEPER PC1 #define BEEPER PC1
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -26,7 +26,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -33,8 +33,8 @@
#define USBD_SERIALNUMBER_STRING "0x8020000" // Remove this at the next major release (?) #define USBD_SERIALNUMBER_STRING "0x8020000" // Remove this at the next major release (?)
#endif #endif
#define LED0 PB5 #define LED0_PIN PB5
//#define LED1 PB4 // Remove this at the next major release //#define LED1_PIN PB4 // Remove this at the next major release
#define BEEPER PB4 #define BEEPER PB4
#define BEEPER_INVERTED #define BEEPER_INVERTED
@ -93,9 +93,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD #define USE_SDCARD
#define USE_SDCARD_SPI2 #define USE_SDCARD_SPI2
#if defined(OMNIBUSF4SD)
#define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_INVERTED
#endif
#define SDCARD_DETECT_PIN PB7 #define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2 #define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN #define SDCARD_SPI_CS_PIN SPI2_NSS_PIN

View file

@ -19,7 +19,7 @@
#define USBD_PRODUCT_STRING "OmnibusF7" #define USBD_PRODUCT_STRING "OmnibusF7"
#define LED0 PE0 #define LED0_PIN PE0
#define BEEPER PD15 #define BEEPER PD15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -21,10 +21,10 @@
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define TARGET_CONFIG #define TARGET_CONFIG
#define LED0 PB3 #define LED0_PIN PB3
#define LED0_INVERTED #define LED0_INVERTED
#define LED1 PB4 #define LED1_PIN PB4
#define LED1_INVERTED #define LED1_INVERTED
#define BEEPER PA12 #define BEEPER PA12

View file

@ -21,8 +21,8 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB4 #define LED0_PIN PB4
#define LED1 PB5 #define LED1_PIN PB5
#define BEEPER PA0 #define BEEPER PA0
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -48,10 +48,10 @@
#endif #endif
#define LED0 PB5 #define LED0_PIN PB5
#if defined(PODIUMF4) #if defined(PODIUMF4)
#define LED1 PB4 #define LED1_PIN PB4
#define LED2 PB6 #define LED2_PIN PB6
#endif #endif
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper // Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
@ -64,7 +64,7 @@
#define BEEPER PB6 #define BEEPER PB6
#define BEEPER_INVERTED #define BEEPER_INVERTED
#else #else
#define LED1 PB4 #define LED1_PIN PB4
// Leave beeper here but with none as io - so disabled unless mapped. // Leave beeper here but with none as io - so disabled unless mapped.
#define BEEPER NONE #define BEEPER NONE
#endif #endif

View file

@ -23,8 +23,8 @@
#define USBD_SERIALNUMBER_STRING "0x8010000" #define USBD_SERIALNUMBER_STRING "0x8010000"
#endif #endif
#define LED0 PC14 #define LED0_PIN PC14
#define LED1 PC13 #define LED1_PIN PC13
#define BEEPER PC13 #define BEEPER PC13

View file

@ -19,8 +19,8 @@
#define TARGET_BOARD_IDENTIFIER "RGF3" // rgSSD_F3 #define TARGET_BOARD_IDENTIFIER "RGF3" // rgSSD_F3
#define LED0 PC1 #define LED0_PIN PC1
#define LED1 PC0 #define LED1_PIN PC0
#define BEEPER PA8 #define BEEPER PA8
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -21,7 +21,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15

View file

@ -19,7 +19,7 @@
#define TARGET_BOARD_IDENTIFIER "SIRF" #define TARGET_BOARD_IDENTIFIER "SIRF"
#define LED0 PB2 #define LED0_PIN PB2
#define BEEPER PA1 #define BEEPER PA1

View file

@ -45,6 +45,8 @@
#undef SCHEDULER_DELAY_LIMIT #undef SCHEDULER_DELAY_LIMIT
#define SCHEDULER_DELAY_LIMIT 1 #define SCHEDULER_DELAY_LIMIT 1
#define USE_FAKE_LED
#define ACC #define ACC
#define USE_FAKE_ACC #define USE_FAKE_ACC

View file

@ -21,8 +21,8 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB4 // Blue (Rev 1 & 2) - PB4 #define LED0_PIN PB4 // Blue (Rev 1 & 2) - PB4
#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5 #define LED1_PIN PB5 // Green (Rev 1) / Red (Rev 2) - PB5
#define BEEPER PA1 #define BEEPER PA1
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -23,9 +23,9 @@
#define USBD_SERIALNUMBER_STRING "0x8020000" #define USBD_SERIALNUMBER_STRING "0x8020000"
#endif #endif
#define LED0 PB5 #define LED0_PIN PB5
#define LED1 PB4 #define LED1_PIN PB4
#define LED2 PB6 #define LED2_PIN PB6
#define BEEPER PC9 #define BEEPER PC9
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -30,11 +30,11 @@
#if defined(ZCOREF3) #if defined(ZCOREF3)
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB8 #define LED0_PIN PB8
#else #else
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#endif #endif
#define BEEPER PC15 #define BEEPER PC15

View file

@ -46,7 +46,7 @@
#define BRUSHED_ESC_AUTODETECT #define BRUSHED_ESC_AUTODETECT
#define LED0 PB8 #define LED0_PIN PB8
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -22,7 +22,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB8 #define LED0_PIN PB8
#else #else
#define TARGET_BOARD_IDENTIFIER "SRFM" #define TARGET_BOARD_IDENTIFIER "SRFM"
@ -32,7 +32,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3 #define LED0_PIN PB3
#endif #endif
#define BEEPER PC15 #define BEEPER PC15

Some files were not shown because too many files have changed in this diff Show more