With bootloader

This commit is contained in:
lulko 2025-03-17 15:43:34 +03:00
parent b5ff05bed6
commit 023026987c
8 changed files with 312 additions and 141 deletions

View file

@ -1,4 +1,9 @@
#include "flash.h"
#include <stdbool.h>
static uint32_t write_ptr = SECTOR_6;
void flash_unlock(){
@ -73,16 +78,78 @@ void flash_program_word(uint32_t address,uint32_t data,uint32_t byte_len){
FLASH->CR &= ~FLASH_CR_PG;
}
void flash_write(uint32_t addr, FLASH_RECORD* record){
uint8_t flash_read_word(uint32_t address){
// Check if address is valid
if(address < FLASH_BASE || address > FLASH_END) {
return 0;
uint32_t* data = (uint32_t*)record;
uint32_t size = FLASH_RECORD_SIZE / 4; //count words in struct
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Read byte from flash memory
return *((volatile uint8_t*)address);
// Set program bit and write data to flash
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
for(int i = 0;i < size;i++){
*(volatile uint32_t*)(addr + i * 4) = data[i];
}
// Clear program bit
FLASH->CR &= ~FLASH_CR_PG;
flash_lock();
}
// Wait if flash
// Wait if flash
bool validate_crc(FLASH_RECORD* crc){
if(crc->crc == 0x6933)
return true;
return false;
}
/* read struct from FLASH */
void flash_read(uint32_t addr,FLASH_RECORD* ptr){
uint32_t* flash_ptr = (uint32_t*)addr;
uint32_t* dest = (uint32_t*)ptr;
for (int i = 0; i < FLASH_RECORD_SIZE / 4; i++) {
dest[i] = flash_ptr[i];
}
}
/* Поиск актуального адреса во флэш памяти */
FLASH_RECORD load_params(){
__disable_irq();
FLASH_RECORD latest = {0};
FLASH_RECORD res;
for(uint32_t addr = SECTOR_6;addr < SECTOR_6_END;addr +=FLASH_RECORD_SIZE) {
flash_read(addr,&res);
if (!validate_crc(&res))
break;
else if(res.data_id == addr_id) {
latest = res;
}
}
__enable_irq();
return latest;
}
/**
* @brief Записывает страницу данных во флеш-память
* @param data: Указатель на буфер с данными
* @param len: Длина данных в байтах (должна быть кратна 4)
* @retval bool: true - успех, false - ошибка
*/
void write_flash_page(const uint8_t* data, uint16_t len) { // Добавлен const
flash_unlock();
for (uint16_t i = 0; i < len; i += 4) {
uint32_t word;
memcpy(&word, &data[i], 4); // Безопасное копирование
HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, write_ptr + i, word);
}
flash_lock();
}

View file

@ -1,31 +1,52 @@
#ifndef FLASH_H_
#define FLASH_H_
#include "stm32f446xx.h"
#include "hal_conf_extra.h"
/* for addr in FLASH */
typedef struct{
uint32_t write_ptr_now;
uint16_t crc;
uint8_t value;
uint8_t data_id; // data_id = id register of can
}FLASH_RECORD;
enum {
addr_id = 0
};
#define FLASH_RECORD_SIZE sizeof(FLASH_RECORD) //size flash struct
#define PARAM_COUNT 1 // count data in flash
#define FLAG_BOOT 0x08060000 // Адрес хранения флага для обновления прошивки
#define UPDATE_FLAG 0xDEADBEEF // Уникальное 32-битное значение
#define APP_ADDRESS 0x08004000 // Адрес основной прошивки
#define BOOT_CAN_ID 0x721 // CAN ID бутлоадера
#define BOOT_CAN_END 0x722 // CAN ID завершения передачи
#define DATA_CAN_ID 0x730 // CAN ID данных
#define MAX_FW_SIZE 0x3FFF // Макс. размер прошивки (256KB)
// Flash sectors for STM32F407
#define BOOT 0x08000000 // 16KB - Bootloader
#define APP_ADDR 0x08004000 // 16KB - Application
#define SECTOR_2 0x08008000 // 16KB
#define SECTOR_3 0x0800C000 // 16KB
#define SECTOR_4 0x08010000 // 64KB
#define SECTOR_5 0x08020000 // 128KB
#define SECTOR_6 0x08040000 // 128KB
#define SECTOR_7 0x08060000 // 128KB
#define SECTOR_2 0x08008000 // 16KB
#define SECTOR_3 0x0800C000 // 16KB
#define SECTOR_4 0x08010000 // 64KB
#define SECTOR_5 0x08020000 // 128KB
#define SECTOR_6 0x08040000 // 128KB
#define SECTOR_6_END (SECTOR_6 + 128 * 1024) // sector 6 end
#define SECTOR_7 0x08060000
#define FLAG_BOOT (0x08040000 + 4)
// Flash keys for unlocking flash memory
#define FLASH_KEY1 0x45670123
#define FLASH_KEY2 0xCDEF89AB
//FLASH SET ONE PROGRAMM WORD
#define FLASH_8BYTE FLASH->CR &= ~FLASH_CR_PSIZE & ~FLASH_CR_PSIZE_1
#define FLASH_32BYTE FLASH->CR |= FLASH_CR_PSIZE | FLASH_CR_PSIZE_0
// Flash command bits
#define FLASH_LOCK FLASH->CR |= FLASH_CR_LOCK
#define FLASH_UNLOCK FLASH->KEYR = FLASH_KEY1; FLASH->KEYR = FLASH_KEY2
#define FLASH_32BYTE \
FLASH->CR = (FLASH->CR & ~FLASH_CR_PSIZE) | (0x2 << FLASH_CR_PSIZE_Pos)
// Flash status flags
#define FLASH_BUSY (FLASH->SR & FLASH_SR_BSY)
@ -37,10 +58,14 @@ typedef void(*pFunction)(void);
// Function prototypes
void flash_unlock(void);
void flash_lock(void);
void flash_erase_sector(uint8_t sector);
void flash_program_word(uint32_t address, uint32_t data,uint32_t byte_len);
void erase_sector(uint8_t sector);
void flash_program_word(uint32_t address,uint32_t data,uint32_t byte_len);
void write_flash_page(const uint8_t *data, uint16_t len);
void flash_read(uint32_t addr,FLASH_RECORD* ptr);
bool validate_crc(FLASH_RECORD* crc);
uint8_t flash_read_word(uint32_t address);
void flash_write(uint32_t addr, FLASH_RECORD* record);
FLASH_RECORD load_params();
//bool write_flash_page(const uint8_t* data, uint16_t len);
#endif /* FLASH_H_ */

View file

@ -1,110 +1,146 @@
#include <Arduino.h>
#include <STM32_CAN.h>
//#include "CRC32.h"
#include "flash.h"
//CRC
// put function declarations here:
STM32_CAN Can(CAN2, DEF);
static CAN_message_t CAN_TX_msg;
static CAN_message_t CAN_inMsg;
void buff_data_can(size_t len,size_t len_frame) {
uint8_t buff[len] = {0};
uint32_t buff_32[len / 4] = {0};
uint32_t bias = 0;
while(Can.read(CAN_inMsg)) {
for(size_t i = 0; i < len_frame; i++,bias++) {
buff[bias] = CAN_inMsg.buf[i];
/* if data from len no end blink led 5 count and stop programm */
if(bias >= len){
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
GPIOC->MODER |= GPIO_MODER_MODE10_0;
for(int i = 0;i < 5;i++){
GPIOC->ODR ^= GPIO_ODR_OD10;
HAL_Delay(500);
}
return;
}
}
}
/* from 8byte to 32 byte */
for(size_t i = 0; i < len / 4; i++) {
buff_32[i] = (buff[i*4] << 24) |
(buff[i*4 + 1] << 16) |
(buff[i*4 + 2] << 8) |
buff[i*4 + 3];
}
/* CRC check */
/* Work with FLASH */
FLASH_UNLOCK;
uint32_t address = (uint32_t)APP_ADDR;
FLASH_32BYTE;
for(size_t i = 0; i < len; i++) {
if(i == 0) {
flash_erase_sector(1); // Erase sector 1 (APP_ADDR)
while(FLASH_BUSY);
}
flash_program_word(address + (i * 4), buff_32[i],0);
while(FLASH_BUSY);
}
flash_lock();
}
volatile bool fw_update = false;
volatile uint32_t fw_size = 0;
volatile uint32_t fw_crc = 0;
volatile uint32_t write_ptr = APP_ADDRESS;
static FLASH_RECORD flash_record = {0};
// Прототипы функций
void jump_to_app();
void process_can_message(const CAN_message_t &msg);
void erase_flash_pages();
bool verify_firmware();
void send_ack(uint8_t status);
void setup() {
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
Can.begin();
Can.setBaudRate(1000000);
// put your setup code here, to run once:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
GPIOC->MODER |= GPIO_MODER_MODE10_0 | GPIO_MODER_MODE11_0;;
GPIOC->ODR |= GPIO_ODR_OD11;
// Инициализация периферии
Serial.begin(115200);
Can.begin(1000000); // 1 Mbps
Can.setFilter(0,BOOT_CAN_ID,STD);
// Настройка GPIO
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
GPIOC->MODER |= GPIO_MODER_MODE10_0 | GPIO_MODER_MODE11_0;
GPIOC->ODR |= GPIO_ODR_OD11;
// Проверка флага обновления
/*erase_sector(6);
flash_program_word(FLAG_BOOT,0xDEADBEEF,0);
flash_record.data_id = addr_id;
flash_record.crc = 0x6933;
flash_record.value = 0x69;
flash_record.write_ptr_now = SECTOR_6;*/
flash_write(SECTOR_6, &flash_record);
flash_record = load_params();
/* Добавить проверку адреса, т.е во время отправки запроса прошивки по CAN
мы сохраняем как флаг, так и аддрес устройства к которому будет обращатлься во
время прошивки */
if(*(volatile uint32_t*)(FLAG_BOOT) == UPDATE_FLAG) {
fw_update = true;
GPIOC->ODR |= GPIO_ODR_OD10; // Индикация обновления
erase_flash_pages();
} else {
jump_to_app();
}
}
void loop() {
flash_program_word(FLAG_BOOT,1,1);
for(int i = 0; i < 4; i++ ) {
GPIOC->ODR ^= GPIO_ODR_OD11;
HAL_Delay(500);
}
if(FLAG_BOOT == 1){
while (Can.read(CAN_inMsg)){
// buff_data_can(32000,8);
}
/* Go to application */
volatile uint32_t* appjump = (volatile uint32_t*)APP_ADDR;
uint32_t msp_start = *(appjump);
uint32_t reset_handler = *(appjump + 1);
pFunction start = (pFunction)reset_handler;
__set_MSP(msp_start);
start();
}
// put your main code here, to run repeatedly:
if(fw_update) {
CAN_message_t msg;
if(Can.read(msg)) {
process_can_message(msg);
}
}
}
void process_can_message(const CAN_message_t &msg) {
switch(msg.id) {
case BOOT_CAN_ID:
if(msg.buf[0] == 0x01) { // Старт передачи
fw_size = *(uint32_t*)&msg.buf[1]; //размер прошивки тип 4 байта
fw_crc = *(uint32_t*)&msg.buf[5]; //crc
write_ptr = APP_ADDRESS;
send_ack(0x01);
}
break;
case DATA_CAN_ID: // Пакет данных
if(write_ptr < (APP_ADDRESS + fw_size)) {
write_flash_page((const uint8_t*)msg.buf, msg.len);
write_ptr += msg.len;
send_ack(0x02);
}
break;
case BOOT_CAN_END: // Завершение передачи
if(verify_firmware()) {
erase_sector(7); // Сброс флага
send_ack(0xAA);
NVIC_SystemReset();
} else {
send_ack(0x55);
}
break;
}
}
void jump_to_app() {
typedef void (*app_entry_t)(void);
auto app_entry = (app_entry_t)(*(volatile uint32_t*)(APP_ADDRESS + 4));
// SCB->VTOR = APP_ADDRESS;
__set_MSP(*(volatile uint32_t*)APP_ADDRESS);
app_entry();
}
void erase_flash_pages() {
FLASH_EraseInitTypeDef erase;
erase.TypeErase = FLASH_TYPEERASE_SECTORS;
erase.Sector = FLASH_SECTOR_1;
erase.NbSectors = 5;
erase.VoltageRange = FLASH_VOLTAGE_RANGE_3;
uint32_t error;
flash_unlock();
HAL_FLASHEx_Erase(&erase, &error);
flash_lock();
}
// CRC16 implementation for STM32
uint16_t CalculateCRC16(const uint8_t* data, uint32_t length) {
uint16_t crc = 0xFFFF;
while (length--) {
crc ^= (uint16_t)(*data++) << 8;
for(uint8_t i = 0; i < 8; i++) {
crc = crc & 0x8000 ? (crc << 1) ^ 0x8005 : crc << 1;
}
}
return crc;
}
bool verify_firmware() {
uint32_t calculated_crc = 0;
calculated_crc = CalculateCRC16((uint8_t*)fw_crc,fw_size);
if(calculated_crc != (uint16_t)fw_crc)
return false;
// Реализация проверки CRC
// ...
// return (calculated_crc == fw_crc);
return true;
}
void send_ack(uint8_t status) {
CAN_message_t ack;
ack.id = BOOT_CAN_ID + 2;
ack.len = 1;
ack.buf[0] = status;
Can.write(ack);
}

View file

@ -0,0 +1,38 @@
#ifndef REG_CAH_H_
#define REG_CAH_H_
#define APP_ADDR 0x0800400 // 16KB - Application
#define ADDR_VAR 0x8040000
#define REG_READ 0x99
#define REG_WRITE 0xA0
/* Startup ID device */
#define START_ID 0x00
/* CAN REGISTER ID */
#define REG_ID 0x01
#define REG_BAUDRATE 0x02
#define REG_MOTOR_POSPID_Kp 0x30
#define REG_MOTOR_POSPID_Ki 0x31
#define REG_MOTOR_POSPID_Kd 0x32
#define REG_MOTOR_VELPID_Kp 0x40
#define REG_MOTOR_VELPID_Ki 0x41
#define REG_MOTOR_VELPID_Kd 0x42
#define REG_MOTOR_IMPPID_Kp 0x50
#define REG_MOTOR_IMPPID_Kd 0x51
#define REG_RESET 0x88
#define REG_LED_BLINK 0x8B
#define FOC_STATE 0x60
#define MOTOR_VELOCITY 0x70
#define MOTOR_ENABLED 0x71
#define MOTOR_ANGLE 0x72
#endif // REG_CAH_H_

View file

@ -10,6 +10,7 @@ typedef struct{
uint8_t data_id; // data_id = id register of can
uint8_t value;
uint16_t crc;
uint32_t write_ptr_now;
}FLASH_RECORD;
enum {
addr_id = 0,
@ -29,6 +30,7 @@ kp_id = 2,
#define SECTOR_4 0x08010000 // 64KB
#define SECTOR_5 0x08020000 // 128KB
#define SECTOR_6 0x08040000 // 128KB
#define SECTOR_6_END (SECTOR_6 + 128 * 1024) // sector 6 end
#define SECTOR_7 0x08060000 // 128KB

View file

@ -3,10 +3,7 @@
#define APP_ADDR 0x0800400 // 16KB - Application
#define ADDR_VAR 0x8040000
#define ADDR_VAR_ID ADDR_VAR
#define ADDR_VAR_P (ADDR_VAR + 1)
#define ADDR_VAR_I (ADDR_VAR + 2)
#define ADDR_VAR_D (ADDR_VAR + 3)
#define REG_READ 0x99
#define REG_WRITE 0xA0

View file

@ -165,19 +165,24 @@ void write_param(uint8_t param_id, uint8_t val){
__disable_irq();
flash_write(write_ptr,&param_flash);
write_ptr += FLASH_RECORD_SIZE;
flash_program_word(SECTOR_7 - sizeof(uint32_t),write_ptr,0);
// flash_program_word(SECTOR_7 - sizeof(uint32_t),write_ptr,0);
}
FLASH_RECORD* load_params(){
__disable_irq();
static FLASH_RECORD latest[PARAM_COUNT] = {0};
FLASH_RECORD res;
for(uint32_t addr = SECTOR_6;addr < SECTOR_7;addr +=FLASH_RECORD_SIZE) {
for(uint32_t addr = SECTOR_6;addr < SECTOR_6_END;addr +=FLASH_RECORD_SIZE) {
flash_read(addr,&res);
if (validate_crc(&res))
if (!validate_crc(&res))
break;
else{
latest[res.data_id] = res;
write_ptr = addr;
}
}
__enable_irq();
return latest;
}

View file

@ -103,7 +103,7 @@ void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
void send_velocity() {
float current_velocity = motor.shaftVelocity();
uint8_t id = *(volatile uint8_t*)ADDR_VAR_ID;
uint8_t id = *(volatile uint8_t*)ADDR_VAR;
CAN_TX_msg.id = id;
CAN_TX_msg.buf[0] = 'V';
CAN_TX_msg.len = 5;
@ -113,7 +113,7 @@ void send_velocity() {
void send_angle() {
float current_angle = motor.shaftAngle();
uint8_t id = *(volatile uint8_t*)ADDR_VAR_ID;
uint8_t id = *(volatile uint8_t*)ADDR_VAR;
CAN_TX_msg.id = id;
CAN_TX_msg.buf[0] = 'A';
CAN_TX_msg.len = 5;
@ -122,7 +122,7 @@ void send_angle() {
}
void send_motor_enabled() {
uint8_t id = *(volatile uint8_t*)ADDR_VAR_ID;
uint8_t id = *(volatile uint8_t*)ADDR_VAR;
CAN_TX_msg.id = id;
CAN_TX_msg.buf[0] = 'E';
memcpy(&CAN_TX_msg.buf[1], &motor_control_inputs.motor_enabled,
@ -131,7 +131,7 @@ void send_motor_enabled() {
}
void send_foc_state() {
uint8_t id = *(volatile uint8_t*)ADDR_VAR_ID;
uint8_t id = *(volatile uint8_t*)ADDR_VAR;
CAN_TX_msg.id = id;
CAN_TX_msg.buf[0] = 'F';
memcpy(&CAN_TX_msg.buf[1], &motor_control_inputs.foc_state,
@ -142,7 +142,7 @@ Can.write(CAN_TX_msg);
void send_id() {
/* data for reading of firmware */
uint8_t id = *(volatile uint8_t*)ADDR_VAR_ID;
uint8_t id = *(volatile uint8_t*)ADDR_VAR;
CAN_TX_msg.id = id;
CAN_TX_msg.buf[0] = 'I';
memcpy(&CAN_TX_msg.buf[0], &id, sizeof(id));
@ -195,9 +195,7 @@ void send_data() {
void listen_can() {
flash_rec = load_params();
for(int i = 0;i < PARAM_COUNT;i++)
flash_buf[i] = flash_rec[i];
uint8_t reg_id = CAN_inMsg.buf[0]; //reg id
if (CAN_inMsg.id == flash_buf[addr_id].value) {
if (CAN_inMsg.buf[1] == REG_WRITE) {
@ -316,6 +314,9 @@ void setup() {
pEraseInit.Sector = ADDR_VAR; // Начальная страница
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE_3;*/
flash_rec = load_params();
for(int i = 0;i < PARAM_COUNT;i++)
flash_buf[i] = flash_rec[i];
}
void loop() {
foc_step(&motor, &command);