Fix test and work with bootloader

Fix tests

Fix commit
This commit is contained in:
Valentin Dabstep 2025-06-03 10:48:29 +03:00
parent e9fb2656b8
commit 05621e7150
11 changed files with 128 additions and 54 deletions

View file

@ -0,0 +1,11 @@
Import("env")
hex_name = "bootloader.hex"
# Custom HEX from ELF
env.AddPostAction(
"$BUILD_DIR/${PROGNAME}.elf",
env.VerboseAction(" ".join([
"$OBJCOPY", "-O", "ihex", "-R", ".eeprom",
"$BUILD_DIR/${PROGNAME}.elf", "$BUILD_DIR/{}".format(hex_name)
]), "Building $BUILD_DIR/{}".format(hex_name))
)

View file

@ -34,14 +34,13 @@ union{
#define FLASH_RECORD_SIZE sizeof(FLASH_RECORD) //size flash struct
// Flash sectors for STM32F407
#define APP_ADDRESS 0x08008000 // Адрес основной прошивки
// #define FLAG_BOOT 0x08060000 // Адрес хранения флага для обновления прошивки
#define UPDATE_FLAG 0xDEADBEEF // Уникальное 32-битное значение
#define BOOT_CAN_ID 0x01 // CAN ID бутлоадера
#define BOOT_CAN_END 0x02 // CAN ID завершения передачи
#define DATA_CAN_ID 0x03 // CAN ID данных
#define ACK_CAN_ID 0x05 // CAN ID подтверждения
#define MAX_FW_SIZE 0x3FFF // Макс. размер прошивки (256KB)
#define APP_ADDRESS 0x08008000
#define UPDATE_FLAG 0xDEADBEEF // flag forz update firmware
#define BOOT_CAN_ID 0x01 // CAN ID bootloader
#define BOOT_CAN_END 0x02 // CAN ID end of transfer
#define DATA_CAN_ID 0x03 // CAN ID packet data
#define ACK_CAN_ID 0x05 // CAN ID acknowledge
#define MAX_FW_SIZE 0x3FFF // Max size firmware = 256 kB
#define PARAM_COUNT 5 // count data in flash
#define SECTOR_6 0x08040000 // 128KB
#define SECTOR_6_END (SECTOR_6 + 128 * 1024) // sector 6 end

View file

@ -25,4 +25,7 @@ build_flags =
lib_deps =
askuric/Simple FOC@^2.3.4
pazi88/STM32_CAN@^1.1.2
extra_scripts = pre:gen_compile_commands.py
extra_scripts =
pre:gen_compile_commands.py
post:hex_compile.py

View file

@ -25,9 +25,9 @@ void process_can_message(const CAN_message_t &msg);
void erase_flash_pages();
bool verify_firmware();
void send_ack(uint8_t status);
bool is_app_valid();
void setup() {
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
@ -36,9 +36,7 @@ void setup() {
TIM_TypeDef *Instance = TIM2;
HardwareTimer *SendTimer = new HardwareTimer(Instance);
SendTimer->setOverflow(100, HERTZ_FORMAT); // 50 Hz
// SendTimer->attachInterrupt(process_can_message);
SendTimer->resume();
// Разрешить все ID (маска 0x00000000)
Can.setFilter(0, 0, STD);
// Настройка GPIO
@ -48,22 +46,20 @@ void setup() {
GPIOC->ODR |= GPIO_ODR_OD10;
flash_record = load_params();
/* Добавить проверку адреса, т.е во время отправки запроса прошивки по CAN
мы сохраняем как флаг, так и аддрес устройства к которому будет обращатлься во
время прошивки */
if(flash_record[firmw].value == UPDATE_FLAG) {
fw_update = true;
for(int i = 0; i < 5;i++){
GPIOC->ODR ^= GPIO_ODR_OD10; // Индикация обновления
GPIOC->ODR ^= GPIO_ODR_OD10; // Indecate message
delay(100);
}
write_param(firmw,0); //reset flasg
// write_param(firmw,0); //reset flasg
erase_flash_pages();
}
else
jump_to_app();
else{
// for st-link update, because he doesnt reset flag_update
if(is_app_valid()) jump_to_app(); //firmware exist
else fw_update = true; //firmware doesnt exist, but we in bootloader
}
GPIOC->ODR |= GPIO_ODR_OD10;
}
@ -72,24 +68,24 @@ void setup() {
void process_can_message(const CAN_message_t &msg) {
msg_id = msg.id;
/* 0x691
69 - адрес устройства
1 - что делать дальше с данными */
/* 0x697
69 - slave addr
7 || 8 - REG_READ or REG_WRITE */
id_x = (msg_id >> 4) & 0xFFFF; //получение адреса устройства страшие 2 бита
msg_ch = msg_id & 0xF; // получения id, чтобы выбрать, что делать
id_x = (msg_id >> 4) & 0xFFFF; // saved address
msg_ch = msg_id & 0xF; // saved id
if(id_x == flash_record[addr_id].value){
switch(msg_ch) {
case BOOT_CAN_ID:
if(msg.buf[0] == 0x01) { // Старт передачи
fw_size = *(uint32_t*)&msg.buf[1]; //размер прошивки тип 4 байта
if(msg.buf[0] == 0x01) { // start transfer
fw_size = *(uint32_t*)&msg.buf[1]; //size of firmware
fw_crc = *(uint16_t*)&msg.buf[5]; //crc
ptr_flash = APP_ADDRESS;
send_ack(0x01);
}
break;
case DATA_CAN_ID: // Пакет данных
case DATA_CAN_ID: // Data packet
if(ptr_flash < (APP_ADDRESS + fw_size)) {
write_flash_page((const uint8_t*)msg.buf, msg.len);
ptr_flash += msg.len;
@ -98,11 +94,13 @@ void process_can_message(const CAN_message_t &msg) {
}
break;
case BOOT_CAN_END: // Завершение передачи
case BOOT_CAN_END: // End of transfer
if(verify_firmware()) {
send_ack(0xAA);
write_param(firmw,0); //reset flasg
// erase_sector(7); // Сброс флага
write_param(firmw,0); //reset flag set 0
fw_update = false; //reset flag
// erase_sector(7);
delay(500);
NVIC_SystemReset();
} else {
send_ack(0x55);
@ -130,15 +128,9 @@ void jump_to_app() {
}
volatile uint32_t add = (uint32_t)APP_ADDRESS;
bool verify_firmware() {
uint16_t calculated_crc = 0;
calculated_crc = validate_crc16((uint8_t*)add,fw_size);
calculated_crc = validate_crc16((uint8_t*)APP_ADDRESS,fw_size);
return (calculated_crc == fw_crc);
}
@ -151,6 +143,25 @@ void send_ack(uint8_t status) {
Can.write(ack);
}
bool is_app_valid() {
volatile uint32_t* app_vector = (volatile uint32_t*)APP_ADDRESS;
// Check stack pointer
bool sp_valid = (app_vector[0] >= 0x20000000) &&
(app_vector[0] <= (0x20000000 + 128*1024)); // Для STM32 с 128K RAM
// check reset_handler
bool pc_valid = (app_vector[1] >= 0x08000000) &&
(app_vector[1] <= (0x08000000 + 1024*1024)); // Для 1MB Flash
// check two words on reset value
bool not_erased = (app_vector[0] != 0xFFFFFFFF) &&
(app_vector[1] != 0xFFFFFFFF);
return sp_valid && pc_valid && not_erased;
}
void loop() {
if(fw_update) {
CAN_message_t msg;

View file

@ -18,3 +18,53 @@ platformio run --target upload --environment robotroller_reborn
```bash
platformio device monitor
```
## Для прошивки
- [Установить python3]
```bash
sudo apt install python3
```
- [Устаноивть st-link]
```bash
sudo apt install st-link
```
## Выбор интерфейса прошивки
### CAN
- Если уже есть какя-то основная прошивка, то чтобы перепрошить другую прошивку, добавляем флаг для бутлоадера
```bash
python3 firmw_update_flag.py [адрес устройства]
```
- Передача прошивки по CAN
```bash
python3 firmware_can.py firmware.hex [адрес устройства]
```
### St-link(нет адресации можно прошивать только по одному)
```bash
python3 st-link.py firmware.hex
```
<!-- ### Не работает!
Если бутлоадер не был прошит и FLASH микрокотроллера полностью стерта
- [Скачать прошивку и бутлоадер в hex формате]
ССЫЛКА
- [Прошить через программатор]
```bash
python3 st-link_full.py bootloader.hex firmware.hex
``` -->
## Работа по CAN
- Установка адреса(если до этого не был установлен адрес, то адрес устройства = 0)
```bash
python3 set_id.py [адрес устройства]
```
- Установка PID коэффициентов для угла
```bash
python3 writePID_angle_parametrs.py [адрес устройства]
```
-Чтение PID коэффициентов для угла
```bash
python3 readPID_angle_parametrs.py [адрес устройства]

View file

@ -20,7 +20,7 @@ ACK_CAN_ID = 0x05
def debug_print(msg):
print(f"[DEBUG] {msg}")
def calculate_crc16_modbus(data: bytes) -> int:
def calculate_crc16(data: bytes) -> int:
crc = 0xFFFF
for byte in data:
crc ^= byte
@ -49,7 +49,7 @@ def send_firmware(hex_file):
# Расчет CRC
debug_print("Расчёт CRC...")
# calculator = Calculator(Crc16.IBM)
fw_crc = calculate_crc16_modbus(binary_data)
fw_crc = calculate_crc16(binary_data)
debug_print(f"CRC: 0x{fw_crc:04X}")
# Отправка START
@ -113,7 +113,7 @@ def send_firmware(hex_file):
)
bus.send(finish_msg)
ack = wait_for_ack(bus, timeout=3)
ack = wait_for_ack(bus, timeout=1.0)
if ack and ack.data[0] == 0xAA:
debug_print("Прошивка подтверждена!")
else:
@ -127,7 +127,7 @@ def send_firmware(hex_file):
def wait_for_ack(bus, timeout=1.0):
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0) # Неблокирующий режим
msg = bus.recv(timeout=0.1) # Неблокирующий режим
if msg and msg.arbitration_id == ACK_CAN_ID:
return msg
return None

View file

@ -4,7 +4,7 @@ import struct
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
DEVICE_ID = 0x27 # ID ADDR for servo
DEVICE_ID = int(sys.argv[1]) # ID ADDR for servo
REG_READ = 0x7 # Код команды чтения
REG_MOTOR_POSPID_Kp = 0x30
REG_MOTOR_POSPID_Ki = 0x31
@ -120,7 +120,7 @@ def main():
bus.shutdown()
if __name__ == "__main__":
# if len(sys.argv) != 2:
# print("Используйте python3 read_pid.py addr")
# sys.exit(1)
if len(sys.argv) != 2:
print("Используйте python3 read_pid.py addr")
sys.exit(1)
main()

View file

@ -46,7 +46,7 @@ def flash_hex_with_stlink(hex_file_path):
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
else:
print(f"⚠️ Ошибка сброса (код: {reset_result.returncode})")
print(f"⚠️ Ошибка (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
except Exception as e:

View file

@ -4,7 +4,7 @@ import struct
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
DEVICE_ID = 0x27 # ID ADDR for servo
DEVICE_ID = int(sys.argv[1]) # ID ADDR for servo
REG_WRITE = 0x8 # Код команды записи
REG_MOTOR_POSPID_Kp = 0x30
REG_MOTOR_POSPID_Ki = 0x31
@ -89,7 +89,7 @@ def main():
bus.shutdown()
if __name__ == "__main__":
# if len(sys.argv) != 2:
# print("Используйте python3 pid_set.py addr")
# sys.exit(1)
if len(sys.argv) != 2:
print("Используйте python3 pid_set.py addr")
sys.exit(1)
main()