Fix include and add/fixed python test
This commit is contained in:
parent
6844ca9a8d
commit
ec086e2d47
7 changed files with 320 additions and 7 deletions
|
@ -1 +0,0 @@
|
||||||
Subproject commit 01e1b2f27e07936f3b700e2d02c28ba75c32179d
|
|
85
controller/fw/bootloader/include/flash.h
Normal file
85
controller/fw/bootloader/include/flash.h
Normal file
|
@ -0,0 +1,85 @@
|
||||||
|
#ifndef FLASH_H_
|
||||||
|
#define FLASH_H_
|
||||||
|
#include "stm32f446xx.h"
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
|
||||||
|
/* no padding for this struct, beacuse storing 8 bytes*/
|
||||||
|
typedef struct{
|
||||||
|
uint8_t data_id; // data_id = id register of can
|
||||||
|
uint8_t data_type;
|
||||||
|
uint16_t crc;
|
||||||
|
uint32_t value;
|
||||||
|
// uint32_t write_ptr_now;
|
||||||
|
}FLASH_RECORD;
|
||||||
|
enum {
|
||||||
|
addr_id = 0,
|
||||||
|
pid_p = 1,
|
||||||
|
pid_i,
|
||||||
|
pid_d,
|
||||||
|
foc_id,
|
||||||
|
angl,
|
||||||
|
vel
|
||||||
|
};
|
||||||
|
|
||||||
|
/* for saved in FLASH float data*/
|
||||||
|
union{
|
||||||
|
uint32_t i;
|
||||||
|
float f;
|
||||||
|
}conv_float_to_int;
|
||||||
|
|
||||||
|
#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 PARAM_COUNT 4 // count data in flash
|
||||||
|
#define SECTOR_6 0x08040000 // 128KB
|
||||||
|
#define SECTOR_6_END (SECTOR_6 + 128 * 1024) // sector 6 end
|
||||||
|
// Flash keys for unlocking flash memory
|
||||||
|
#define BYTE32 0
|
||||||
|
#define BYTE8 1
|
||||||
|
//FLASH SET ONE PROGRAMM WORD
|
||||||
|
#define FLASH_8BYTE FLASH->CR &= ~FLASH_CR_PSIZE & ~FLASH_CR_PSIZE_1
|
||||||
|
#define FLASH_32BYTE \
|
||||||
|
FLASH->CR = (FLASH->CR & ~FLASH_CR_PSIZE) | (0x2 << FLASH_CR_PSIZE_Pos)
|
||||||
|
|
||||||
|
// Flash command bits
|
||||||
|
#define FLASH_LOCK FLASH->CR |= FLASH_CR_LOCK
|
||||||
|
#define FLASH_UNLOCK FLASH->KEYR = FLASH_KEY1; FLASH->KEYR = FLASH_KEY2
|
||||||
|
|
||||||
|
|
||||||
|
// Flash status flags
|
||||||
|
#define FLASH_BUSY (FLASH->SR & FLASH_SR_BSY)
|
||||||
|
#define FLASH_ERROR (FLASH->SR & (FLASH_SR_WRPERR | FLASH_SR_PGAERR | FLASH_SR_PGPERR | FLASH_SR_PGSERR))
|
||||||
|
|
||||||
|
//for bootloader
|
||||||
|
typedef void(*pFunction)(void);
|
||||||
|
|
||||||
|
|
||||||
|
/* for start addr in FLASH */
|
||||||
|
static uint32_t write_ptr = SECTOR_6;
|
||||||
|
static uint32_t ptr_fl = APP_ADDRESS;
|
||||||
|
// Function prototypes
|
||||||
|
void flash_unlock(void);
|
||||||
|
void flash_lock(void);
|
||||||
|
void erase_sector(uint8_t sector);
|
||||||
|
void flash_program_word(uint32_t address, uint32_t data,uint32_t byte_len);
|
||||||
|
uint8_t flash_read_word(uint32_t address);
|
||||||
|
FLASH_RECORD* load_params();
|
||||||
|
void compact_page();
|
||||||
|
void flash_read(uint32_t addr,FLASH_RECORD* ptr);
|
||||||
|
uint16_t validate_crc16(uint8_t *data,uint32_t length);
|
||||||
|
void flash_write(uint32_t addr, FLASH_RECORD* record);
|
||||||
|
void write_flash_page(const uint8_t* data, uint16_t len);
|
||||||
|
void erase_flash_pages();
|
||||||
|
void write_param(uint8_t param_id,uint32_t val);
|
||||||
|
uint16_t calc_crc_struct(FLASH_RECORD* res);
|
||||||
|
#endif /* FLASH_H_ */
|
38
controller/fw/bootloader/include/hal_conf_extra.h
Normal file
38
controller/fw/bootloader/include/hal_conf_extra.h
Normal file
|
@ -0,0 +1,38 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#pragma region "Motor and sensor setup"
|
||||||
|
#define LED1 PC10
|
||||||
|
#define LED2 PC11
|
||||||
|
#define HARDWARE_SERIAL_RX_PIN PB7
|
||||||
|
#define HARDWARE_SERIAL_TX_PIN PB6
|
||||||
|
#define AS5045_CS PB15
|
||||||
|
#define AS5045_MISO PB14
|
||||||
|
#define AS5045_MOSI PC1
|
||||||
|
#define AS5045_SCLK PB10
|
||||||
|
#define CURRENT_SENSOR_1 PB1
|
||||||
|
#define CURRENT_SENSOR_2 PB0
|
||||||
|
#define CURRENT_SENSOR_3 PC5
|
||||||
|
#define TIM1_CH1 PA8
|
||||||
|
#define TIM1_CH2 PA9
|
||||||
|
#define TIM1_CH3 PA10
|
||||||
|
#define EN_W_GATE_DRIVER PC6
|
||||||
|
#define EN_U_GATE_DRIVER PA11
|
||||||
|
#define EN_V_GATE_DRIVER PA12
|
||||||
|
#define SLEEP_DRIVER PC9
|
||||||
|
#define RESET_DRIVER PC8
|
||||||
|
#define FAULT_DRIVER PC7
|
||||||
|
#define POLE_PAIRS 14
|
||||||
|
#define CAN2_TX PB13
|
||||||
|
#define CAN2_RX PB12
|
||||||
|
#define CAN1_TX PB9
|
||||||
|
#define CAN1_RX PB8
|
||||||
|
#define GM6208_RESISTANCE 31
|
||||||
|
#define OWN_RESISTANCE 26
|
||||||
|
#pragma endregion
|
||||||
|
|
||||||
|
#if !defined(HAL_CAN_MODULE_ENABLED)
|
||||||
|
#define HAL_CAN_MODULE_ENABLED
|
||||||
|
#endif
|
||||||
|
#include "stm32f4xx_hal.h"
|
||||||
|
#include "stm32f4xx_hal_can.h"
|
||||||
|
#include <STM32_CAN.h>
|
38
controller/fw/bootloader/include/reg_cah.h
Normal file
38
controller/fw/bootloader/include/reg_cah.h
Normal 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 0x07
|
||||||
|
#define REG_WRITE 0x08
|
||||||
|
|
||||||
|
|
||||||
|
/* 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_
|
141
controller/fw/embed/test/python_firmware.py
Normal file
141
controller/fw/embed/test/python_firmware.py
Normal file
|
@ -0,0 +1,141 @@
|
||||||
|
import can
|
||||||
|
import sys
|
||||||
|
import time
|
||||||
|
from intelhex import IntelHex
|
||||||
|
# Конфигурация
|
||||||
|
CAN_CHANNEL = 'socketcan'
|
||||||
|
CAN_INTERFACE = 'can0'
|
||||||
|
CAN_BITRATE = 1000000
|
||||||
|
#ch =int(input("Введите id устройства:"))
|
||||||
|
ch = int(sys.argv[2])
|
||||||
|
BOOT_CAN_ID = (ch * 16) + 1
|
||||||
|
DATA_CAN_ID = (ch * 16) + 3
|
||||||
|
BOOT_CAN_END = (ch * 16) + 2
|
||||||
|
ACK_CAN_ID = 0x05
|
||||||
|
|
||||||
|
#конфиг для crc16 ibm
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
def debug_print(msg):
|
||||||
|
print(f"[DEBUG] {msg}")
|
||||||
|
|
||||||
|
def calculate_crc16_modbus(data: bytes) -> int:
|
||||||
|
crc = 0xFFFF
|
||||||
|
for byte in data:
|
||||||
|
crc ^= byte
|
||||||
|
for _ in range(8):
|
||||||
|
if crc & 0x0001:
|
||||||
|
crc = (crc >> 1) ^ 0xA001
|
||||||
|
else:
|
||||||
|
crc >>= 1
|
||||||
|
return crc
|
||||||
|
|
||||||
|
def send_firmware(hex_file):
|
||||||
|
try:
|
||||||
|
debug_print("Инициализация CAN...")
|
||||||
|
bus = can.interface.Bus(
|
||||||
|
channel=CAN_INTERFACE,
|
||||||
|
bustype=CAN_CHANNEL,
|
||||||
|
bitrate=CAN_BITRATE
|
||||||
|
)
|
||||||
|
|
||||||
|
debug_print("Чтение HEX-файла...")
|
||||||
|
ih = IntelHex(hex_file)
|
||||||
|
binary_data = ih.tobinstr() # Исправлено на tobinstr()
|
||||||
|
fw_size = len(binary_data)
|
||||||
|
debug_print(f"Размер прошивки: {fw_size} байт")
|
||||||
|
|
||||||
|
# Расчет CRC
|
||||||
|
debug_print("Расчёт CRC...")
|
||||||
|
# calculator = Calculator(Crc16.IBM)
|
||||||
|
fw_crc = calculate_crc16_modbus(binary_data)
|
||||||
|
debug_print(f"CRC: 0x{fw_crc:04X}")
|
||||||
|
|
||||||
|
# Отправка START
|
||||||
|
start_data = bytearray([0x01])
|
||||||
|
start_data += fw_size.to_bytes(4, 'little')
|
||||||
|
start_data += fw_crc.to_bytes(2, 'little')
|
||||||
|
|
||||||
|
debug_print(f"START: {list(start_data)}")
|
||||||
|
start_msg = can.Message(
|
||||||
|
arbitration_id=BOOT_CAN_ID,
|
||||||
|
data=bytes(start_data),
|
||||||
|
is_extended_id=False
|
||||||
|
)
|
||||||
|
|
||||||
|
try:
|
||||||
|
bus.send(start_msg)
|
||||||
|
except can.CanError as e:
|
||||||
|
debug_print(f"Ошибка отправки START: {str(e)}")
|
||||||
|
return
|
||||||
|
|
||||||
|
# Ожидание ACK
|
||||||
|
debug_print("Ожидание ACK...")
|
||||||
|
ack = wait_for_ack(bus)
|
||||||
|
if not ack:
|
||||||
|
debug_print("Таймаут ACK START")
|
||||||
|
return
|
||||||
|
debug_print(f"Получен ACK: {list(ack.data)}")
|
||||||
|
|
||||||
|
# Отправка данных
|
||||||
|
packet_size = 8
|
||||||
|
for i in range(0, len(binary_data), packet_size):
|
||||||
|
chunk = binary_data[i:i+packet_size]
|
||||||
|
# Дополнение до 8 байт
|
||||||
|
if len(chunk) < 8:
|
||||||
|
chunk += b'\xFF' * (8 - len(chunk))
|
||||||
|
|
||||||
|
debug_print(f"Пакет {i//8}: {list(chunk)}")
|
||||||
|
data_msg = can.Message(
|
||||||
|
arbitration_id=DATA_CAN_ID,
|
||||||
|
data=chunk,
|
||||||
|
is_extended_id=False
|
||||||
|
)
|
||||||
|
|
||||||
|
try:
|
||||||
|
bus.send(data_msg)
|
||||||
|
except can.CanError as e:
|
||||||
|
debug_print(f"Ошибка отправки данных: {str(e)}")
|
||||||
|
return
|
||||||
|
|
||||||
|
ack = wait_for_ack(bus)
|
||||||
|
if not ack:
|
||||||
|
debug_print("Таймаут ACK DATA")
|
||||||
|
return
|
||||||
|
|
||||||
|
# Финал
|
||||||
|
debug_print("Отправка FINISH...")
|
||||||
|
finish_msg = can.Message(
|
||||||
|
arbitration_id=BOOT_CAN_END,
|
||||||
|
data=bytes([0xAA]),
|
||||||
|
is_extended_id=False
|
||||||
|
)
|
||||||
|
bus.send(finish_msg)
|
||||||
|
|
||||||
|
ack = wait_for_ack(bus, timeout=3)
|
||||||
|
if ack and ack.data[0] == 0xAA:
|
||||||
|
debug_print("Прошивка подтверждена!")
|
||||||
|
else:
|
||||||
|
debug_print("Ошибка верификации!")
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
debug_print(f"Критическая ошибка: {str(e)}")
|
||||||
|
finally:
|
||||||
|
bus.shutdown()
|
||||||
|
|
||||||
|
def wait_for_ack(bus, timeout=1.0):
|
||||||
|
start_time = time.time()
|
||||||
|
while time.time() - start_time < timeout:
|
||||||
|
msg = bus.recv(timeout=0) # Неблокирующий режим
|
||||||
|
if msg and msg.arbitration_id == ACK_CAN_ID:
|
||||||
|
return msg
|
||||||
|
return None
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
import sys
|
||||||
|
if len(sys.argv) != 3:
|
||||||
|
print("Использование: sudo python3 can_flasher.py firmware.hex")
|
||||||
|
sys.exit(1)
|
||||||
|
|
||||||
|
send_firmware(sys.argv[1])
|
|
@ -1,11 +1,11 @@
|
||||||
import can
|
import can
|
||||||
import time
|
import time
|
||||||
|
import sys
|
||||||
# Конфигурация
|
# Конфигурация
|
||||||
CAN_INTERFACE = 'can0'
|
CAN_INTERFACE = 'can0'
|
||||||
OLD_DEVICE_ID = 0x03 # Текущий ID устройства (по умолчанию)
|
OLD_DEVICE_ID = int(sys.argv[1]) # Текущий ID устройства (по умолчанию)
|
||||||
REG_READ = 0x7 # Код команды чтения
|
REG_READ = 0x7 # Код команды чтения
|
||||||
REG_ID = 0x1 # Адрес регистра с ID устройства
|
REG_ID = 0x01 # Адрес регистра с ID устройства
|
||||||
|
|
||||||
def send_can_message(bus, can_id, data):
|
def send_can_message(bus, can_id, data):
|
||||||
"""Отправка CAN-сообщения"""
|
"""Отправка CAN-сообщения"""
|
||||||
|
@ -100,3 +100,9 @@ else:
|
||||||
|
|
||||||
# Завершаем работу с шиной
|
# Завершаем работу с шиной
|
||||||
bus.shutdown()
|
bus.shutdown()
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
import sys
|
||||||
|
if len(sys.argv) != 2:
|
||||||
|
print("Использование: python3 can_flasher.py address")
|
||||||
|
sys.exit(1)
|
||||||
|
|
|
@ -1,10 +1,10 @@
|
||||||
import can
|
import can
|
||||||
import time
|
import time
|
||||||
|
import sys
|
||||||
# Конфигурация
|
# Конфигурация
|
||||||
CAN_INTERFACE = 'can0'
|
CAN_INTERFACE = 'can0'
|
||||||
OLD_DEVICE_ID = 0x03
|
OLD_DEVICE_ID = int(sys.argv[1])
|
||||||
NEW_DEVICE_ID = 0x69
|
NEW_DEVICE_ID = int(sys.argv[2])
|
||||||
REG_WRITE = 0x8
|
REG_WRITE = 0x8
|
||||||
REG_READ = 0x7
|
REG_READ = 0x7
|
||||||
REG_ID = 0x1
|
REG_ID = 0x1
|
||||||
|
@ -116,3 +116,9 @@ else:
|
||||||
print("Нет ответа от устройства.")
|
print("Нет ответа от устройства.")
|
||||||
|
|
||||||
bus.shutdown()
|
bus.shutdown()
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
import sys
|
||||||
|
if len(sys.argv) != 3:
|
||||||
|
print("Использование: python3 can_flasher.py old_addr new addr")
|
||||||
|
sys.exit(1)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue