Merge pull request #1298 from martinbudden/bf_pg_code

Copied parameter group code over from Cleanflight
This commit is contained in:
Martin Budden 2016-10-12 05:40:40 +01:00 committed by GitHub
commit 98c5e0298a
4 changed files with 428 additions and 0 deletions

View File

@ -407,6 +407,7 @@ COMMON_SRC = \
config/config.c \
config/config_eeprom.c \
config/feature.c \
config/parameter_group.c \
fc/runtime_config.c \
drivers/adc.c \
drivers/buf_writer.c \

View File

@ -0,0 +1,115 @@
/*
* 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 <stddef.h>
#include <string.h>
#include <stdint.h>
#include "parameter_group.h"
#include "common/maths.h"
const pgRegistry_t* pgFind(pgn_t pgn)
{
PG_FOREACH(reg) {
if (pgN(reg) == pgn) {
return reg;
}
}
return NULL;
}
static uint8_t *pgOffset(const pgRegistry_t* reg, uint8_t profileIndex)
{
const uint16_t regSize = pgSize(reg);
uint8_t *base = reg->address;
if (!pgIsSystem(reg)) {
base += (regSize * profileIndex);
}
return base;
}
static void pgResetInstance(const pgRegistry_t *reg, uint8_t *base)
{
const uint16_t regSize = pgSize(reg);
memset(base, 0, regSize);
if (reg->reset.ptr >= (void*)__pg_resetdata_start && reg->reset.ptr < (void*)__pg_resetdata_end) {
// pointer points to resetdata section, to it is data template
memcpy(base, reg->reset.ptr, regSize);
} else if (reg->reset.fn) {
// reset function, call it
reg->reset.fn(base, regSize);
}
}
void pgReset(const pgRegistry_t* reg, int profileIndex)
{
pgResetInstance(reg, pgOffset(reg, profileIndex));
}
void pgResetCurrent(const pgRegistry_t *reg)
{
if (pgIsSystem(reg)) {
pgResetInstance(reg, reg->address);
} else {
pgResetInstance(reg, *reg->ptr);
}
}
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version)
{
pgResetInstance(reg, pgOffset(reg, profileIndex));
// restore only matching version, keep defaults otherwise
if (version == pgVersion(reg)) {
const int take = MIN(size, pgSize(reg));
memcpy(pgOffset(reg, profileIndex), from, take);
}
}
int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex)
{
const int take = MIN(size, pgSize(reg));
memcpy(to, pgOffset(reg, profileIndex), take);
return take;
}
void pgResetAll(int profileCount)
{
PG_FOREACH(reg) {
if (pgIsSystem(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

@ -0,0 +1,229 @@
/*
* 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
typedef uint16_t pgn_t;
// parameter group registry flags
typedef enum {
PGRF_NONE = 0,
PGRF_CLASSIFICATON_BIT = (1 << 0),
} pgRegistryFlags_e;
typedef enum {
PGR_PGN_MASK = 0x0fff,
PGR_PGN_VERSION_MASK = 0xf000,
PGR_SIZE_MASK = 0x0fff,
PGR_SIZE_SYSTEM_FLAG = 0x0000, // documentary
PGR_SIZE_PROFILE_FLAG = 0x8000, // start using flags from the top bit down
} pgRegistryInternal_e;
// function that resets a single parameter group instance
typedef void (pgResetFunc)(void * /* base */, int /* size */);
typedef struct pgRegistry_s {
pgn_t pgn; // The parameter group number, the top 4 bits are reserved for version
uint16_t size; // Size of the group in RAM, the top 4 bits are reserved for flags
uint8_t *address; // Address of the group in RAM.
uint8_t **ptr; // The pointer to update after loading the record into ram.
union {
void *ptr; // Pointer to init template
pgResetFunc *fn; // Popinter to pgResetFunc
} reset;
} pgRegistry_t;
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 reg->pgn >> 12;}
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;}
#define PG_PACKED __attribute__((packed))
#ifdef __APPLE__
extern const pgRegistry_t __pg_registry_start[] __asm("section$start$__DATA$__pg_registry");
extern const pgRegistry_t __pg_registry_end[] __asm("section$end$__DATA$__pg_registry");
#define PG_REGISTER_ATTRIBUTES __attribute__ ((section("__DATA,__pg_registry"), used, aligned(4)))
extern const uint8_t __pg_resetdata_start[] __asm("section$start$__DATA$__pg_resetdata");
extern const uint8_t __pg_resetdata_end[] __asm("section$end$__DATA$__pg_resetdata");
#define PG_RESETDATA_ATTRIBUTES __attribute__ ((section("__DATA,__pg_resetdata"), used, aligned(2)))
#else
extern const pgRegistry_t __pg_registry_start[];
extern const pgRegistry_t __pg_registry_end[];
#define PG_REGISTER_ATTRIBUTES __attribute__ ((section(".pg_registry"), used, aligned(4)))
extern const uint8_t __pg_resetdata_start[];
extern const uint8_t __pg_resetdata_end[];
#define PG_RESETDATA_ATTRIBUTES __attribute__ ((section(".pg_resetdata"), used, aligned(2)))
#endif
#define PG_REGISTRY_SIZE (__pg_registry_end - __pg_registry_start)
// Helper to iterate over the PG register. Cheaper than a visitor style callback.
#define PG_FOREACH(_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)
// Only current profile is reset for profile based configs
#define PG_RESET_CURRENT(_name) \
do { \
extern const pgRegistry_t _name ##_Registry; \
pgResetCurrent(&_name ## _Registry); \
} while(0) \
/**/
// Declare system config
#define PG_DECLARE(_type, _name) \
extern _type _name ## _System; \
static inline _type* _name(void) { return &_name ## _System; } \
struct _dummy \
/**/
// Declare system config array
#define PG_DECLARE_ARR(_type, _size, _name) \
extern _type _name ## _SystemArray[_size]; \
static inline _type* _name(int _index) { return &_name ## _SystemArray[_index]; } \
static inline _type (* _name ## _arr(void))[_size] { return &_name ## _SystemArray; } \
struct _dummy \
/**/
// Declare profile config
#define PG_DECLARE_PROFILE(_type, _name) \
extern _type *_name ## _ProfileCurrent; \
static inline _type* _name(void) { return _name ## _ProfileCurrent; } \
struct _dummy \
/**/
// Register system config
#define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \
_type _name ## _System; \
/* Force external linkage for g++. Catch multi registration */ \
extern const pgRegistry_t _name ## _Registry; \
const pgRegistry_t _name ##_Registry PG_REGISTER_ATTRIBUTES = { \
.pgn = _pgn | (_version << 12), \
.size = sizeof(_type) | PGR_SIZE_SYSTEM_FLAG, \
.address = (uint8_t*)&_name ## _System, \
.ptr = 0, \
_reset, \
} \
/**/
#define PG_REGISTER(_type, _name, _pgn, _version) \
PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.ptr = 0}) \
/**/
#define PG_REGISTER_WITH_RESET_FN(_type, _name, _pgn, _version) \
extern void pgResetFn_ ## _name(_type *); \
PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.fn = (pgResetFunc*)&pgResetFn_ ## _name }) \
/**/
#define PG_REGISTER_WITH_RESET_TEMPLATE(_type, _name, _pgn, _version) \
extern const _type pgResetTemplate_ ## _name; \
PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.ptr = (void*)&pgResetTemplate_ ## _name}) \
/**/
// Register system config array
#define PG_REGISTER_ARR_I(_type, _size, _name, _pgn, _version, _reset) \
_type _name ## _SystemArray[_size]; \
extern const pgRegistry_t _name ##_Registry; \
const pgRegistry_t _name ## _Registry PG_REGISTER_ATTRIBUTES = { \
.pgn = _pgn | (_version << 12), \
.size = (sizeof(_type) * _size) | PGR_SIZE_SYSTEM_FLAG, \
.address = (uint8_t*)&_name ## _SystemArray, \
.ptr = 0, \
_reset, \
} \
/**/
#define PG_REGISTER_ARR(_type, _size, _name, _pgn, _version) \
PG_REGISTER_ARR_I(_type, _size, _name, _pgn, _version, .reset = {.ptr = 0}) \
/**/
#define PG_REGISTER_ARR_WITH_RESET_FN(_type, _size, _name, _pgn, _version) \
extern void pgResetFn_ ## _name(_type *); \
PG_REGISTER_ARR_I(_type, _size, _name, _pgn, _version, .reset = {.fn = (pgResetFunc*)&pgResetFn_ ## _name}) \
/**/
#if 0
// ARRAY reset mechanism is not implemented yet, only few places in code would benefit from it - See pgResetInstance
#define PG_REGISTER_ARR_WITH_RESET_TEMPLATE(_type, _size, _name, _pgn, _version) \
extern const _type pgResetTemplate_ ## _name; \
PG_REGISTER_ARR_I(_type, _size, _name, _pgn, _version, .reset = {.ptr = (void*)&pgResetTemplate_ ## _name}) \
/**/
#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[MAX_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.
// Config must be registered with PG_REGISTER_<xxx>_WITH_RESET_TEMPLATE macro
#define PG_RESET_TEMPLATE(_type, _name, ...) \
const _type pgResetTemplate_ ## _name PG_RESETDATA_ATTRIBUTES = { \
__VA_ARGS__ \
} \
/**/
const pgRegistry_t* pgFind(pgn_t pgn);
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version);
int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex);
void pgResetAll(int profileCount);
void pgResetCurrent(const pgRegistry_t *reg);
void pgReset(const pgRegistry_t* reg, int profileIndex);
void pgActivateProfile(int profileIndex);

View File

@ -0,0 +1,83 @@
/*
* 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/>.
*/
// FC configuration
#define PG_FAILSAFE_CONFIG 1
#define PG_BOARD_ALIGNMENT 2
#define PG_GIMBAL_CONFIG 3
#define PG_MOTOR_MIXER 4
#define PG_BLACKBOX_CONFIG 5
#define PG_MOTOR_AND_SERVO_CONFIG 6
#define PG_SENSOR_SELECTION_CONFIG 7
#define PG_SENSOR_ALIGNMENT_CONFIG 8
#define PG_SENSOR_TRIMS 9
#define PG_GYRO_CONFIG 10
#define PG_BATTERY_CONFIG 11
#define PG_CONTROL_RATE_PROFILES 12
#define PG_SERIAL_CONFIG 13
#define PG_PID_PROFILE 14
#define PG_GTUNE_CONFIG 15
#define PG_ARMING_CONFIG 16
#define PG_TRANSPONDER_CONFIG 17
#define PG_SYSTEM_CONFIG 18
#define PG_FEATURE_CONFIG 19
#define PG_MIXER_CONFIG 20
#define PG_SERVO_MIXER 21
#define PG_IMU_CONFIG 22
#define PG_PROFILE_SELECTION 23
#define PG_RX_CONFIG 24
#define PG_RC_CONTROLS_CONFIG 25
#define PG_MOTOR_3D_CONFIG 26
#define PG_LED_STRIP_CONFIG 27
#define PG_COLOR_CONFIG 28
#define PG_AIRPLANE_ALT_HOLD_CONFIG 29
#define PG_GPS_CONFIG 30
#define PG_TELEMETRY_CONFIG 31
#define PG_FRSKY_TELEMETRY_CONFIG 32
#define PG_HOTT_TELEMETRY_CONFIG 33
#define PG_NAVIGATION_CONFIG 34
#define PG_ACCELEROMETER_CONFIG 35
#define PG_RATE_PROFILE_SELECTION 36
#define PG_ADJUSTMENT_PROFILE 37
#define PG_BAROMETER_CONFIG 38
#define PG_THROTTLE_CORRECTION_CONFIG 39
#define PG_COMPASS_CONFIGURATION 40
#define PG_MODE_ACTIVATION_PROFILE 41
#define PG_SERVO_PROFILE 42
#define PG_FAILSAFE_CHANNEL_CONFIG 43
#define PG_CHANNEL_RANGE_CONFIG 44
#define PG_MODE_COLOR_CONFIG 45
#define PG_SPECIAL_COLOR_CONFIG 46
#define PG_PILOT_CONFIG 47
#define PG_MSP_SERVER_CONFIG 48
#define PG_VOLTAGE_METER_CONFIG 49
#define PG_AMPERAGE_METER_CONFIG 50
// Driver configuration
#define PG_DRIVER_PWM_RX_CONFIG 100
#define PG_DRIVER_FLASHCHIP_CONFIG 101
// OSD configuration (subject to change)
#define PG_OSD_FONT_CONFIG 32768
#define PG_OSD_VIDEO_CONFIG 32769
#define PG_OSD_ELEMENT_CONFIG 32770
#define PG_RESERVED_FOR_TESTING_1 65533
#define PG_RESERVED_FOR_TESTING_2 65534
#define PG_RESERVED_FOR_TESTING_3 65535