This commit is contained in:
Valentin Dabstep 2025-06-04 11:44:10 +03:00
parent 6be663c914
commit 9d3aa54272
25 changed files with 405 additions and 26432 deletions

View file

@ -1,11 +1,19 @@
# Встроенное ПО для сервипривода на STM32F446RE
# Встроенное ПО для сервопривода на STM32F446RE
## Для разработки
- [Установить platformio](#introduction)
```bash
pip install -U platformio
```
- Установить python3
```bash
sudo apt install python3
```
- Устаноивть st-link
```bash
sudo apt install st-link
```
### Прошивка делится на два файла один для загрузчика другой для основной прошивки. Чтобы загрузить как описано ниже нужно находится в директории этого проекта. Нужно сделать как для bootloader так и для embed
- [Скомпилировать проект](#build_project)
```bash
platformio run --environment robotroller_reborn
@ -14,23 +22,10 @@ platformio run --environment robotroller_reborn
```bash
platformio run --target upload --environment robotroller_reborn
```
- [Открыть монитор UART](#monitor_port)
```bash
platformio device monitor
```
## Для прошивки
- [Установить python3]
```bash
sudo apt install python3
```
- [Устаноивть st-link]
```bash
sudo apt install st-link
```
## Другой способ прошивки
## Выбор интерфейса прошивки
### CAN
### Для основной прошивки в директории ./embed
- Если уже есть какя-то основная прошивка, то чтобы перепрошить другую прошивку, добавляем флаг для бутлоадера
```bash
python3 firmw_update_flag.py [адрес устройства]
@ -43,7 +38,10 @@ python3 firmware_can.py firmware.hex [адрес устройства]
```bash
python3 st-link.py firmware.hex
```
### St-link_full(полная прошивка без адресации)
#### Прошивает и программатор и основную прошивку можно находится как в ./embed, так и в ./bootloader(в директории где есть данный тест в папке test).
- Если до этого сохраняли адреса и данные, то они останутся даже при полной перепрошивке
- Если бутлоадер не был прошит и FLASH микрокотроллера полностью стерта
- [Скачать прошивку и бутлоадер в hex формате]
@ -55,6 +53,7 @@ python3 st-link_full.py bootloader.hex firmware.hex
```
## Работа по CAN
#### Для основной прошивки в директории ./embed
- Установка адреса(если до этого не был установлен адрес, то адрес устройства = 0)
```bash
python3 set_id.py [адрес устройства]

View file

@ -1,20 +0,0 @@
# Встроенное ПО для сервипривода на STM32F446RE
## Для разработки
- [Установить platformio](#introduction)
```bash
pip install -U platformio
```
- [Скомпилировать проект](#build_project)
```bash
platformio run --environment robotroller_reborn
```
- [Загрузить прошивку](#upload_project)
```bash
platformio run --target upload --environment robotroller_reborn
```
- [Открыть монитор UART](#monitor_port)
```bash
platformio device monitor
```

File diff suppressed because one or more lines are too long

View file

@ -1,44 +0,0 @@
#include "AS5045.h"
MagneticSensorAS5045::MagneticSensorAS5045(uint16_t as5040_cs, uint16_t as5040_mosi, uint16_t as5040_miso,
uint16_t as5040_sclk): AS5040_CS_(as5040_cs),
AS5040_MOSI_(as5040_mosi),
AS5040_MISO_(as5040_miso),
AS5040_SCLK_(as5040_sclk),
spi(nullptr),
settings(AS5145SSISettings) {
}
MagneticSensorAS5045::~MagneticSensorAS5045() = default;
auto MagneticSensorAS5045::init(SPIClass *_spi) -> void {
this->spi = _spi;
settings = AS5145SSISettings;
pinMode(AS5040_CS_, OUTPUT);
pinMode(AS5040_MISO_, INPUT);
pinMode(AS5040_MOSI_, OUTPUT);
pinMode(AS5040_SCLK_, OUTPUT);
spi->setMISO(AS5040_MISO_);
spi->setMOSI(AS5040_MOSI_);
spi->setSCLK(AS5040_SCLK_);
spi->begin();
this->Sensor::init();
}
float MagneticSensorAS5045::getSensorAngle() {
float angle_data = readRawAngleSSI();
angle_data = (static_cast<float>(angle_data) / AS5045_CPR) * _2PI;
return angle_data;
}
uint16_t MagneticSensorAS5045::readRawAngleSSI() const {
spi->beginTransaction(settings);
digitalWrite(AS5040_CS_, LOW);
uint16_t value = spi->transfer16(0x0000);
digitalWrite(AS5040_CS_, HIGH);
spi->endTransaction();
delayMicroseconds(30);
return (value >> 3) & 0x1FFF; // TODO(vanyabeat): Add error checking MAGNETIC OWERFLOW and etc.
}

View file

@ -1,32 +0,0 @@
#pragma once
#include "SimpleFOC.h"
#include "SPI.h"
#ifndef MSBFIRST
#define MSBFIRST BitOrder::MSBFIRST
#endif
#define AS5045_BITORDER MSBFIRST
#define AS5045_CPR 4096.0f
#define _2PI 6.28318530718f
static SPISettings AS5145SSISettings(1000000, AS5045_BITORDER, SPI_MODE0);
class MagneticSensorAS5045 final: public Sensor {
public:
MagneticSensorAS5045(uint16_t as5040_cs, uint16_t as5040_mosi, uint16_t as5040_miso, uint16_t as5040_sclk);
virtual ~MagneticSensorAS5045();
float getSensorAngle() override;
virtual void init(SPIClass *_spi = &SPI);
[[nodiscard]] uint16_t readRawAngleSSI() const;
private:
uint16_t AS5040_CS_, AS5040_MOSI_, AS5040_MISO_, AS5040_SCLK_;
SPIClass *spi;
SPISettings settings;
};

View file

@ -1,10 +0,0 @@
name=AS5045
version=1.0.1
author=vanyabeat <vanyabeat@protonmail.com>
maintainer=vanyabeat <vanyabeat@protonmail.com>
sentence=Simple library to work with AS5040 and Simple FOC (for Robotroller in Robosemmbler) Fork from https://github.com/runger1101001
paragraph=Simple library to work with AS5040 and Simple FOC and simple library intended for hobby comunity to run the AS5040 magnetic sensor using FOC algorithm. It is intended to support as many BLDC/Stepper motor+sensor+driver combinations as possible and in the same time maintain simplicity of usage. Library supports Arudino devices such as Arduino UNO, MEGA, NANO and similar, stm32 boards such as Nucleo and Bluepill, ESP32 and Teensy boards.
category=Device Control
url=https://docs.simplefoc.com
architectures=*
includes=SimpleFOC.h

View file

@ -1,42 +0,0 @@
#include "DRV8313.h"
DRV8313Driver::DRV8313Driver(int phA, int phB, int phC, int en1, int en2, int en3, int slp, int rst,
int flt) : BLDCDriver3PWM(phA, phB, phC, en1, en2, en3), slp_pin(slp), rst_pin(rst),
flt_pin(flt) {
}
int DRV8313Driver::init() {
// Get state from flt pin
if (_isset(flt_pin)) {
pinMode(flt_pin, INPUT);
if (digitalRead(flt_pin) == HIGH) {
// if the fault pin is high the driver is in fault state
// reset the driver
if (_isset(rst_pin)) {
pinMode(rst_pin, OUTPUT);
digitalWrite(rst_pin, LOW);
delay(1);
digitalWrite(rst_pin, HIGH);
delay(1);
}
}
}
return BLDCDriver3PWM::init();
}
void DRV8313Driver::enable() {
// Enable the driver
if (_isset(slp_pin)) {
pinMode(slp_pin, OUTPUT);
digitalWrite(slp_pin, HIGH);
}
BLDCDriver3PWM::enable();
}
void DRV8313Driver::disable() {
if (_isset(slp_pin)) {
pinMode(slp_pin, OUTPUT);
digitalWrite(slp_pin, LOW);
}
BLDCDriver3PWM::disable();
}

View file

@ -1,20 +0,0 @@
#pragma once
#include "SimpleFOC.h"
class DRV8313Driver : public BLDCDriver3PWM {
public:
DRV8313Driver(int phA, int phB, int phC, int en1 = NOT_SET, int en2 = NOT_SET, int en3 = NOT_SET, int slp = NOT_SET,
int rst = NOT_SET, int flt = NOT_SET);
int init() override;
void enable() override;
void disable() override;
private:
int slp_pin;
int rst_pin;
int flt_pin;
};

View file

@ -1,10 +0,0 @@
name=DRV8313 Simple FOC
version=1.0.0
author=vanyabeat <vanyabeat@protonmail.com>
maintainer=vanyabeat <vanyabeat@protonmail.com>
sentence=Simple library to work with DRV8313 and Simple FOC (for Robotroller in Robosemmbler)
paragraph=Simple library to work with DRV8313 and Simple FOC and simple library intended for hobby comunity to run the BLDC and Stepper motor using FOC algorithm. It is intended to support as many BLDC/Stepper motor+sensor+driver combinations as possible and in the same time maintain simplicity of usage. Library supports Arudino devices such as Arduino UNO, MEGA, NANO and similar, stm32 boards such as Nucleo and Bluepill, ESP32 and Teensy boards.
category=Device Control
url=https://docs.simplefoc.com
architectures=*
includes=SimpleFOC.h

View file

@ -1,46 +0,0 @@
This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file.
The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]").
For example, see a structure of the following two libraries `Foo` and `Bar`:
|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c
and a contents of `src/main.c`:
```
#include <Foo.h>
#include <Bar.h>
int main (void)
{
...
}
```
PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files.
More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html

View file

@ -1,86 +0,0 @@
# CAN Communication Scripts
This repository contains Python scripts for testing and interacting with a CAN bus system. These scripts enable sending and receiving CAN messages to control a motor, set angles, and adjust velocities.
## Prerequisites
1. **Python 3.7+** installed on your system.
2. **`python-can` library** installed. Install it via pip:
```bash
pip install python-can
```
3. **SocketCAN interface** properly configured on your Linux system. The default channel is `can0`.
## Usage
### 1. Receiving CAN Messages
The script `python_can.py` listens to the CAN bus and processes incoming messages.
#### Run:
```bash
python3 python_can.py
```
#### Features:
- Processes messages with data length 5.
- Parses the first byte (`flag`) to determine the type:
- `'A'`: Angle (float).
- `'V'`: Velocity (float).
- `'E'`: Enable/disable status (boolean).
### 2. Enabling or Disabling the Motor
The script `python_enable_motor.py` sends commands to enable or disable the motor.
#### Run:
```bash
python3 python_enable_motor.py <0|1>
```
#### Arguments:
- `0`: Disable the motor.
- `1`: Enable the motor.
### 3. Sending Target Angle
The script `python_send_angle.py` sends a target angle to the CAN bus.
#### Run:
```bash
python3 python_send_angle.py
```
#### Behavior:
- Sends a message with a predefined target angle every second.
- Adjust the target angle in the script (`target_angle` variable).
### 4. Sending Target Velocity
The script `python_send_velocity.py` sends a target velocity to the CAN bus.
#### Run:
```bash
python3 python_send_velocity.py
```
#### Behavior:
- Sends a message with a predefined target velocity every second.
- Adjust the target velocity in the script (`target_speed` variable).
## Configuration
### CAN Interface
The scripts use the following default CAN bus settings:
- **Channel**: `can0`
- **Bitrate**: `1 Mbps`
If your configuration differs, update the `Bus()` initialization in the scripts.
## Troubleshooting
1. **"Error initializing CAN bus"**:
- Ensure your CAN interface is correctly configured and active:
```bash
sudo ip link set can0 up type can bitrate 1000000
```

View 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(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(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=1.0)
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.1) # Неблокирующий режим
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])

View file

@ -0,0 +1,70 @@
import can
import time
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = int(sys.argv[1]) # Текущий ID устройства (по умолчанию)
REG_WRITE = 0x8 # Код команды чтения
REG_ID = 0x55 # Адрес регистра с Firmware Update
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def validate_crc16(data):
"""Расчет CRC16 (MODBUS) для проверки целостности данных"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация CAN-интерфейса
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Запрос текущего ID устройства =======
# Формируем CAN ID для чтения: (OLD_DEVICE_ID << 4) | REG_READ
can_id_read = (OLD_DEVICE_ID << 4) | REG_WRITE
# Данные для запроса: [регистр, резервный байт]
data_read = [REG_ID, 0x00]
# Формируем полные данные для расчета CRC:
# - CAN ID разбивается на 2 байта (little-endian)
# - Добавляем данные запроса
full_data_for_crc = list(can_id_read.to_bytes(2, 'little')) + data_read
# Рассчитываем CRC и разбиваем на байты (little-endian)
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Собираем итоговый пакет: данные + CRC
packet_read = data_read + crc_bytes
print("Переход в boot режим", packet_read)
send_can_message(bus, can_id_read, packet_read)
bus.shutdown()
if __name__ == "__main__":
import sys
if len(sys.argv) != 2:
print("Использование: python3 firmware_test.py address")
sys.exit(1)

View file

@ -1,47 +0,0 @@
import can
import struct
import time
def process_can_message(msg):
if msg.dlc == 5: # Check the message length
print(f"Received message with ID: {msg.arbitration_id}")
print(f"Data: {msg.data}")
# The first byte determines the data type (flag)
flag = chr(msg.data[0])
if flag == 'A': # Angle
angle_bytes = msg.data[1:5]
angle = struct.unpack('<f', bytes(angle_bytes))[0]
print(f"Angle: {angle} degrees")
elif flag == 'V': # Velocity
velocity_bytes = msg.data[1:5]
velocity = struct.unpack('<f', bytes(velocity_bytes))[0]
print(f"Velocity: {velocity} rad/s")
elif flag == 'E' and msg.dlc >= 2: # Enable/Disable
enabled = msg.data[1] # Expecting 1 byte (0 or 1)
print(f"Enabled: {bool(enabled)}")
else:
print(f"Unknown flag: {flag}")
else:
print(f"Received message with unexpected length: {msg.dlc}")
def receive_can_messages():
try:
# Connect to the CAN bus
bus = can.interface.Bus(channel='can0', bustype='socketcan')
print("Waiting for messages on the CAN bus...")
while True:
msg = bus.recv()
if msg:
process_can_message(msg)
except KeyboardInterrupt:
print("\nExiting program...")
except Exception as e:
print(f"Error: {e}")
if __name__ == '__main__':
receive_can_messages()

View file

@ -1,54 +0,0 @@
import can
import sys
# Function to send the motor enable/disable command
def send_motor_enable(bus, enable):
"""
Sends a command to enable or disable the motor.
:param bus: The CAN bus
:param enable: 1 to enable the motor, 0 to disable it
"""
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 2 # Message length (flag + 1 byte of data)
msg.data = [ord('E'), enable] # 'E' for the command, followed by 0 or 1
try:
bus.send(msg)
state = "enabled" if enable else "disabled"
print(f"Sent message to {state} motor")
print(f"Message data: {msg.data}")
except can.CanError as e:
print(f"Message failed to send: {e}")
sys.exit(1) # Exit the program on failure
def main():
# CAN interface setup
bus = None # Define outside the try block for proper shutdown
try:
bus = can.interface.Bus(channel='can0', bustype='socketcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized.")
# Ensure the state is passed via arguments
if len(sys.argv) != 2 or sys.argv[1] not in ['0', '1']:
print("Usage: python3 script_name.py <0|1>")
print("0 - Disable motor, 1 - Enable motor")
sys.exit(1)
enable = int(sys.argv[1])
send_motor_enable(bus, enable)
except Exception as e:
print(f"Error initializing CAN bus: {e}")
sys.exit(1)
finally:
# Ensure the bus is properly shut down
if bus is not None:
bus.shutdown()
print("CAN bus shut down.")
if __name__ == '__main__':
main()

View file

@ -1,37 +0,0 @@
import can
import struct
import time
import argparse
# Function to send the target angle
def send_target_angle(bus, target_angle):
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 5 # Message length
msg.data = [ord('A')] + list(struct.pack('<f', target_angle)) # 'A' for the command identifier, followed by the angle in float format
try:
bus.send(msg)
print(f"Sent message with target angle: {target_angle} degrees")
print(f"Message data: {msg.data}")
except can.CanError:
print("Message failed to send")
# Main function
def main():
parser = argparse.ArgumentParser(description="Send target angles over CAN bus.")
parser.add_argument("--angle", type=float, required=True, help="Target angle to send over the CAN bus")
args = parser.parse_args()
target_angle = args.angle
# CAN interface setup
bus = can.interface.Bus(channel='can0', bustype='socketcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized, sending target angles...")
# Loop to send messages
send_target_angle(bus, target_angle)
if __name__ == '__main__':
main()

View file

@ -1,76 +0,0 @@
import can
import struct
import time
import sys
# Function to send the target speed
def send_target_speed(bus, target_speed):
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 5 # Message length
msg.data = bytearray([ord('V')] + list(struct.pack('<f', target_speed))) # 'V' for the command identifier, followed by the speed in float format
try:
bus.send(msg)
print(f"Sent message with target speed: {target_speed} rad/s")
except can.CanError:
print("Message failed to send")
# Function to send the motor enable/disable command
def send_motor_enable(bus, enable):
"""
Sends a command to enable or disable the motor.
:param bus: The CAN bus
:param enable: 1 to enable the motor, 0 to disable it
"""
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 2 # Message length (flag + 1 byte of data)
msg.data = bytearray([ord('E'), enable]) # 'E' for the command, followed by 0 or 1
try:
bus.send(msg)
state = "enabled" if enable else "disabled"
print(f"Sent message to {state} motor")
except can.CanError as e:
print(f"Message failed to send: {e}")
sys.exit(1) # Exit the program on failure
send_target_speed(bus,0.0)
def main():
# CAN interface setup
bus = None # Define outside the try block for proper shutdown
try:
bus = can.interface.Bus(channel='COM4', bustype='slcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized.")
while True:
user_input = input("Enter target speed: ")
if user_input.lower() == 'exit':
print("Exiting...")
break
try:
target_speed = float(user_input)
send_target_speed(bus, target_speed)
except ValueError:
print("Invalid input. Please enter a valid number.")
# Disable motor before exiting
send_motor_enable(bus, 0)
print("Motor disabled.")
except Exception as e:
print(f"Error initializing1 CAN bus: {e}")
sys.exit(1)
finally:
if bus is not None:
bus.shutdown()
print("CAN bus shut down.")
if __name__ == '__main__':
main()

View file

@ -1,73 +0,0 @@
import can
import time
def send_write_read_requests():
try:
bus = can.interface.Bus(channel='can0', bustype='socketcan')
# Конфигурация сообщений (ЗАПОЛНИТЕ ВАШИ ЗНАЧЕНИЯ)
write_msg = {
'arbitration_id': 0x01, # CAN ID для записи
'data': [0x27, 0xA0, 0xFF, 0x00], # Данные для записи (4 байта)
'description': "Установка id устройства"
}
read_msg = {
'arbitration_id': 0x01, # CAN ID для чтения
'data': [0xFF,0x99], # Адрес новый + команда запроса данных
'description': "Запрос id устройства",
'response_id': 0xFF, # Ожидаемый ID ответа
'timeout': 1.0 # Таймаут ожидания ответа (сек)
}
# 1. Отправка команды записи
print("Отправка команды записи...")
msg = can.Message(
arbitration_id=write_msg['arbitration_id'],
data=write_msg['data'],
is_extended_id=False
)
bus.send(msg)
print(f"Запись: ID={hex(msg.arbitration_id)}, Данные={list(msg.data)}")
# Ждем обработки команды устройством
time.sleep(2.0)
# 2. Отправка запроса чтения и ожидание ответа
print("\nОтправка запроса чтения...")
msg = can.Message(
arbitration_id=read_msg['arbitration_id'],
data=read_msg['data'],
is_extended_id=False
)
bus.send(msg)
print(f"Чтение: ID={hex(msg.arbitration_id)}, Команда={list(msg.data)}")
# Ожидаем ответа
start_time = time.time()
response_received = False
print("\nОжидание ответа...")
while (time.time() - start_time) < read_msg['timeout']:
response = bus.recv(timeout=0.1)
if response and response.arbitration_id == read_msg['response_id']:
print(f"\nПолучен ответ: ID={hex(response.arbitration_id)}")
print(f"Данные: {list(response.data)}")
print(f"Длина: {response.dlc} байт")
response_received = True
break
if not response_received:
print("\nОшибка: ответ не получен в течение заданного времени")
except KeyboardInterrupt:
print("\nПрерывание пользователем")
except Exception as e:
print(f"Ошибка: {str(e)}")
finally:
bus.shutdown()
print("\nCAN соединение закрыто")
if __name__ == '__main__':
send_write_read_requests()

View file

@ -1,35 +0,0 @@
import can
import struct
import time
# Function to send the target speed
def send_target_speed(bus, target_speed):
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 5 # Message length
msg.data = [ord('V')] + list(struct.pack('<f', target_speed)) # 'V' for the command identifier, followed by the speed in float format
try:
bus.send(msg)
print(f"Sent message with target speed: {target_speed} m/s")
print(f"Message data: {msg.data}")
except can.CanError:
print("Message failed to send")
# Main function
def main():
# CAN interface setup
bus = can.interface.Bus(channel='can0', bustype='socketcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized, sending target speed impulses...")
# Send impulses of target speed from -2 to 2 m/s
target_speeds = [-1, 1]
while True:
for speed in target_speeds:
send_target_speed(bus, speed)
time.sleep(1) # 1-second delay between messages
if __name__ == '__main__':
main()

View file

@ -0,0 +1,78 @@
import subprocess
import os
import sys
def flash_hex_with_stlink(hex_file_path):
if not os.path.isfile(hex_file_path):
print(f"❌ Файл не найден: {hex_file_path}")
return False
command = [
"st-flash",
"--format", "ihex",
"write",
hex_file_path
]
try:
print(f"⚡️ Прошиваем {hex_file_path} через ST-Link...")
result = subprocess.run(
command,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=30
)
print("▬▬▬ STDOUT ▬▬▬")
print(result.stdout)
print("▬▬▬ STDERR ▬▬▬")
print(result.stderr)
if result.returncode == 0:
print("✅ Прошивка успешно завершена!")
# Добавленный блок сброса
try:
print("🔄 Выполняем сброс устройства...")
reset_result = subprocess.run(
["st-info", "--reset"],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=10
)
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
else:
print(f"⚠️ Ошибка (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
except Exception as e:
print(f"⚠️ Ошибка при сбросе: {str(e)}")
return True
else:
print(f"❌ Ошибка прошивки (код: {result.returncode})")
return False
except FileNotFoundError:
print("❌ st-flash не найден! Установите stlink-tools.")
return False
except subprocess.TimeoutExpired:
print("❌ Таймаут операции! Проверьте подключение ST-Link.")
return False
except Exception as e:
print(f"❌ Неизвестная ошибка: {str(e)}")
return False
if __name__ == "__main__":
if len(sys.argv) != 2:
print("Использование: python stlink_flash.py <firmware.hex>")
sys.exit(1)
if flash_hex_with_stlink(sys.argv[1]):
sys.exit(0)
else:
sys.exit(1)

View file

@ -0,0 +1,100 @@
import subprocess
import os
import sys
import time
def flash_hex_with_stlink(hex_file_path, component_name):
if not os.path.isfile(hex_file_path):
print(f"❌ Файл {component_name} не найден: {hex_file_path}")
return False
command = [
"st-flash",
"--format", "ihex",
"write",
hex_file_path
]
try:
print(f"⚡️ Прошиваем {component_name} ({hex_file_path}) через ST-Link...")
result = subprocess.run(
command,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=30
)
print("▬▬▬ STDOUT ▬▬▬")
print(result.stdout)
print("▬▬▬ STDERR ▬▬▬")
print(result.stderr)
if result.returncode == 0:
print(f"{component_name} успешно прошит!")
return True
else:
print(f"❌ Ошибка прошивки {component_name} (код: {result.returncode})")
return False
except FileNotFoundError:
print("❌ st-flash не найден! Установите stlink-tools.")
return False
except subprocess.TimeoutExpired:
print(f"❌ Таймаут операции при прошивке {component_name}! Проверьте подключение ST-Link.")
return False
except Exception as e:
print(f"❌ Неизвестная ошибка при прошивке {component_name}: {str(e)}")
return False
def reset_device():
try:
print("🔄 Выполняем сброс(перезагрузку) устройства...")
reset_result = subprocess.run(
["st-info", "--reset"],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=10
)
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
return True
else:
print(f"⚠️ Ошибка при сбросе (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
return False
except Exception as e:
print(f"⚠️ Ошибка при сбросе: {str(e)}")
return False
if __name__ == "__main__":
if len(sys.argv) != 3:
print("Использование: python stlink_flash.py <bootloader.hex> <application.hex>")
print("Пример: python stlink_flash.py bootloader.hex firmware.hex")
sys.exit(1)
bootloader_path = sys.argv[1]
app_path = sys.argv[2]
# Прошиваем сначала бутлоадер
if not flash_hex_with_stlink(bootloader_path, "Bootloader"):
print("\n💥 Ошибка прошивки бутлоадера!")
sys.exit(1)
# Сбрасываем устройство после прошивки бутлоадера
reset_device()
time.sleep(1) # Короткая пауза
# Прошиваем основное приложение
if not flash_hex_with_stlink(app_path, "Application"):
print("\n💥 Ошибка прошивки основного приложения!")
sys.exit(1)
# Финальный сброс устройства
reset_device()
print("\n🎉 Все компоненты успешно прошиты!")
sys.exit(0)

View file

@ -31,11 +31,9 @@ FLASH_EraseInitTypeDef pEraseInit;
uint32_t SectorError;
/* bool for test CAN */
volatile bool CAN_GET = false;
volatile float kt = 0.1; // Torque calculation constant
FLASH_RECORD* flash_rec;