Parameter groups EEPROM migration
This commit is contained in:
parent
cbd036a187
commit
974037c150
1
Makefile
1
Makefile
|
@ -561,6 +561,7 @@ COMMON_SRC = \
|
|||
config/config_eeprom.c \
|
||||
config/feature.c \
|
||||
config/parameter_group.c \
|
||||
config/config_streamer.c \
|
||||
drivers/adc.c \
|
||||
drivers/buf_writer.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
|
|
|
@ -18,294 +18,271 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stddef.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_streamer.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#if !defined(FLASH_SIZE)
|
||||
#error "Flash size not defined for target. (specify in KB)"
|
||||
#endif
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#ifndef FLASH_PAGE_SIZE
|
||||
#ifdef STM32F303xC
|
||||
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
|
||||
#endif
|
||||
extern uint8_t __config_start; // configured via linker script when building binaries.
|
||||
extern uint8_t __config_end;
|
||||
|
||||
#ifdef STM32F10X_MD
|
||||
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
|
||||
#endif
|
||||
typedef enum {
|
||||
CR_CLASSICATION_SYSTEM = 0,
|
||||
CR_CLASSICATION_PROFILE1 = 1,
|
||||
CR_CLASSICATION_PROFILE2 = 2,
|
||||
CR_CLASSICATION_PROFILE3 = 3,
|
||||
CR_CLASSICATION_PROFILE_LAST = CR_CLASSICATION_PROFILE3,
|
||||
} configRecordFlags_e;
|
||||
|
||||
#ifdef STM32F10X_HD
|
||||
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
|
||||
#endif
|
||||
#define CR_CLASSIFICATION_MASK (0x3)
|
||||
|
||||
#if defined(STM32F745xx)
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
||||
#endif
|
||||
// Header for the saved copy.
|
||||
typedef struct {
|
||||
uint8_t format;
|
||||
} PG_PACKED configHeader_t;
|
||||
|
||||
#if defined(STM32F746xx)
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
||||
#endif
|
||||
// Header for each stored PG.
|
||||
typedef struct {
|
||||
// split up.
|
||||
uint16_t size;
|
||||
pgn_t pgn;
|
||||
uint8_t version;
|
||||
|
||||
#if defined(STM32F722xx)
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
#endif
|
||||
// lower 2 bits used to indicate system or profile number, see CR_CLASSIFICATION_MASK
|
||||
uint8_t flags;
|
||||
|
||||
#if defined(STM32F40_41xxx)
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
#endif
|
||||
uint8_t pg[];
|
||||
} PG_PACKED configRecord_t;
|
||||
|
||||
#if defined (STM32F411xE)
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
|
||||
#ifdef STM32F10X_MD
|
||||
#define FLASH_PAGE_COUNT 128
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X_HD
|
||||
#define FLASH_PAGE_COUNT 128
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(FLASH_SIZE)
|
||||
#if defined(STM32F40_41xxx)
|
||||
#define FLASH_PAGE_COUNT 4
|
||||
#elif defined (STM32F411xE)
|
||||
#define FLASH_PAGE_COUNT 3
|
||||
#elif defined (STM32F722xx)
|
||||
#define FLASH_PAGE_COUNT 3
|
||||
#elif defined (STM32F745xx)
|
||||
#define FLASH_PAGE_COUNT 4
|
||||
#elif defined (STM32F746xx)
|
||||
#define FLASH_PAGE_COUNT 4
|
||||
#else
|
||||
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if !defined(FLASH_PAGE_SIZE)
|
||||
#error "Flash page size not defined for target."
|
||||
#endif
|
||||
|
||||
#if !defined(FLASH_PAGE_COUNT)
|
||||
#error "Flash page count not defined for target."
|
||||
#endif
|
||||
|
||||
#if FLASH_SIZE <= 128
|
||||
#define FLASH_TO_RESERVE_FOR_CONFIG 0x800
|
||||
#else
|
||||
#define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
|
||||
#endif
|
||||
|
||||
// use the last flash pages for storage
|
||||
#ifdef CUSTOM_FLASH_MEMORY_ADDRESS
|
||||
size_t custom_flash_memory_address = 0;
|
||||
#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
|
||||
#else
|
||||
// use the last flash pages for storage
|
||||
#ifndef CONFIG_START_FLASH_ADDRESS
|
||||
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
|
||||
#endif
|
||||
#endif
|
||||
// Footer for the saved copy.
|
||||
typedef struct {
|
||||
uint16_t terminator;
|
||||
} PG_PACKED configFooter_t;
|
||||
// checksum is appended just after footer. It is not included in footer to make checksum calculation consistent
|
||||
|
||||
// Used to check the compiler packing at build time.
|
||||
typedef struct {
|
||||
uint8_t byte;
|
||||
uint32_t word;
|
||||
} PG_PACKED packingTest_t;
|
||||
|
||||
void initEEPROM(void)
|
||||
{
|
||||
// Verify that this architecture packs as expected.
|
||||
BUILD_BUG_ON(offsetof(packingTest_t, byte) != 0);
|
||||
BUILD_BUG_ON(offsetof(packingTest_t, word) != 1);
|
||||
BUILD_BUG_ON(sizeof(packingTest_t) != 5);
|
||||
|
||||
BUILD_BUG_ON(sizeof(configHeader_t) != 1);
|
||||
BUILD_BUG_ON(sizeof(configFooter_t) != 2);
|
||||
BUILD_BUG_ON(sizeof(configRecord_t) != 6);
|
||||
}
|
||||
|
||||
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
|
||||
static uint8_t updateChecksum(uint8_t chk, const void *data, uint32_t length)
|
||||
{
|
||||
uint8_t checksum = 0;
|
||||
const uint8_t *byteOffset;
|
||||
const uint8_t *p = (const uint8_t *)data;
|
||||
const uint8_t *pend = p + length;
|
||||
|
||||
for (byteOffset = data; byteOffset < (data + length); byteOffset++)
|
||||
checksum ^= *byteOffset;
|
||||
return checksum;
|
||||
for (; p != pend; p++) {
|
||||
chk ^= *p;
|
||||
}
|
||||
return chk;
|
||||
}
|
||||
|
||||
// Scan the EEPROM config. Returns true if the config is valid.
|
||||
static bool scanEEPROM(void)
|
||||
{
|
||||
uint8_t chk = 0;
|
||||
const uint8_t *p = &__config_start;
|
||||
const configHeader_t *header = (const configHeader_t *)p;
|
||||
|
||||
if (header->format != EEPROM_CONF_VERSION) {
|
||||
return false;
|
||||
}
|
||||
chk = updateChecksum(chk, header, sizeof(*header));
|
||||
p += sizeof(*header);
|
||||
// include the transitional masterConfig record
|
||||
chk = updateChecksum(chk, p, sizeof(masterConfig));
|
||||
p += sizeof(masterConfig);
|
||||
|
||||
for (;;) {
|
||||
const configRecord_t *record = (const configRecord_t *)p;
|
||||
|
||||
if (record->size == 0) {
|
||||
// Found the end. Stop scanning.
|
||||
break;
|
||||
}
|
||||
if (p + record->size >= &__config_end
|
||||
|| record->size < sizeof(*record)) {
|
||||
// Too big or too small.
|
||||
return false;
|
||||
}
|
||||
|
||||
chk = updateChecksum(chk, p, record->size);
|
||||
|
||||
p += record->size;
|
||||
}
|
||||
|
||||
const configFooter_t *footer = (const configFooter_t *)p;
|
||||
chk = updateChecksum(chk, footer, sizeof(*footer));
|
||||
p += sizeof(*footer);
|
||||
chk = ~chk;
|
||||
return chk == *p;
|
||||
}
|
||||
|
||||
// find config record for reg + classification (profile info) in EEPROM
|
||||
// return NULL when record is not found
|
||||
// this function assumes that EEPROM content is valid
|
||||
static const configRecord_t *findEEPROM(const pgRegistry_t *reg, configRecordFlags_e classification)
|
||||
{
|
||||
const uint8_t *p = &__config_start;
|
||||
p += sizeof(configHeader_t); // skip header
|
||||
p += sizeof(master_t); // skip the transitional master_t record
|
||||
while (true) {
|
||||
const configRecord_t *record = (const configRecord_t *)p;
|
||||
if (record->size == 0
|
||||
|| p + record->size >= &__config_end
|
||||
|| record->size < sizeof(*record))
|
||||
break;
|
||||
if (pgN(reg) == record->pgn
|
||||
&& (record->flags & CR_CLASSIFICATION_MASK) == classification)
|
||||
return record;
|
||||
p += record->size;
|
||||
}
|
||||
// record not found
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Initialize all PG records from EEPROM.
|
||||
// This functions processes all PGs sequentially, scanning EEPROM for each one. This is suboptimal,
|
||||
// but each PG is loaded/initialized exactly once and in defined order.
|
||||
bool loadEEPROM(void)
|
||||
{
|
||||
// read in the transitional masterConfig record
|
||||
const uint8_t *p = &__config_start;
|
||||
p += sizeof(configHeader_t); // skip header
|
||||
masterConfig = *(master_t*)p;
|
||||
|
||||
PG_FOREACH(reg) {
|
||||
configRecordFlags_e cls_start, cls_end;
|
||||
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) {
|
||||
// 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);
|
||||
} else {
|
||||
pgReset(reg, profileIndex);
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool isEEPROMContentValid(void)
|
||||
{
|
||||
const master_t *temp = (const master_t *) CONFIG_START_FLASH_ADDRESS;
|
||||
uint8_t checksum = 0;
|
||||
|
||||
// check version number
|
||||
if (EEPROM_CONF_VERSION != temp->version)
|
||||
return false;
|
||||
|
||||
// check size and magic numbers
|
||||
if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
|
||||
return false;
|
||||
|
||||
if (strncasecmp(temp->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER)))
|
||||
return false;
|
||||
|
||||
// verify integrity of temporary copy
|
||||
checksum = calculateChecksum((const uint8_t *) temp, sizeof(master_t));
|
||||
if (checksum != 0)
|
||||
return false;
|
||||
|
||||
// looks good, let's roll!
|
||||
return true;
|
||||
return scanEEPROM();
|
||||
}
|
||||
|
||||
#if defined(STM32F7)
|
||||
|
||||
// FIXME: HAL for now this will only work for F4/F7 as flash layout is different
|
||||
void writeEEPROM(void)
|
||||
static bool writeSettingsToEEPROM(void)
|
||||
{
|
||||
// Generate compile time error if the config does not fit in the reserved area of flash.
|
||||
BUILD_BUG_ON(sizeof(master_t) > FLASH_TO_RESERVE_FOR_CONFIG);
|
||||
config_streamer_t streamer;
|
||||
config_streamer_init(&streamer);
|
||||
|
||||
HAL_StatusTypeDef status;
|
||||
uint32_t wordOffset;
|
||||
int8_t attemptsRemaining = 3;
|
||||
config_streamer_start(&streamer, (uintptr_t)&__config_start, &__config_end - &__config_start);
|
||||
uint8_t chk = 0;
|
||||
|
||||
suspendRxSignal();
|
||||
configHeader_t header = {
|
||||
.format = EEPROM_CONF_VERSION,
|
||||
};
|
||||
|
||||
// prepare checksum/version constants
|
||||
masterConfig.version = EEPROM_CONF_VERSION;
|
||||
masterConfig.size = sizeof(master_t);
|
||||
masterConfig.magic_be = 0xBE;
|
||||
masterConfig.magic_ef = 0xEF;
|
||||
masterConfig.chk = 0; // erase checksum before recalculating
|
||||
masterConfig.chk = calculateChecksum((const uint8_t *) &masterConfig, sizeof(master_t));
|
||||
config_streamer_write(&streamer, (uint8_t *)&header, sizeof(header));
|
||||
chk = updateChecksum(chk, (uint8_t *)&header, sizeof(header));
|
||||
// write the transitional masterConfig record
|
||||
config_streamer_write(&streamer, (uint8_t *)&masterConfig, sizeof(masterConfig));
|
||||
chk = updateChecksum(chk, (uint8_t *)&masterConfig, sizeof(masterConfig));
|
||||
PG_FOREACH(reg) {
|
||||
const uint16_t regSize = pgSize(reg);
|
||||
configRecord_t record = {
|
||||
.size = sizeof(configRecord_t) + regSize,
|
||||
.pgn = pgN(reg),
|
||||
.version = pgVersion(reg),
|
||||
.flags = 0
|
||||
};
|
||||
|
||||
// write it
|
||||
/* Unlock the Flash to enable the flash control register access *************/
|
||||
HAL_FLASH_Unlock();
|
||||
while (attemptsRemaining--)
|
||||
{
|
||||
/* Fill EraseInit structure*/
|
||||
FLASH_EraseInitTypeDef EraseInitStruct = {0};
|
||||
EraseInitStruct.TypeErase = FLASH_TYPEERASE_SECTORS;
|
||||
EraseInitStruct.VoltageRange = FLASH_VOLTAGE_RANGE_3; // 2.7-3.6V
|
||||
EraseInitStruct.Sector = (FLASH_SECTOR_TOTAL-1);
|
||||
EraseInitStruct.NbSectors = 1;
|
||||
uint32_t SECTORError;
|
||||
status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError);
|
||||
if (status != HAL_OK)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
else
|
||||
{
|
||||
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4)
|
||||
{
|
||||
status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, CONFIG_START_FLASH_ADDRESS + wordOffset, *(uint32_t *) ((char *) &masterConfig + wordOffset));
|
||||
if(status != HAL_OK)
|
||||
{
|
||||
break;
|
||||
}
|
||||
if (pgIsSystem(reg)) {
|
||||
// write the only instance
|
||||
record.flags |= CR_CLASSICATION_SYSTEM;
|
||||
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
|
||||
chk = updateChecksum(chk, (uint8_t *)&record, sizeof(record));
|
||||
config_streamer_write(&streamer, reg->address, regSize);
|
||||
chk = updateChecksum(chk, reg->address, regSize);
|
||||
} else {
|
||||
// write one instance for each profile
|
||||
for (uint8_t profileIndex = 0; profileIndex < MAX_PROFILE_COUNT; profileIndex++) {
|
||||
record.flags = 0;
|
||||
|
||||
record.flags |= ((profileIndex + 1) & CR_CLASSIFICATION_MASK);
|
||||
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
|
||||
chk = updateChecksum(chk, (uint8_t *)&record, sizeof(record));
|
||||
const uint8_t *address = reg->address + (regSize * profileIndex);
|
||||
config_streamer_write(&streamer, address, regSize);
|
||||
chk = updateChecksum(chk, address, regSize);
|
||||
}
|
||||
}
|
||||
if (status == HAL_OK) {
|
||||
break;
|
||||
}
|
||||
|
||||
configFooter_t footer = {
|
||||
.terminator = 0,
|
||||
};
|
||||
|
||||
config_streamer_write(&streamer, (uint8_t *)&footer, sizeof(footer));
|
||||
chk = updateChecksum(chk, (uint8_t *)&footer, sizeof(footer));
|
||||
|
||||
// append checksum now
|
||||
chk = ~chk;
|
||||
config_streamer_write(&streamer, &chk, sizeof(chk));
|
||||
|
||||
config_streamer_flush(&streamer);
|
||||
|
||||
bool success = config_streamer_finish(&streamer) == 0;
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
void writeConfigToEEPROM(void)
|
||||
{
|
||||
bool success = false;
|
||||
// write it
|
||||
for (int attempt = 0; attempt < 3 && !success; attempt++) {
|
||||
if (writeSettingsToEEPROM()) {
|
||||
success = true;
|
||||
}
|
||||
}
|
||||
HAL_FLASH_Lock();
|
||||
|
||||
if (success && isEEPROMContentValid()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Flash write failed - just die now
|
||||
if (status != HAL_OK || !isEEPROMContentValid()) {
|
||||
failureMode(FAILURE_FLASH_WRITE_FAILED);
|
||||
}
|
||||
|
||||
resumeRxSignal();
|
||||
}
|
||||
#else
|
||||
void writeEEPROM(void)
|
||||
{
|
||||
// Generate compile time error if the config does not fit in the reserved area of flash.
|
||||
BUILD_BUG_ON(sizeof(master_t) > FLASH_TO_RESERVE_FOR_CONFIG);
|
||||
|
||||
FLASH_Status status = 0;
|
||||
uint32_t wordOffset;
|
||||
int8_t attemptsRemaining = 3;
|
||||
|
||||
suspendRxSignal();
|
||||
|
||||
// prepare checksum/version constants
|
||||
masterConfig.version = EEPROM_CONF_VERSION;
|
||||
masterConfig.size = sizeof(master_t);
|
||||
masterConfig.magic_be = 0xBE;
|
||||
masterConfig.magic_ef = 0xEF;
|
||||
masterConfig.chk = 0; // erase checksum before recalculating
|
||||
masterConfig.chk = calculateChecksum((const uint8_t *) &masterConfig, sizeof(master_t));
|
||||
|
||||
// write it
|
||||
FLASH_Unlock();
|
||||
while (attemptsRemaining--) {
|
||||
#if defined(STM32F4)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
|
||||
#elif defined(STM32F303)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
|
||||
#elif defined(STM32F10X)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
|
||||
#endif
|
||||
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
|
||||
if (wordOffset % FLASH_PAGE_SIZE == 0) {
|
||||
#if defined(STM32F40_41xxx)
|
||||
status = FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); //0x08080000 to 0x080A0000
|
||||
#elif defined (STM32F411xE)
|
||||
status = FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); //0x08060000 to 0x08080000
|
||||
#else
|
||||
status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
|
||||
#endif
|
||||
if (status != FLASH_COMPLETE) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
status = FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS + wordOffset,
|
||||
*(uint32_t *) ((char *) &masterConfig + wordOffset));
|
||||
if (status != FLASH_COMPLETE) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (status == FLASH_COMPLETE) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
FLASH_Lock();
|
||||
|
||||
// Flash write failed - just die now
|
||||
if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
|
||||
failureMode(FAILURE_FLASH_WRITE_FAILED);
|
||||
}
|
||||
|
||||
resumeRxSignal();
|
||||
}
|
||||
#endif
|
||||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
// Sanity check
|
||||
if (!isEEPROMContentValid())
|
||||
failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
|
||||
|
||||
suspendRxSignal();
|
||||
|
||||
// Read flash
|
||||
memcpy(&masterConfig, (char *) CONFIG_START_FLASH_ADDRESS, sizeof(master_t));
|
||||
|
||||
if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) // sanity check
|
||||
masterConfig.current_profile_index = 0;
|
||||
|
||||
setProfile(masterConfig.current_profile_index);
|
||||
|
||||
validateAndFixConfig();
|
||||
activateConfig();
|
||||
|
||||
resumeRxSignal();
|
||||
failureMode(FAILURE_FLASH_WRITE_FAILED);
|
||||
}
|
||||
|
|
|
@ -19,7 +19,6 @@
|
|||
|
||||
#define EEPROM_CONF_VERSION 154
|
||||
|
||||
void initEEPROM(void);
|
||||
void writeEEPROM();
|
||||
void readEEPROM(void);
|
||||
bool isEEPROMContentValid(void);
|
||||
bool loadEEPROM(void);
|
||||
void writeConfigToEEPROM(void);
|
||||
|
|
|
@ -17,7 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "flight/pid.h"
|
||||
|
|
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
#ifndef __UNIQL
|
||||
# define __UNIQL_CONCAT2(x,y) x ## y
|
||||
# define __UNIQL_CONCAT(x,y) __UNIQL_CONCAT2(x,y)
|
||||
# define __UNIQL(x) __UNIQL_CONCAT(x,__LINE__)
|
||||
#endif
|
||||
|
||||
// overwrite _name with data passed as arguments. This version forces GCC to really copy data
|
||||
// It is not possible to use multiple RESET_CONFIGs on single line (__UNIQL limitation)
|
||||
#define RESET_CONFIG(_type, _name, ...) \
|
||||
static const _type __UNIQL(_reset_template_) = { \
|
||||
__VA_ARGS__ \
|
||||
}; \
|
||||
memcpy((_name), &__UNIQL(_reset_template_), sizeof(*(_name))); \
|
||||
/**/
|
||||
|
||||
// overwrite _name with data passed as arguments. GCC is alloved to set structure field-by-field
|
||||
#define RESET_CONFIG_2(_type, _name, ...) \
|
||||
*(_name) = (_type) { \
|
||||
__VA_ARGS__ \
|
||||
}; \
|
||||
/**/
|
|
@ -0,0 +1,177 @@
|
|||
/*
|
||||
* 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 "config_streamer.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#if !defined(FLASH_PAGE_SIZE)
|
||||
# if defined(STM32F10X_MD)
|
||||
# define FLASH_PAGE_SIZE (0x400)
|
||||
# elif defined(STM32F10X_HD)
|
||||
# define FLASH_PAGE_SIZE (0x800)
|
||||
# elif defined(STM32F303xC)
|
||||
# define FLASH_PAGE_SIZE (0x800)
|
||||
# elif defined(STM32F40_41xxx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
# elif defined (STM32F411xE)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
# elif defined(STM32F745xx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
||||
# elif defined(STM32F746xx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
||||
# elif defined(UNIT_TEST)
|
||||
# define FLASH_PAGE_SIZE (0x400)
|
||||
# else
|
||||
# error "Flash page size not defined for target."
|
||||
# endif
|
||||
#endif
|
||||
|
||||
void config_streamer_init(config_streamer_t *c)
|
||||
{
|
||||
memset(c, 0, sizeof(*c));
|
||||
}
|
||||
|
||||
void config_streamer_start(config_streamer_t *c, uintptr_t base, int size)
|
||||
{
|
||||
// base must start at FLASH_PAGE_SIZE boundary
|
||||
c->address = base;
|
||||
c->size = size;
|
||||
if (!c->unlocked) {
|
||||
#if defined(STM32F7)
|
||||
HAL_FLASH_Unlock();
|
||||
#else
|
||||
FLASH_Unlock();
|
||||
#endif
|
||||
c->unlocked = true;
|
||||
}
|
||||
|
||||
#if defined(STM32F10X)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
|
||||
#elif defined(STM32F303)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
|
||||
#elif defined(STM32F4)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
|
||||
#elif defined(STM32F7)
|
||||
// NOP
|
||||
#elif defined(UNIT_TEST)
|
||||
// NOP
|
||||
#else
|
||||
# error "Unsupported CPU"
|
||||
#endif
|
||||
c->err = 0;
|
||||
}
|
||||
|
||||
#if defined(STM32F7)
|
||||
static int write_word(config_streamer_t *c, uint32_t value)
|
||||
{
|
||||
if (c->err != 0) {
|
||||
return c->err;
|
||||
}
|
||||
|
||||
HAL_StatusTypeDef status;
|
||||
if (c->address % FLASH_PAGE_SIZE == 0) {
|
||||
FLASH_EraseInitTypeDef EraseInitStruct = {0};
|
||||
EraseInitStruct.TypeErase = FLASH_TYPEERASE_SECTORS;
|
||||
EraseInitStruct.VoltageRange = FLASH_VOLTAGE_RANGE_3; // 2.7-3.6V
|
||||
EraseInitStruct.Sector = (FLASH_SECTOR_TOTAL-1);
|
||||
EraseInitStruct.NbSectors = 1;
|
||||
uint32_t SECTORError;
|
||||
status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError);
|
||||
if (status != HAL_OK){
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, c->address, value);
|
||||
if (status != HAL_OK) {
|
||||
return -2;
|
||||
}
|
||||
c->address += sizeof(value);
|
||||
return 0;
|
||||
}
|
||||
#else
|
||||
static int write_word(config_streamer_t *c, uint32_t value)
|
||||
{
|
||||
if (c->err != 0) {
|
||||
return c->err;
|
||||
}
|
||||
|
||||
FLASH_Status status;
|
||||
|
||||
if (c->address % FLASH_PAGE_SIZE == 0) {
|
||||
#if defined(STM32F40_41xxx)
|
||||
status = FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); //0x08080000 to 0x080A0000
|
||||
#elif defined (STM32F411xE)
|
||||
status = FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); //0x08060000 to 0x08080000
|
||||
#else
|
||||
status = FLASH_ErasePage(c->address);
|
||||
#endif
|
||||
if (status != FLASH_COMPLETE) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
status = FLASH_ProgramWord(c->address, value);
|
||||
if (status != FLASH_COMPLETE) {
|
||||
return -2;
|
||||
}
|
||||
c->address += sizeof(value);
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
int config_streamer_write(config_streamer_t *c, const uint8_t *p, uint32_t size)
|
||||
{
|
||||
for (const uint8_t *pat = p; pat != (uint8_t*)p + size; pat++) {
|
||||
c->buffer.b[c->at++] = *pat;
|
||||
|
||||
if (c->at == sizeof(c->buffer)) {
|
||||
c->err = write_word(c, c->buffer.w);
|
||||
c->at = 0;
|
||||
}
|
||||
}
|
||||
return c->err;
|
||||
}
|
||||
|
||||
int config_streamer_status(config_streamer_t *c)
|
||||
{
|
||||
return c->err;
|
||||
}
|
||||
|
||||
int config_streamer_flush(config_streamer_t *c)
|
||||
{
|
||||
if (c->at != 0) {
|
||||
memset(c->buffer.b + c->at, 0, sizeof(c->buffer) - c->at);
|
||||
c->err = write_word(c, c->buffer.w);
|
||||
c->at = 0;
|
||||
}
|
||||
return c-> err;
|
||||
}
|
||||
|
||||
int config_streamer_finish(config_streamer_t *c)
|
||||
{
|
||||
if (c->unlocked) {
|
||||
#if defined(STM32F7)
|
||||
HAL_FLASH_Lock();
|
||||
#else
|
||||
FLASH_Lock();
|
||||
#endif
|
||||
c->unlocked = false;
|
||||
}
|
||||
return c->err;
|
||||
}
|
|
@ -0,0 +1,45 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
// Streams data out to the EEPROM, padding to the write size as
|
||||
// needed, and updating the checksum as it goes.
|
||||
|
||||
typedef struct config_streamer_s {
|
||||
uintptr_t address;
|
||||
int size;
|
||||
union {
|
||||
uint8_t b[4];
|
||||
uint32_t w;
|
||||
} buffer;
|
||||
int at;
|
||||
int err;
|
||||
bool unlocked;
|
||||
} config_streamer_t;
|
||||
|
||||
void config_streamer_init(config_streamer_t *c);
|
||||
|
||||
void config_streamer_start(config_streamer_t *c, uintptr_t base, int size);
|
||||
int config_streamer_write(config_streamer_t *c, const uint8_t *p, uint32_t size);
|
||||
int config_streamer_flush(config_streamer_t *c);
|
||||
|
||||
int config_streamer_finish(config_streamer_t *c);
|
||||
int config_streamer_status(config_streamer_t *c);
|
|
@ -91,6 +91,7 @@
|
|||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#ifndef DEFAULT_RX_FEATURE
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
|
||||
|
@ -1129,12 +1130,40 @@ void validateAndFixGyroConfig(void)
|
|||
}
|
||||
}
|
||||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
suspendRxSignal();
|
||||
|
||||
// Sanity check, read flash
|
||||
if (!loadEEPROM()) {
|
||||
failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
|
||||
}
|
||||
|
||||
pgActivateProfile(getCurrentProfile());
|
||||
|
||||
// setControlRateProfile(rateProfileSelection()->defaultRateProfileIndex);
|
||||
setControlRateProfile(0);
|
||||
|
||||
validateAndFixConfig();
|
||||
activateConfig();
|
||||
|
||||
resumeRxSignal();
|
||||
}
|
||||
|
||||
void writeEEPROM(void)
|
||||
{
|
||||
suspendRxSignal();
|
||||
|
||||
writeConfigToEEPROM();
|
||||
|
||||
resumeRxSignal();
|
||||
}
|
||||
|
||||
void ensureEEPROMContainsValidData(void)
|
||||
{
|
||||
if (isEEPROMContentValid()) {
|
||||
return;
|
||||
}
|
||||
|
||||
resetEEPROM();
|
||||
}
|
||||
|
||||
|
|
|
@ -69,7 +69,10 @@ void setPreferredBeeperOffMask(uint32_t mask);
|
|||
|
||||
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
|
||||
|
||||
void initEEPROM(void);
|
||||
void resetEEPROM(void);
|
||||
void readEEPROM(void);
|
||||
void writeEEPROM();
|
||||
void ensureEEPROMContainsValidData(void);
|
||||
|
||||
void saveConfigAndNotify(void);
|
||||
|
@ -80,6 +83,8 @@ void activateConfig(void);
|
|||
uint8_t getCurrentProfile(void);
|
||||
void changeProfile(uint8_t profileIndex);
|
||||
void setProfile(uint8_t profileIndex);
|
||||
struct profile_s;
|
||||
void resetProfile(struct profile_s *profile);
|
||||
|
||||
uint8_t getCurrentControlRateProfile(void);
|
||||
void changeControlRateProfile(uint8_t profileIndex);
|
||||
|
|
|
@ -105,7 +105,6 @@
|
|||
#endif
|
||||
|
||||
extern uint16_t cycleTime; // FIXME dependency on mw.c
|
||||
extern void resetProfile(profile_t *profile);
|
||||
|
||||
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;
|
||||
|
|
|
@ -81,6 +81,19 @@ SECTIONS
|
|||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
.pg_registry :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_registry_start = .);
|
||||
KEEP (*(.pg_registry))
|
||||
KEEP (*(SORT(.pg_registry.*)))
|
||||
PROVIDE_HIDDEN (__pg_registry_end = .);
|
||||
} >FLASH
|
||||
.pg_resetdata :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_resetdata_start = .);
|
||||
KEEP (*(.pg_resetdata))
|
||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
|
Loading…
Reference in New Issue