Fix test and work with bootloader
Fix tests Fix commit
This commit is contained in:
parent
e9fb2656b8
commit
05621e7150
11 changed files with 128 additions and 54 deletions
|
@ -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 [адрес устройства]
|
|
@ -1,4 +1,4 @@
|
|||
// clang-format off
|
||||
// clang-format off
|
||||
#include "Arduino.h"
|
||||
#include "stm32f446xx.h"
|
||||
#include <SimpleFOC.h>
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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()
|
||||
|
|
|
@ -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:
|
||||
|
@ -75,4 +75,4 @@ if __name__ == "__main__":
|
|||
if flash_hex_with_stlink(sys.argv[1]):
|
||||
sys.exit(0)
|
||||
else:
|
||||
sys.exit(1)
|
||||
sys.exit(1)
|
||||
|
|
|
@ -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()
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue