Merge
This commit is contained in:
commit
6be663c914
60 changed files with 29349 additions and 490 deletions
1
controller/fw/embed/.gitignore
vendored
1
controller/fw/embed/.gitignore
vendored
|
@ -7,3 +7,4 @@
|
|||
.metadata/
|
||||
cubemx_config/
|
||||
compile_commands.json
|
||||
../embed.rar
|
||||
|
|
|
@ -18,3 +18,52 @@ 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 [адрес устройства]
|
178
controller/fw/embed/custom_script.ld
Normal file
178
controller/fw/embed/custom_script.ld
Normal file
|
@ -0,0 +1,178 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file LinkerScript.ld
|
||||
* @author Auto-generated by STM32CubeIDE
|
||||
* @brief Linker script for STM32F446RCTx Device from STM32F4 series
|
||||
* 256Kbytes FLASH
|
||||
* 128Kbytes RAM
|
||||
*
|
||||
* Set heap size, stack size and stack location according
|
||||
* to application requirements.
|
||||
*
|
||||
* Set memory bank area and size if external memory is used
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2020 STMicroelectronics.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* This software component is licensed by ST under BSD 3-Clause license,
|
||||
* the "License"; You may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at:
|
||||
* opensource.org/licenses/BSD-3-Clause
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
|
||||
|
||||
_Min_Heap_Size = 0x200; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x400; /* required amount of stack */
|
||||
|
||||
|
||||
/* Memories definition */
|
||||
MEMORY
|
||||
{
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
|
||||
FLASH (rx) : ORIGIN = 0x8000000 + 0x8000, LENGTH = 512K - 0x8000
|
||||
}
|
||||
|
||||
/* Sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code into "FLASH" Rom type memory */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data into "FLASH" Rom type memory */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
/* Constant data into "FLASH" Rom type memory */
|
||||
.rodata :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.ARM.extab (READONLY) : {
|
||||
. = ALIGN(4);
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.ARM (READONLY) : {
|
||||
. = ALIGN(4);
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.preinit_array (READONLY) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.init_array (READONLY) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.fini_array (READONLY) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
KEEP (*(.fini_array*))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* Used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
/* Initialized data sections into "RAM" Ram type memory */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
*(.RamFunc) /* .RamFunc sections */
|
||||
*(.RamFunc*) /* .RamFunc* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section into "RAM" Ram type memory */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(8);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(8);
|
||||
} >RAM
|
||||
|
||||
/* Remove information from the compiler libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -5,4 +5,4 @@ Import("env")
|
|||
env.Replace(COMPILATIONDB_INCLUDE_TOOLCHAIN=True)
|
||||
|
||||
# override compilation DB path
|
||||
env.Replace(COMPILATIONDB_PATH="compile_commands.json")
|
||||
env.Replace(COMPILATIONDB_PATH="compile_commands.json")
|
10
controller/fw/embed/hex_compile.py
Normal file
10
controller/fw/embed/hex_compile.py
Normal file
|
@ -0,0 +1,10 @@
|
|||
Import("env")
|
||||
|
||||
# Custom HEX from ELF
|
||||
env.AddPostAction(
|
||||
"$BUILD_DIR/${PROGNAME}.elf",
|
||||
env.VerboseAction(" ".join([
|
||||
"$OBJCOPY", "-O", "ihex", "-R", ".eeprom",
|
||||
"$BUILD_DIR/${PROGNAME}.elf", "$BUILD_DIR/${PROGNAME}.hex"
|
||||
]), "Building $BUILD_DIR/${PROGNAME}.hex")
|
||||
)
|
31
controller/fw/embed/include/config.h
Normal file
31
controller/fw/embed/include/config.h
Normal file
|
@ -0,0 +1,31 @@
|
|||
#pragma once
|
||||
#include "Arduino.h"
|
||||
#include <AS5045.h>
|
||||
#include <DRV8313.h>
|
||||
#include <SimpleFOC.h>
|
||||
#include <STM32_CAN.h>
|
||||
#include "flash.h"
|
||||
|
||||
extern STM32_CAN Can;
|
||||
extern SPIClass spi;
|
||||
extern MagneticSensorAS5045 encoder;
|
||||
extern BLDCMotor motor;
|
||||
extern DRV8313Driver driver;
|
||||
extern LowsideCurrentSense current_sense;
|
||||
extern Commander command;
|
||||
|
||||
struct MotorControlInputs {
|
||||
float target_angle = 0.0;
|
||||
float target_velocity = 0.0;
|
||||
bool motor_enabled = false;
|
||||
bool foc_state = false;
|
||||
};
|
||||
|
||||
extern MotorControlInputs motor_control_inputs;
|
||||
|
||||
void doMotor(char *cmd);
|
||||
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
|
||||
DRV8313Driver *driver, LowsideCurrentSense *current_sense,
|
||||
FLASH_RECORD* pid_data);
|
||||
|
||||
void foc_step(BLDCMotor *motor);
|
|
@ -4,27 +4,36 @@
|
|||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
|
||||
/* for addr in FLASH */
|
||||
|
||||
/* no padding for this struct, beacuse storing 8 bytes*/
|
||||
typedef struct{
|
||||
uint8_t data_id; // data_id = id register of can
|
||||
uint8_t value;
|
||||
uint8_t data_type;
|
||||
uint16_t crc;
|
||||
uint32_t value;
|
||||
// uint32_t write_ptr_now;
|
||||
}FLASH_RECORD;
|
||||
enum {
|
||||
addr_id = 0,
|
||||
foc_id = 1,
|
||||
angl = 2,
|
||||
vel = 3,
|
||||
pid_p = 4,
|
||||
pid_p = 1,
|
||||
pid_i,
|
||||
pid_d
|
||||
pid_d,
|
||||
firmw,
|
||||
foc_id,
|
||||
angl,
|
||||
vel
|
||||
};
|
||||
|
||||
#define FLASH_RECORD_SIZE sizeof(FLASH_RECORD) //size flash struct
|
||||
#define PARAM_COUNT 4 // count data in flash
|
||||
/* 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
|
||||
#define PARAM_COUNT 5 // count data in flash
|
||||
#define FIRMWARE_FLAG (uint32_t)0xDEADBEEF
|
||||
// Flash sectors for STM32F407
|
||||
|
||||
#define SECTOR_2 0x08008000 // 16KB
|
||||
|
@ -40,7 +49,7 @@ enum {
|
|||
// Flash keys for unlocking flash memory
|
||||
#define BYTE32 0
|
||||
#define BYTE8 1
|
||||
#define UPDATE_FLAG 0xDEADBEEF // Уникальное 32-битное значение
|
||||
#define UPDATE_FLAG 0xDEADBEEF // Unique 32bit value
|
||||
//FLASH SET ONE PROGRAMM WORD
|
||||
#define FLASH_8BYTE FLASH->CR &= ~FLASH_CR_PSIZE & ~FLASH_CR_PSIZE_1
|
||||
#define FLASH_32BYTE \
|
||||
|
@ -54,21 +63,24 @@ enum {
|
|||
// 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))
|
||||
|
||||
static uint32_t write_ptr = SECTOR_6;
|
||||
//for bootloader
|
||||
typedef void(*pFunction)(void);
|
||||
|
||||
|
||||
// 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);
|
||||
void write_param(uint8_t param_id, uint8_t val);
|
||||
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);
|
||||
bool validaate_crc(FLASH_RECORD* crc);
|
||||
|
||||
void write_param(uint8_t param_id,uint32_t val);
|
||||
|
||||
#endif /* FLASH_H_ */
|
||||
|
|
27
controller/fw/embed/include/process_can.h
Normal file
27
controller/fw/embed/include/process_can.h
Normal file
|
@ -0,0 +1,27 @@
|
|||
#pragma once
|
||||
#include "config.h"
|
||||
#include "STM32_CAN.h"
|
||||
#include "flash.h"
|
||||
#include "reg_cah.h"
|
||||
|
||||
extern FLASH_RECORD *flash_rec;
|
||||
extern volatile uint16_t msg_id;
|
||||
extern volatile uint16_t id_x;
|
||||
extern volatile uint8_t msg_ch;
|
||||
extern volatile uint8_t crc_h;
|
||||
extern volatile uint8_t crc_l;
|
||||
|
||||
|
||||
void send_velocity();
|
||||
void send_angle();
|
||||
void send_motor_enabled();
|
||||
void send_motor_enabled();
|
||||
void send_id();
|
||||
void firmware_update();
|
||||
void send_pid_angle(uint8_t param_pid);
|
||||
// void send_motor_torque();
|
||||
void send_pid(uint8_t param_pid);
|
||||
void setup_id(uint8_t my_id);
|
||||
void setup_angle(float target_angle);
|
||||
void setup_pid_angle(uint8_t param_pid, float data);
|
||||
void listen_can(const CAN_message_t &msg);
|
|
@ -37,4 +37,12 @@
|
|||
#define MOTOR_ANGLE 0x72
|
||||
#define MOTOR_TORQUE 0x73
|
||||
|
||||
#define FIRMWARE_UPDATE 0x55
|
||||
|
||||
//For send
|
||||
#define CAN_MSG_MAX_LEN 7
|
||||
#define CRC_SIZE 2
|
||||
#define ID_SIZE sizeof(uint8_t)
|
||||
|
||||
|
||||
#endif // REG_CAH_H_
|
||||
|
|
|
@ -1,15 +1,3 @@
|
|||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[platformio]
|
||||
|
||||
[env:robotroller_reborn]
|
||||
platform = ststm32
|
||||
board = genericSTM32F446RE
|
||||
|
@ -18,11 +6,19 @@ upload_protocol = stlink
|
|||
debug_tool = stlink
|
||||
monitor_speed = 19200
|
||||
monitor_parity = N
|
||||
|
||||
board_upload.offset_address = 0x08008000
|
||||
board_build.ldscript = ${PROJECT_DIR}/custom_script.ld
|
||||
|
||||
build_flags =
|
||||
-DSTM32F446xx
|
||||
-D HAL_CAN_MODULE_ENABLED
|
||||
-D SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
|
||||
-D STM32F446xx
|
||||
-D HAL_CAN_MODULE_ENABLED
|
||||
-D SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
|
||||
|
||||
lib_deps =
|
||||
askuric/Simple FOC@^2.3.4
|
||||
pazi88/STM32_CAN@^1.1.2
|
||||
extra_scripts = pre:gen_compile_commands.py
|
||||
askuric/Simple FOC@^2.3.4
|
||||
pazi88/STM32_CAN@^1.1.2
|
||||
|
||||
extra_scripts =
|
||||
pre:gen_compile_commands.py
|
||||
post:hex_compile.py
|
||||
|
|
75
controller/fw/embed/src/config.cpp
Normal file
75
controller/fw/embed/src/config.cpp
Normal file
|
@ -0,0 +1,75 @@
|
|||
#include "config.h"
|
||||
|
||||
|
||||
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
|
||||
DRV8313Driver *driver, LowsideCurrentSense *current_sense,
|
||||
FLASH_RECORD* pid_data) {
|
||||
encoder->init(&spi);
|
||||
|
||||
/* convert data from flash int value to float*/
|
||||
conv_float_to_int.i = pid_data[pid_p].value;
|
||||
float p = conv_float_to_int.f;
|
||||
|
||||
conv_float_to_int.i = pid_data[pid_i].value;
|
||||
float i = conv_float_to_int.f;
|
||||
|
||||
conv_float_to_int.i = pid_data[pid_d].value;
|
||||
float d = conv_float_to_int.f;
|
||||
|
||||
// Driver configuration
|
||||
driver->pwm_frequency = 20000;
|
||||
driver->voltage_power_supply = 24;
|
||||
driver->voltage_limit = 24;
|
||||
driver->init();
|
||||
|
||||
// Current sense initialization
|
||||
current_sense->linkDriver(driver);
|
||||
current_sense->init();
|
||||
|
||||
// Motor configuration
|
||||
motor->linkSensor(encoder);
|
||||
motor->linkDriver(driver);
|
||||
motor->linkCurrentSense(current_sense);
|
||||
motor->controller = MotionControlType::angle;
|
||||
motor->torque_controller = TorqueControlType::voltage;
|
||||
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// PID Configuration
|
||||
motor->PID_velocity.P = 0.5f;
|
||||
motor->PID_velocity.I = 2.0f;
|
||||
motor->PID_velocity.D = 0.0f;
|
||||
|
||||
motor->LPF_velocity.Tf = 0.01f;
|
||||
motor->P_angle.P = p;
|
||||
motor->P_angle.I = i;
|
||||
motor->P_angle.D = d;
|
||||
motor->LPF_angle.Tf = 0.02f;
|
||||
|
||||
// Motor limits
|
||||
motor->velocity_limit = 40; // Speed limit in rad/s (382 rpm)
|
||||
motor->voltage_limit = 24;
|
||||
motor->current_limit = 0.5;
|
||||
|
||||
motor->sensor_direction = Direction::CCW;
|
||||
motor->init();
|
||||
motor->initFOC();
|
||||
}
|
||||
|
||||
|
||||
void foc_step(BLDCMotor *motor) {
|
||||
if (motor_control_inputs.target_velocity != 0 ||
|
||||
motor->controller == MotionControlType::velocity) {
|
||||
if (motor->controller != MotionControlType::velocity) {
|
||||
motor->controller = MotionControlType::velocity;
|
||||
}
|
||||
motor->target = motor_control_inputs.target_velocity;
|
||||
} else {
|
||||
if (motor->controller != MotionControlType::angle) {
|
||||
motor->controller = MotionControlType::angle;
|
||||
}
|
||||
motor->target = motor_control_inputs.target_angle;
|
||||
}
|
||||
|
||||
motor->loopFOC();
|
||||
motor->move();
|
||||
}
|
|
@ -2,10 +2,8 @@
|
|||
#include <stdbool.h>
|
||||
#include "hal_conf_extra.h"
|
||||
|
||||
static uint32_t write_ptr = SECTOR_6;
|
||||
|
||||
void flash_unlock(){
|
||||
|
||||
// Check if flash is locked
|
||||
if(!(FLASH->CR & FLASH_CR_LOCK)) {
|
||||
return; // Already unlocked
|
||||
|
@ -94,12 +92,12 @@ void flash_write(uint32_t addr, FLASH_RECORD* record){
|
|||
FLASH->CR |= FLASH_CR_PG;
|
||||
|
||||
for(int i = 0;i < size;i++){
|
||||
*(volatile uint32_t*)(addr + i) = data[i];
|
||||
write_ptr++;
|
||||
*(volatile uint32_t*)(addr + (i * 4)) = data[i];
|
||||
}
|
||||
|
||||
// Clear program bit
|
||||
FLASH->CR &= ~FLASH_CR_PG;
|
||||
write_ptr = addr + (size * 4); //increase variable storing addr
|
||||
flash_lock();
|
||||
}
|
||||
|
||||
|
@ -115,29 +113,53 @@ uint8_t flash_read_word(uint32_t address){
|
|||
|
||||
}
|
||||
// Wait if flash
|
||||
bool validata_crc(FLASH_RECORD* crc){
|
||||
return crc->crc == 0x6933? true : false;
|
||||
}
|
||||
// bool validata_crc(FLASH_RECORD* crc){
|
||||
// return crc->crc == 0x6933? true : false;
|
||||
// }
|
||||
|
||||
uint16_t validate_crc16(uint8_t *data, uint32_t length) {
|
||||
uint16_t crc = 0xFFFF; // Начальное значение для MODBUS
|
||||
uint16_t crc = 0xFFFF; // start value for CRC MODBUS
|
||||
while (length--) {
|
||||
crc ^= *data++; // XOR с очередным байтом данных
|
||||
crc ^= *data++; // XOR
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (crc & 0x0001) {
|
||||
crc = (crc >> 1) ^ 0xA001; // Полином 0x8005 (reverse)
|
||||
crc = (crc >> 1) ^ 0xA001; // polynome 0x8005 (reverse)
|
||||
} else {
|
||||
crc >>= 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
return crc; // Возвращаем вычисленный CRC
|
||||
return crc;
|
||||
}
|
||||
|
||||
|
||||
|
||||
uint16_t calc_crc_struct(FLASH_RECORD* res){
|
||||
|
||||
uint8_t arr_res[FLASH_RECORD_SIZE - 2];
|
||||
uint16_t crc_res;
|
||||
/* sorting data without CRC */
|
||||
arr_res[0] = res->data_id;
|
||||
arr_res[1] = res->data_type;
|
||||
|
||||
/* from 32 to 8 bit */
|
||||
for(int i = 0;i < 4;i++)
|
||||
arr_res[i + 2] = (uint8_t)(res->value >> i * 8);
|
||||
|
||||
crc_res = validate_crc16(arr_res,FLASH_RECORD_SIZE - 2);
|
||||
return crc_res;
|
||||
}
|
||||
|
||||
|
||||
void disable_flash_protection() {
|
||||
HAL_FLASH_Unlock();
|
||||
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR);
|
||||
HAL_FLASH_Lock();
|
||||
}
|
||||
|
||||
/* read struct from FLASH */
|
||||
void flash_read(uint32_t addr,FLASH_RECORD* ptr){
|
||||
disable_flash_protection();
|
||||
uint8_t* flash_ptr = (uint8_t*)addr;
|
||||
uint8_t* dest = (uint8_t*)ptr;
|
||||
for(int i = 0;i < FLASH_RECORD_SIZE;i++)
|
||||
|
@ -149,14 +171,14 @@ void compact_page(){
|
|||
for(int i = (uint32_t)SECTOR_6;i < (uint32_t)SECTOR_7;i += FLASH_RECORD_SIZE) {
|
||||
FLASH_RECORD rec;
|
||||
flash_read(i,&rec);
|
||||
uint16_t calculated_crc = validate_crc16((uint8_t*)&rec, sizeof(FLASH_RECORD) - 2); //Вычисляем CRC без последних двух байтов.STRUCT - 2BYTE__CRC
|
||||
uint16_t calculated_crc = calc_crc_struct(&rec);
|
||||
|
||||
if (calculated_crc == rec.crc && rec.data_id < PARAM_COUNT) {
|
||||
// Если CRC совпадает и ID параметра валидный, сохраняем последнее значение
|
||||
// if the crc does not match, we check further
|
||||
latest[rec.data_id] = rec;
|
||||
}
|
||||
else
|
||||
//Если не совпадает продолжить читать флэш
|
||||
// if
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -164,7 +186,7 @@ void compact_page(){
|
|||
write_ptr = SECTOR_6; // Сброс на начало
|
||||
for (int i = 0; i < PARAM_COUNT; i++) {
|
||||
if (latest[i].data_id != 0xFF) {
|
||||
// Выравнивание перед каждой записью
|
||||
// alignment
|
||||
if (write_ptr % 4 != 0) {
|
||||
write_ptr += (4 - (write_ptr % 4));
|
||||
}
|
||||
|
@ -174,48 +196,56 @@ void compact_page(){
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
void write_param(uint8_t param_id, uint8_t val) {
|
||||
FLASH_RECORD param_flash = {param_id, val};
|
||||
// __disable_irq(); // Запрещаем прерывания на время всей операции
|
||||
|
||||
param_flash.crc = validate_crc16((uint8_t*)¶m_flash,sizeof(param_flash) - 2);//Нахождение CRC для данных, хранящихся во флэш памяти
|
||||
void write_param(uint8_t param_id, uint32_t val) {
|
||||
FLASH_RECORD param_flash;
|
||||
// __disable_irq(); // Interrupt off
|
||||
param_flash.data_id = param_id;
|
||||
param_flash.value = val;
|
||||
param_flash.data_type = sizeof(uint8_t);
|
||||
param_flash.crc = calc_crc_struct(¶m_flash);
|
||||
|
||||
// Проверка выравнивания ДО проверки границ сектора кратного 4
|
||||
if (write_ptr % 4 != 0) {
|
||||
write_ptr += (4 - (write_ptr % 4));
|
||||
// check alignment
|
||||
if (write_ptr % 8 != 0) {
|
||||
write_ptr += (8 - (write_ptr % 8));
|
||||
}
|
||||
|
||||
// Проверка переполнения с учётом выравнивания
|
||||
// check buffer overflow
|
||||
if (write_ptr + FLASH_RECORD_SIZE >= SECTOR_6_END) {
|
||||
compact_page(); // После compact_page write_ptr обновляется
|
||||
// Повторно выравниваем после функции. То есть сколько не хватает для кратности
|
||||
if (write_ptr % 4 != 0) {
|
||||
write_ptr += (4 - (write_ptr % 4));
|
||||
compact_page(); // after compact_page update
|
||||
// alignment
|
||||
if (write_ptr % 8 != 0) {
|
||||
write_ptr += (8 - (write_ptr % 8));
|
||||
}
|
||||
}
|
||||
|
||||
flash_write(write_ptr, ¶m_flash); //внутри функции итак автоматические инкрементируется указатель write_ptr на размер структуры
|
||||
flash_write(write_ptr, ¶m_flash); //inside the function, the write_ptr pointer is automatically incremented by the size of the structure
|
||||
|
||||
// __enable_irq(); // Разрешаем прерывания
|
||||
// __enable_irq(); // Interrupt on
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
FLASH_RECORD* load_params(){
|
||||
__disable_irq();
|
||||
static FLASH_RECORD latest[PARAM_COUNT] = {0};
|
||||
FLASH_RECORD res;
|
||||
|
||||
for(uint32_t addr = SECTOR_6;addr < SECTOR_6_END;addr +=FLASH_RECORD_SIZE) {
|
||||
flash_read(addr,&res);
|
||||
/* провекра CRC */
|
||||
uint16_t calculated_crc = validate_crc16((uint8_t*)&res, sizeof(FLASH_RECORD) - 2); //Вычисляем CRC без последних двух байтов.STRUCT - 2BYTE__CRC
|
||||
if (calculated_crc != res.crc || res.data_id >= PARAM_COUNT)
|
||||
continue;
|
||||
else{
|
||||
|
||||
|
||||
uint16_t calculated_crc = calc_crc_struct(&res);
|
||||
if (calculated_crc != res.crc || res.data_id >= PARAM_COUNT) continue;
|
||||
|
||||
else{
|
||||
latest[res.data_id] = res;
|
||||
write_ptr = addr + FLASH_RECORD_SIZE;
|
||||
}
|
||||
}
|
||||
write_ptr = addr + FLASH_RECORD_SIZE;
|
||||
}
|
||||
|
||||
__enable_irq();
|
||||
return latest;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -1,4 +1,3 @@
|
|||
// clang-format off
|
||||
#include "Arduino.h"
|
||||
#include "stm32f446xx.h"
|
||||
#include <SimpleFOC.h>
|
||||
|
@ -6,21 +5,23 @@
|
|||
#include <AS5045.h>
|
||||
#include <DRV8313.h>
|
||||
#include <cstring>
|
||||
#include <iostream>
|
||||
#include <iterator>
|
||||
#include "common/base_classes/FOCMotor.h"
|
||||
#include "hal_conf_extra.h"
|
||||
#include "wiring_analog.h"
|
||||
#include "wiring_constants.h"
|
||||
// clang-format on
|
||||
|
||||
#include "reg_cah.h"
|
||||
#include "flash.h"
|
||||
|
||||
#include "config.h"
|
||||
#include "process_can.h"
|
||||
|
||||
void SysTick_Handler(void) {
|
||||
HAL_IncTick();
|
||||
}
|
||||
|
||||
|
||||
STM32_CAN Can(CAN2, DEF);
|
||||
/* for FLASH */
|
||||
uint32_t flash_flag;
|
||||
|
@ -29,18 +30,16 @@ uint32_t flash_error;
|
|||
FLASH_EraseInitTypeDef pEraseInit;
|
||||
uint32_t SectorError;
|
||||
|
||||
volatile uint16_t msg_id;
|
||||
volatile uint16_t id_x;
|
||||
volatile uint8_t msg_ch;
|
||||
volatile uint8_t crc_h;
|
||||
volatile uint8_t crc_l;
|
||||
|
||||
volatile float kt = 0.1; //for torgue calculation
|
||||
|
||||
static FLASH_RECORD* flash_rec;
|
||||
static FLASH_RECORD flash_buf[PARAM_COUNT];
|
||||
static CAN_message_t CAN_TX_msg;
|
||||
static CAN_message_t CAN_inMsg;
|
||||
/* bool for test CAN */
|
||||
volatile bool CAN_GET = false;
|
||||
|
||||
|
||||
volatile float kt = 0.1; // Torque calculation constant
|
||||
|
||||
FLASH_RECORD* flash_rec;
|
||||
|
||||
|
||||
SPIClass spi;
|
||||
MagneticSensorAS5045 encoder(AS5045_CS, AS5045_MOSI, AS5045_MISO, AS5045_SCLK);
|
||||
|
@ -53,430 +52,66 @@ DRV8313Driver driver(TIM1_CH1, TIM1_CH2, TIM1_CH3, EN_W_GATE_DRIVER,
|
|||
LowsideCurrentSense current_sense(0.01, 10.0, CURRENT_SENSOR_1,
|
||||
CURRENT_SENSOR_2, CURRENT_SENSOR_3);
|
||||
|
||||
Commander command(Serial);
|
||||
|
||||
struct MotorControlInputs {
|
||||
float target_angle = 0.0;
|
||||
float target_velocity = 0.0;
|
||||
bool motor_enabled = false;
|
||||
bool foc_state = false;
|
||||
};
|
||||
// Commander command(Serial);
|
||||
|
||||
MotorControlInputs motor_control_inputs;
|
||||
|
||||
void doMotor(char *cmd) {
|
||||
command.motor(&motor, cmd);
|
||||
digitalWrite(PC10, !digitalRead(PC10));
|
||||
delayMicroseconds(2);
|
||||
}
|
||||
volatile uint16_t msg_id;
|
||||
volatile uint16_t id_x;
|
||||
volatile uint8_t msg_ch;
|
||||
volatile uint8_t crc_h;
|
||||
volatile uint8_t crc_l;
|
||||
|
||||
void CAN2_RX0_IRQHandler() {
|
||||
// Пустая функция, но прерывание не приведет к Default Handler
|
||||
}
|
||||
|
||||
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
|
||||
DRV8313Driver *driver, LowsideCurrentSense *current_sense,
|
||||
Commander *commander, CommandCallback callback) {
|
||||
encoder->init(&spi);
|
||||
|
||||
driver->pwm_frequency = 20000;
|
||||
driver->voltage_power_supply = 24;
|
||||
driver->voltage_limit = 24;
|
||||
driver->init();
|
||||
|
||||
current_sense->linkDriver(driver);
|
||||
current_sense->init();
|
||||
|
||||
motor->linkSensor(encoder);
|
||||
motor->linkDriver(driver);
|
||||
motor->linkCurrentSense(current_sense);
|
||||
motor->useMonitoring(Serial);
|
||||
motor->monitor_downsample = 5000; // default 0
|
||||
motor->controller = MotionControlType::angle;
|
||||
motor->torque_controller = TorqueControlType::voltage;
|
||||
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// PID start
|
||||
motor->PID_velocity.P = 0.75;
|
||||
motor->PID_velocity.I = 20;
|
||||
motor->LPF_velocity.Tf = 0.005;
|
||||
motor->P_angle.P = 0.5;
|
||||
motor->LPF_angle.Tf = 0.001;
|
||||
// PID end
|
||||
|
||||
motor->velocity_limit = 40; // Ограничение по скорости вращения rad/s (382 rpm)
|
||||
motor->voltage_limit = 24;
|
||||
motor->current_limit = 0.5;
|
||||
|
||||
motor->sensor_direction = Direction::CCW;
|
||||
motor->init();
|
||||
motor->initFOC();
|
||||
}
|
||||
|
||||
void send_can_with_id_crc(uint32_t id, uint8_t message_type, const void* data, size_t data_length) {
|
||||
// Создаем сообщение
|
||||
CAN_message_t msg;
|
||||
msg.id = id;
|
||||
msg.len = 8; // или как в протоколе
|
||||
msg.buf[0] = message_type;
|
||||
memcpy(&msg.buf[1], data, data_length);
|
||||
|
||||
// Формируем массив для CRC, включающий ID и все данные
|
||||
size_t crc_data_size = sizeof(msg.id) + data_length;
|
||||
uint8_t crc_data[crc_data_size];
|
||||
|
||||
// Копируем ID
|
||||
memcpy(crc_data, &msg.id, sizeof(msg.id));
|
||||
// Копируем все байты data
|
||||
memcpy(crc_data + sizeof(msg.id), data, data_length);
|
||||
|
||||
// Расчет CRC
|
||||
uint16_t crc_value = validate_crc16(crc_data, crc_data_size);
|
||||
|
||||
// Вставляем CRC в буфер
|
||||
msg.buf[6] = crc_value & 0xFF;
|
||||
msg.buf[7] = (crc_value >> 8) & 0xFF;
|
||||
|
||||
// Отправляем
|
||||
Can.write(msg);
|
||||
__NOP();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void send_velocity() {
|
||||
float current_velocity = motor.shaftVelocity();
|
||||
flash_rec = load_params();
|
||||
if (flash_rec == nullptr) { // Проверка на NULL
|
||||
// Обработка ошибки: запись в лог, сигнализация и т.д.
|
||||
return;
|
||||
}
|
||||
uint8_t value = flash_rec[vel].value;
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'V',&value,sizeof(value));
|
||||
}
|
||||
|
||||
void send_angle() {
|
||||
float current_angle = motor.shaftAngle();
|
||||
|
||||
flash_rec = load_params();
|
||||
if (flash_rec == nullptr) { // Проверка на NULL
|
||||
// Обработка ошибки: запись в лог, сигнализация и т.д.
|
||||
return;
|
||||
}
|
||||
// uint8_t value = flash_rec[angl].value;
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'A',¤t_angle,sizeof(current_angle));
|
||||
}
|
||||
|
||||
void send_motor_enabled() {
|
||||
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,
|
||||
sizeof(motor_control_inputs.motor_enabled));
|
||||
Can.write(CAN_TX_msg);
|
||||
}
|
||||
|
||||
void send_foc_state() {
|
||||
/* data for reading of firmware */
|
||||
flash_rec = load_params();
|
||||
if (flash_rec == nullptr) { // Проверка на NULL
|
||||
// Обработка ошибки: запись в лог, сигнализация и т.д.
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t value = flash_rec[foc_id].value;
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'F',&value,sizeof(value));
|
||||
}
|
||||
|
||||
void send_id() {
|
||||
/* data for reading of firmware */
|
||||
flash_rec = load_params();
|
||||
if (flash_rec == nullptr) { // Проверка на NULL
|
||||
// Обработка ошибки: запись в лог, сигнализация и т.д.
|
||||
return;
|
||||
}
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'I',&id,sizeof(id));
|
||||
__NOP();
|
||||
}
|
||||
|
||||
void send_motor_torque() {
|
||||
float i_q = motor.current.q; // Ток по оси q (А)
|
||||
float torque = kt * i_q; // Расчет момента
|
||||
torque *= 100;
|
||||
flash_rec = load_params();
|
||||
CAN_TX_msg.id = flash_rec->value;
|
||||
CAN_TX_msg.buf[0] = 'T';
|
||||
CAN_TX_msg.len = 5;
|
||||
memcpy(&CAN_TX_msg.buf[1], &torque, sizeof(torque));
|
||||
Can.write(CAN_TX_msg);
|
||||
}
|
||||
|
||||
|
||||
void send_pid(uint8_t param_pid){
|
||||
flash_rec = load_params();
|
||||
if (flash_rec == nullptr) { // Проверка на NULL
|
||||
return;
|
||||
}
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
uint8_t d = flash_rec[param_pid].value;
|
||||
uint8_t data_send = 0;
|
||||
int l = 0;
|
||||
while(d /= 10)
|
||||
l++;
|
||||
if(l >= 2)
|
||||
data_send = (float)d;
|
||||
void setup(){
|
||||
SCB->VTOR = (volatile uint32_t)0x08008004;
|
||||
|
||||
else if(l == 1)
|
||||
data_send = (float)(d * 10);
|
||||
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
|
||||
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
|
||||
Serial.begin(115200);
|
||||
|
||||
else
|
||||
data_send = (float)(d * 100);
|
||||
if(param_pid == pid_p)param_pid = REG_MOTOR_POSPID_Kp;
|
||||
else if(param_pid == pid_i)param_pid = REG_MOTOR_POSPID_Ki;
|
||||
else if(param_pid == pid_d)param_pid = REG_MOTOR_POSPID_Kd;
|
||||
send_can_with_id_crc(id,param_pid,&data_send,sizeof(data_send));
|
||||
}
|
||||
|
||||
void setup_id(uint8_t my_id) {
|
||||
write_param(addr_id,my_id);
|
||||
// send_id();
|
||||
}
|
||||
|
||||
void setup_angle(float target_angle) {
|
||||
// float target_angle = target_angle_rad / 100.0f; // Предполагаем, что передается в значениях сотых градуса или сотые радианы
|
||||
motor.enable(); // Включаем мотор если он отключен
|
||||
motor.controller = MotionControlType::angle;
|
||||
motor.move(target_angle);
|
||||
}
|
||||
|
||||
void setup_pid_angle(uint8_t param_pid, float data){
|
||||
switch (param_pid)
|
||||
{
|
||||
case pid_p:
|
||||
motor.P_angle.P = data;
|
||||
break;
|
||||
|
||||
case pid_i:
|
||||
motor.P_angle.I = data;
|
||||
break;
|
||||
|
||||
case pid_d:
|
||||
motor.P_angle.D = data;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
uint8_t check = uint8_t(data);
|
||||
uint8_t data_save = 0;
|
||||
if(check != 0)
|
||||
if(check /= 10)
|
||||
data_save = check;
|
||||
|
||||
else
|
||||
data_save = (uint8_t)(data * 10);
|
||||
|
||||
else
|
||||
data_save = (uint8_t)(data * 100);
|
||||
|
||||
write_param(param_pid,data_save);
|
||||
}
|
||||
|
||||
|
||||
void listen_can(const CAN_message_t &msg) {
|
||||
msg_id = msg.id;
|
||||
|
||||
msg_ch = msg_id & 0xF; // получения id, чтобы выбрать, что делать
|
||||
id_x = (msg_id >> 4) & 0x7FF; //получение адреса устройства страшие 2 бита msg_ch = msg_id & 0xF; // получения id, чтобы выбрать, что делать
|
||||
pinMode(PC11, OUTPUT);
|
||||
pinMode(PC10,OUTPUT);
|
||||
GPIOC->ODR &= ~GPIO_ODR_OD10;
|
||||
// Can.enableMBInterrupts();
|
||||
Can.begin();
|
||||
Can.setBaudRate(1000000);
|
||||
// Настройка прерываний CAN
|
||||
CAN2->IER |= CAN_IER_FMPIE0;
|
||||
flash_rec = load_params(); //for update write_ptr
|
||||
if(flash_rec[firmw].value == FIRMWARE_FLAG) NVIC_SystemReset(); //if in flash go to the bootloader
|
||||
|
||||
// Initialize FOC system
|
||||
setup_foc(&encoder, &motor, &driver, ¤t_sense,flash_rec);
|
||||
|
||||
/* Вычисление CRC */
|
||||
// Объединение старшего и младшего байтов для получения полученного CRC
|
||||
uint16_t received_crc = (msg.buf[msg.len - 2]) | (msg.buf[msg.len - 1] << 8);
|
||||
uint8_t data[10] = {0}; //буфер хранения сообщения и расчета его CRC для проверки
|
||||
|
||||
// Копируем ID сообщения в буфер данных для расчета CRC 2 байта
|
||||
memcpy(data, (uint8_t*)&msg_id, sizeof(msg_id));
|
||||
|
||||
// Копируем данные сообщения в буфер (без байтов CRC)
|
||||
memcpy(data + sizeof(msg_id), msg.buf, msg.len - 2);
|
||||
|
||||
// Рассчитываем CRC для полученных данных
|
||||
uint16_t calculated_crc = validate_crc16(data, sizeof(msg_id) + msg.len - 2);
|
||||
|
||||
// Проверяем совпадение CRC
|
||||
if (calculated_crc != received_crc) {
|
||||
// Несовпадение CRC, игнорируем сообщение
|
||||
return;
|
||||
}
|
||||
CAN2->IER |= CAN_IER_FMPIE0 | // Сообщение в FIFO0
|
||||
CAN_IER_FFIE0 | // FIFO0 full
|
||||
CAN_IER_FOVIE0; // FIFO0 overflow
|
||||
|
||||
|
||||
/* 0x691
|
||||
69 - адрес устройства
|
||||
1 - что делать дальше с данными */
|
||||
|
||||
if(id_x == flash_rec->value){
|
||||
if(msg_ch == REG_WRITE){
|
||||
switch(msg.buf[0]) {
|
||||
case REG_ID:
|
||||
/* setup new id */
|
||||
setup_id(msg.buf[1]);
|
||||
break;
|
||||
|
||||
case REG_LED_BLINK:
|
||||
for (int i = 0; i < 10; i++) {
|
||||
GPIOC->ODR ^= GPIO_ODR_OD10;
|
||||
delay(100);
|
||||
}
|
||||
break;
|
||||
|
||||
case MOTOR_ANGLE:
|
||||
memcpy(&motor_control_inputs.target_angle, &CAN_inMsg.buf[1],
|
||||
sizeof(motor_control_inputs.target_angle));
|
||||
setup_angle(motor_control_inputs.target_angle);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Kp:
|
||||
setup_pid_angle(pid_p,msg.buf[1]);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Ki:
|
||||
setup_pid_angle(pid_i,msg.buf[1]);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Kd:
|
||||
setup_pid_angle(pid_d,msg.buf[1]);
|
||||
break;
|
||||
|
||||
case MOTOR_ENABLED:
|
||||
if (msg.buf[1] == 1) {
|
||||
motor.enable();
|
||||
motor_control_inputs.motor_enabled = 1;
|
||||
} else {
|
||||
motor.disable();
|
||||
motor_control_inputs.motor_enabled = 0;
|
||||
}
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
else if (msg_ch == REG_READ) {
|
||||
switch (msg.buf[0]) {
|
||||
case REG_ID:
|
||||
send_id();
|
||||
break;
|
||||
case MOTOR_VELOCITY:
|
||||
send_velocity();
|
||||
break;
|
||||
|
||||
case MOTOR_ANGLE:
|
||||
send_angle();
|
||||
break;
|
||||
|
||||
case MOTOR_ENABLED:
|
||||
send_motor_enabled();
|
||||
break;
|
||||
|
||||
case MOTOR_TORQUE:
|
||||
send_motor_torque();
|
||||
break;
|
||||
|
||||
case FOC_STATE:
|
||||
send_foc_state();
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Kp:
|
||||
send_pid(pid_p);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Ki:
|
||||
send_pid(pid_i);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Kd:
|
||||
send_pid(pid_d);
|
||||
break;
|
||||
|
||||
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
volatile uint32_t ipsr_value = 0;
|
||||
|
||||
|
||||
void foc_step(BLDCMotor *motor, Commander *commander) {
|
||||
if (motor_control_inputs.target_velocity != 0 ||
|
||||
motor->controller == MotionControlType::velocity) {
|
||||
if (motor->controller != MotionControlType::velocity) {
|
||||
motor->controller = MotionControlType::velocity;
|
||||
}
|
||||
motor->target = motor_control_inputs.target_velocity;
|
||||
|
||||
} else {
|
||||
if (motor->controller != MotionControlType::angle) {
|
||||
motor->controller = MotionControlType::angle;
|
||||
}
|
||||
motor->target = motor_control_inputs.target_angle;
|
||||
}
|
||||
|
||||
motor->loopFOC();
|
||||
motor->move();
|
||||
motor->monitor();
|
||||
commander->run();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void setup(){
|
||||
/* bias for vector int */
|
||||
// __set_MSP(*(volatile uint32_t*)0x08008000);
|
||||
// SCB->VTOR = (volatile uint32_t)0x08008000;
|
||||
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
|
||||
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
|
||||
Serial.begin(115200);
|
||||
|
||||
pinMode(PC11, OUTPUT);
|
||||
pinMode(PC10,OUTPUT);
|
||||
GPIOC->ODR &= ~GPIO_ODR_OD10;
|
||||
// Setup thermal sensor pin
|
||||
// pinMode(TH1, INPUT_ANALOG);
|
||||
Can.begin();
|
||||
Can.setBaudRate(1000000);
|
||||
TIM_TypeDef *Instance = TIM2;
|
||||
HardwareTimer *SendTimer = new HardwareTimer(Instance);
|
||||
// SendTimer->setOverflow(100, HERTZ_FORMAT); // 50 Hz
|
||||
// SendTimer->attachInterrupt(send_data);
|
||||
// SendTimer->resume();
|
||||
flash_rec = load_params();
|
||||
for(int i = 0;i < PARAM_COUNT;i++)
|
||||
flash_buf[i] = flash_rec[i];
|
||||
setup_foc(&encoder, &motor, &driver, ¤t_sense, &command, doMotor);
|
||||
GPIOC->ODR |= GPIO_ODR_OD11;
|
||||
// Default motor configuration
|
||||
GPIOC->ODR |= GPIO_ODR_OD11; //set LED
|
||||
motor.torque_controller = TorqueControlType::foc_current;
|
||||
motor.controller = MotionControlType::torque;
|
||||
__enable_irq();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void loop() {
|
||||
foc_step(&motor, &command);
|
||||
__enable_irq();
|
||||
foc_step(&motor);
|
||||
CAN_message_t msg;
|
||||
GPIOC->ODR ^= GPIO_ODR_OD11;
|
||||
delay(500);
|
||||
|
||||
// Process incoming CAN messages
|
||||
while (Can.read(msg)) {
|
||||
listen_can(msg);
|
||||
CAN_GET = true;
|
||||
}
|
||||
/* If receive data from CAN */
|
||||
if(CAN_GET) {
|
||||
|
||||
CAN_GET = false;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
245
controller/fw/embed/src/process_can.cpp
Normal file
245
controller/fw/embed/src/process_can.cpp
Normal file
|
@ -0,0 +1,245 @@
|
|||
#include "process_can.h"
|
||||
|
||||
|
||||
static CAN_message_t CAN_TX_msg;
|
||||
static CAN_message_t CAN_inMsg;
|
||||
|
||||
|
||||
template <typename T>
|
||||
void send_can_with_id_crc(uint8_t id, uint8_t message_type, T* data) {
|
||||
// Create CAN message
|
||||
CAN_message_t msg_l;
|
||||
msg_l.id = id;
|
||||
// msg_l.len = 8; // Protocol-defined message length
|
||||
memcpy(&msg_l.buf[0], &message_type, sizeof(uint8_t));
|
||||
memcpy(&msg_l.buf[1], data, sizeof(T));
|
||||
|
||||
// Prepare CRC calculation buffer (ID + data)
|
||||
uint8_t crc_data[CAN_MSG_MAX_LEN];
|
||||
|
||||
// Copy message ID
|
||||
memcpy(crc_data, (uint8_t*)&msg_l.id, sizeof(T));
|
||||
// Copy all data bytes
|
||||
memcpy(crc_data + 1, msg_l.buf, 6);
|
||||
|
||||
// Calculate CRC
|
||||
uint16_t crc_value = validate_crc16(crc_data, CAN_MSG_MAX_LEN);
|
||||
|
||||
// Insert CRC into buffer
|
||||
// memcpy(&msg_l.buf[6], &crc_value, sizeof(uint16_t));
|
||||
msg_l.buf[6] = crc_value & 0xFF;
|
||||
msg_l.buf[7] = (crc_value >> 8) & 0xFF;
|
||||
|
||||
// Send message
|
||||
Can.write(msg_l);
|
||||
}
|
||||
|
||||
void send_velocity() {
|
||||
float current_velocity = motor.shaftVelocity();
|
||||
if (flash_rec == nullptr) { // Null check
|
||||
// Error handling: logging, alerts, etc.
|
||||
return;
|
||||
}
|
||||
float value = flash_rec[vel].value;
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'V',&value);
|
||||
}
|
||||
|
||||
void send_angle() {
|
||||
float current_angle = motor.shaftAngle();
|
||||
if (flash_rec == nullptr) { // Null check
|
||||
// Error handling: logging, alerts, etc.
|
||||
return;
|
||||
}
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'A',¤t_angle);
|
||||
}
|
||||
|
||||
|
||||
void send_motor_enabled() {
|
||||
/* Firmware data reading */
|
||||
if (flash_rec == nullptr) { // Null check
|
||||
// Error handling: logging, alerts, etc.
|
||||
return;
|
||||
}
|
||||
uint8_t value = motor_control_inputs.motor_enabled; //copy current motor state
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'M',&value);
|
||||
}
|
||||
|
||||
void send_id() {
|
||||
/* Firmware data reading */
|
||||
if (flash_rec == nullptr) { // Null check
|
||||
// Error handling: logging, alerts, etc.
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
send_can_with_id_crc(id,'I',&id);
|
||||
}
|
||||
|
||||
// void send_motor_torque() {
|
||||
// float i_q = motor.current.q; // Q-axis current (A)
|
||||
// float torque = kt * i_q; // Torque calculation
|
||||
// torque *= 100;
|
||||
// CAN_TX_msg.id = flash_rec->value;
|
||||
// CAN_TX_msg.buf[0] = 'T';
|
||||
// CAN_TX_msg.len = 5;
|
||||
// memcpy(&CAN_TX_msg.buf[1], &torque, sizeof(torque));
|
||||
// Can.write(CAN_TX_msg);
|
||||
// }
|
||||
|
||||
void send_pid_angle(uint8_t param_pid){
|
||||
if (flash_rec == nullptr) { // Null check
|
||||
return;
|
||||
}
|
||||
uint8_t id = flash_rec[addr_id].value;
|
||||
conv_float_to_int.i = flash_rec[param_pid].value;
|
||||
uint32_t data = conv_float_to_int.i;
|
||||
switch(param_pid){
|
||||
case pid_p:
|
||||
param_pid = REG_MOTOR_POSPID_Kp;
|
||||
break;
|
||||
|
||||
case pid_i:
|
||||
param_pid = REG_MOTOR_POSPID_Ki;
|
||||
break;
|
||||
|
||||
case pid_d:
|
||||
param_pid = REG_MOTOR_POSPID_Kd;
|
||||
break;
|
||||
}
|
||||
|
||||
send_can_with_id_crc(id,param_pid,&data);
|
||||
}
|
||||
|
||||
void setup_id(uint8_t my_id) {
|
||||
write_param(addr_id,my_id);
|
||||
}
|
||||
|
||||
void firmware_update(){
|
||||
write_param(firmw,FIRMWARE_FLAG);
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void setup_angle(float target_angle) {
|
||||
motor.enable(); // Enable motor if disabled
|
||||
// motor.controller = MotionControlType::angle;
|
||||
motor_control_inputs.target_angle = target_angle;
|
||||
// motor.move(target_angle);
|
||||
}
|
||||
|
||||
// void setup_pid_angle(uint8_t param_pid, uint32_t data){
|
||||
// conv_float_to_int.f = data;
|
||||
// switch (param_pid) {
|
||||
// case pid_p:
|
||||
// motor.P_angle.P = conv_float_to_int.f;
|
||||
// break;
|
||||
// case pid_i:
|
||||
// motor.P_angle.I = conv_float_to_int.f;
|
||||
// break;
|
||||
// case pid_d:
|
||||
// motor.P_angle.D = conv_float_to_int.f;
|
||||
// break;
|
||||
// default:
|
||||
// break;
|
||||
// }
|
||||
|
||||
// write_param(param_pid,data);
|
||||
// }
|
||||
|
||||
|
||||
void listen_can(const CAN_message_t &msg) {
|
||||
msg_id = msg.id;
|
||||
msg_ch = msg_id & 0xF; // Extract message channel
|
||||
uint16_t id_x = (msg_id >> 4) & 0x7FF; // Extract device address
|
||||
|
||||
/* CRC Calculation */
|
||||
uint16_t received_crc = (msg.buf[msg.len - 2]) | (msg.buf[msg.len - 1] << 8);
|
||||
uint8_t data[10] = {0}; // Message buffer for CRC verification
|
||||
|
||||
// Copy message ID (2 bytes)
|
||||
memcpy(data, (uint8_t*)&msg_id, sizeof(msg_id));
|
||||
// Copy message data (excluding CRC bytes)
|
||||
memcpy(data + sizeof(msg_id), msg.buf, msg.len - 2);
|
||||
|
||||
// Calculate CRC
|
||||
uint16_t calculated_crc = validate_crc16(data, sizeof(msg_id) + msg.len - 2);
|
||||
|
||||
// Verify CRC match
|
||||
if (calculated_crc != received_crc) {
|
||||
return; // Ignore message on CRC mismatch
|
||||
}
|
||||
flash_rec = load_params();
|
||||
/* Message Structure: 0x691
|
||||
69 - Device address
|
||||
1 - Action code */
|
||||
if(id_x == flash_rec[addr_id].value){
|
||||
if(msg_ch == REG_WRITE){
|
||||
switch(msg.buf[0]) {
|
||||
case REG_ID:
|
||||
setup_id(msg.buf[1]);
|
||||
break;
|
||||
case REG_LED_BLINK:
|
||||
for (int i = 0; i < 10; i++) {
|
||||
GPIOC->ODR ^= GPIO_ODR_OD10;
|
||||
delay(100);
|
||||
}
|
||||
break;
|
||||
|
||||
case MOTOR_ANGLE:
|
||||
memcpy(&motor_control_inputs.target_angle, &msg.buf[1],
|
||||
sizeof(motor_control_inputs.target_angle));
|
||||
setup_angle(motor_control_inputs.target_angle);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Kp:
|
||||
memcpy(&motor.P_angle.P, &msg.buf[1], sizeof(float));
|
||||
conv_float_to_int.f = motor.P_angle.P;
|
||||
write_param(pid_p,conv_float_to_int.i);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Ki:
|
||||
memcpy(&motor.P_angle.I, &msg.buf[1], sizeof(float));
|
||||
conv_float_to_int.f = motor.P_angle.I;
|
||||
write_param(pid_i,conv_float_to_int.i);
|
||||
break;
|
||||
|
||||
case REG_MOTOR_POSPID_Kd:
|
||||
memcpy(&motor.P_angle.D, &msg.buf[1], sizeof(float));
|
||||
conv_float_to_int.f = motor.P_angle.D;
|
||||
write_param(pid_d,conv_float_to_int.i);
|
||||
break;
|
||||
|
||||
case FIRMWARE_UPDATE:
|
||||
firmware_update();
|
||||
break;
|
||||
|
||||
case MOTOR_ENABLED:
|
||||
if (msg.buf[1] == 1) {
|
||||
motor.enable();
|
||||
motor_control_inputs.motor_enabled = 1;
|
||||
} else {
|
||||
motor.disable();
|
||||
motor_control_inputs.motor_enabled = 0;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
else if (msg_ch == REG_READ) {
|
||||
switch (msg.buf[0]) {
|
||||
case REG_ID: send_id(); break;
|
||||
case MOTOR_VELOCITY: send_velocity(); break;
|
||||
case MOTOR_ANGLE: send_angle(); break;
|
||||
case MOTOR_ENABLED: send_motor_enabled(); break;
|
||||
// case MOTOR_TORQUE: send_motor_torque(); break;
|
||||
// case FOC_STATE: send_foc_state(); break;
|
||||
case REG_MOTOR_POSPID_Kp: send_pid_angle(pid_p); break;
|
||||
case REG_MOTOR_POSPID_Ki: send_pid_angle(pid_i); break;
|
||||
case REG_MOTOR_POSPID_Kd: send_pid_angle(pid_d); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
141
controller/fw/embed/test/firmware_can.py
Normal file
141
controller/fw/embed/test/firmware_can.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(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])
|
70
controller/fw/embed/test/firmware_update_flag.py
Normal file
70
controller/fw/embed/test/firmware_update_flag.py
Normal 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)
|
103
controller/fw/embed/test/pid_p.py
Normal file
103
controller/fw/embed/test/pid_p.py
Normal file
|
@ -0,0 +1,103 @@
|
|||
import can
|
||||
import time
|
||||
import struct
|
||||
# Конфигурация
|
||||
CAN_INTERFACE = 'can0'
|
||||
OLD_DEVICE_ID = 0x00 # Текущий ID устройства (по умолчанию)
|
||||
REG_READ = 0x7 # Код команды чтения
|
||||
REG_ID = 0x30 # Адрес регистра с REG_PMOTOR_POSPID_Kp устройства
|
||||
|
||||
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 receive_response(bus, timeout=1.0):
|
||||
"""Ожидание ответа от устройства"""
|
||||
start_time = time.time()
|
||||
while time.time() - start_time < timeout:
|
||||
msg = bus.recv(timeout=0.1)
|
||||
if msg:
|
||||
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
|
||||
return msg
|
||||
print("[Ошибка] Таймаут")
|
||||
return None
|
||||
|
||||
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_READ
|
||||
|
||||
# Данные для запроса: [регистр, резервный байт]
|
||||
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("Запрос на чтение ID:", packet_read)
|
||||
send_can_message(bus, can_id_read, packet_read)
|
||||
|
||||
# ======= 2. Получение и проверка ответа =======
|
||||
response = receive_response(bus)
|
||||
if response:
|
||||
data = response.data
|
||||
|
||||
if len(data) < 4:
|
||||
print("Слишком короткий ответ")
|
||||
|
||||
# Проверяем минимальную длину ответа (данные + CRC)
|
||||
else:
|
||||
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
|
||||
#buff with id and data without CRC
|
||||
full_data = list(id_bytes) + list(data[:-2])
|
||||
print(f"Received full_data: {list(full_data)}")
|
||||
received_crc = int.from_bytes(data[-2:], byteorder='little')
|
||||
#calc CRC
|
||||
calc_crc = validate_crc16(full_data)
|
||||
|
||||
print(f"Расчитанный CRC PYTHON : 0x{calc_crc:02X}")
|
||||
if received_crc == calc_crc:
|
||||
# Если CRC совпадает, проверяем структуру ответа:
|
||||
kp_value = struct.unpack('<f', bytes(data[1:5]))[0]
|
||||
print(f"Текущий Kp устройства: {kp_value:.3f}")
|
||||
else:
|
||||
print("Ошибка: CRC не совпадает")
|
||||
else:
|
||||
print("Устройство не ответило")
|
||||
|
||||
# Завершаем работу с шиной
|
||||
bus.shutdown()
|
|
@ -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()
|
|
@ -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()
|
126
controller/fw/embed/test/readPID_angle_parametrs.py
Normal file
126
controller/fw/embed/test/readPID_angle_parametrs.py
Normal file
|
@ -0,0 +1,126 @@
|
|||
import can
|
||||
import time
|
||||
import struct
|
||||
import sys
|
||||
# Конфигурация
|
||||
CAN_INTERFACE = 'can0'
|
||||
DEVICE_ID = int(sys.argv[1]) # ID ADDR for servo
|
||||
REG_READ = 0x7 # Код команды чтения
|
||||
REG_MOTOR_POSPID_Kp = 0x30
|
||||
REG_MOTOR_POSPID_Ki = 0x31
|
||||
REG_MOTOR_POSPID_Kd = 0x32
|
||||
|
||||
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
|
||||
|
||||
def send_read_request(bus, device_id, register):
|
||||
"""Отправка запроса на чтение регистра"""
|
||||
can_id = (device_id << 4) | REG_READ
|
||||
data_part = [register, 0x00]
|
||||
|
||||
# Расчет CRC для CAN ID (2 байта) + данные
|
||||
full_data_for_crc = list(can_id.to_bytes(2, 'little')) + data_part
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, 'little'))
|
||||
|
||||
# Формирование итогового пакета
|
||||
packet = data_part + crc_bytes
|
||||
send_can_message(bus, can_id, packet)
|
||||
|
||||
def receive_pid_response(bus, timeout=1.0):
|
||||
"""Получение и проверка ответа с PID-значением"""
|
||||
start_time = time.time()
|
||||
while time.time() - start_time < timeout:
|
||||
msg = bus.recv(timeout=0.1)
|
||||
if msg and msg.arbitration_id == DEVICE_ID:
|
||||
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
|
||||
|
||||
if len(msg.data) < 8:
|
||||
print("Ошибка: Слишком короткий ответ")
|
||||
return None
|
||||
|
||||
# Извлечение данных и CRC
|
||||
data = msg.data
|
||||
received_crc = int.from_bytes(data[-2:], byteorder='little')
|
||||
|
||||
# Подготовка данных для проверки CRC
|
||||
id_bytes = msg.arbitration_id.to_bytes(1, 'little')
|
||||
full_data = list(id_bytes) + list(data[:-2])
|
||||
|
||||
# Проверка CRC
|
||||
calc_crc = validate_crc16(full_data)
|
||||
if calc_crc != received_crc:
|
||||
print(f"Ошибка CRC: ожидалось 0x{calc_crc:04X}, получено 0x{received_crc:04X}")
|
||||
return None
|
||||
|
||||
# Извлечение float значения
|
||||
try:
|
||||
value = struct.unpack('<f', bytes(data[1:5]))[0]
|
||||
return value
|
||||
except struct.error:
|
||||
print("Ошибка распаковки float")
|
||||
return None
|
||||
|
||||
print("Таймаут ожидания ответа")
|
||||
return None
|
||||
|
||||
def main():
|
||||
"""Основная логика чтения PID-коэффициентов"""
|
||||
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
|
||||
|
||||
try:
|
||||
# Чтение коэффициентов с задержкой
|
||||
print("\nЧтение Kp...")
|
||||
send_read_request(bus, DEVICE_ID, REG_MOTOR_POSPID_Kp)
|
||||
kp = receive_pid_response(bus)
|
||||
if kp is not None:
|
||||
print(f"Текущий Kp: {kp:.3f}")
|
||||
|
||||
time.sleep(1)
|
||||
|
||||
print("\nЧтение Ki...")
|
||||
send_read_request(bus, DEVICE_ID, REG_MOTOR_POSPID_Ki)
|
||||
ki = receive_pid_response(bus)
|
||||
if ki is not None:
|
||||
print(f"Текущий Ki: {ki:.3f}")
|
||||
|
||||
time.sleep(1)
|
||||
|
||||
print("\nЧтение Kd...")
|
||||
send_read_request(bus, DEVICE_ID, REG_MOTOR_POSPID_Kd)
|
||||
kd = receive_pid_response(bus)
|
||||
if kd is not None:
|
||||
print(f"Текущий Kd: {kd:.3f}")
|
||||
|
||||
finally:
|
||||
bus.shutdown()
|
||||
|
||||
if __name__ == "__main__":
|
||||
if len(sys.argv) != 2:
|
||||
print("Используйте python3 read_pid.py addr")
|
||||
sys.exit(1)
|
||||
main()
|
98
controller/fw/embed/test/read_angle.py
Normal file
98
controller/fw/embed/test/read_angle.py
Normal file
|
@ -0,0 +1,98 @@
|
|||
import can
|
||||
import struct
|
||||
import time
|
||||
import argparse
|
||||
|
||||
# Константы
|
||||
CAN_INTERFACE = 'can0'
|
||||
DEVICE_ID = 0x27 # ID ADDR for servo
|
||||
REG_WRITE = 0x7
|
||||
REG_POS = 0x72 # MOTOR+ANGLE = 0x72
|
||||
|
||||
def validate_crc16(data):
|
||||
# Calculate CRC16
|
||||
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 receive_response(bus, timeout=1.0):
|
||||
"""Ожидание ответа от устройства"""
|
||||
start_time = time.time()
|
||||
while time.time() - start_time < timeout:
|
||||
msg = bus.recv(timeout=0.1)
|
||||
if msg:
|
||||
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
|
||||
return msg
|
||||
print("[Ошибка] Таймаут")
|
||||
return None
|
||||
|
||||
def send_target_angle(bus):
|
||||
# ID and cmd
|
||||
arbitration_id = (DEVICE_ID << 4) | REG_WRITE
|
||||
id_bytes = list(arbitration_id.to_bytes(2, byteorder='little'))
|
||||
|
||||
# cmd + parametrs
|
||||
data_write = [REG_POS]
|
||||
|
||||
|
||||
full_data_for_crc = id_bytes + data_write
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
|
||||
|
||||
# Full packet
|
||||
packet = data_write + crc_bytes
|
||||
|
||||
|
||||
msg = can.Message(
|
||||
arbitration_id=arbitration_id,
|
||||
is_extended_id=False,
|
||||
data=packet
|
||||
)
|
||||
|
||||
bus.send(msg)
|
||||
response = receive_response(bus)
|
||||
|
||||
|
||||
if response:
|
||||
data = response.data
|
||||
|
||||
if len(data) < 4:
|
||||
print("Слишком короткий ответ")
|
||||
|
||||
# Проверяем минимальную длину ответа (данные + CRC)
|
||||
else:
|
||||
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
|
||||
#buff with id and data without CRC
|
||||
full_data = list(id_bytes) + list(data[:-2])
|
||||
print(f"Received full_data: {list(full_data)}")
|
||||
received_crc = int.from_bytes(data[-2:], byteorder='little')
|
||||
#calc CRC
|
||||
calc_crc = validate_crc16(full_data)
|
||||
|
||||
print(f"Расчитанный CRC PYTHON : 0x{calc_crc:02X}")
|
||||
if received_crc == calc_crc:
|
||||
# Если CRC совпадает, проверяем структуру ответа:
|
||||
velocity = struct.unpack('<f', bytes(data[1:5]))[0]
|
||||
print(f"Угол: {velocity}")
|
||||
else:
|
||||
print("Ошибка: CRC не совпадает")
|
||||
else:
|
||||
print("Устройство не ответило")
|
||||
|
||||
def main():
|
||||
# Инициализация CAN
|
||||
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
|
||||
print("CAN шина инициализирована.")
|
||||
|
||||
send_target_angle(bus)
|
||||
|
||||
bus.shutdown()
|
||||
if __name__ == '__main__':
|
||||
main()
|
108
controller/fw/embed/test/read_id.py
Normal file
108
controller/fw/embed/test/read_id.py
Normal file
|
@ -0,0 +1,108 @@
|
|||
import can
|
||||
import time
|
||||
import sys
|
||||
# Конфигурация
|
||||
CAN_INTERFACE = 'can0'
|
||||
OLD_DEVICE_ID = int(sys.argv[1]) # Текущий ID устройства (по умолчанию)
|
||||
REG_READ = 0x7 # Код команды чтения
|
||||
REG_ID = 0x01 # Адрес регистра с ID устройства
|
||||
|
||||
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 receive_response(bus, timeout=1.0):
|
||||
"""Ожидание ответа от устройства"""
|
||||
start_time = time.time()
|
||||
while time.time() - start_time < timeout:
|
||||
msg = bus.recv(timeout=0.1)
|
||||
if msg:
|
||||
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
|
||||
return msg
|
||||
print("[Ошибка] Таймаут")
|
||||
return None
|
||||
|
||||
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_READ
|
||||
|
||||
# Данные для запроса: [регистр, резервный байт]
|
||||
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("Запрос на чтение ID:", packet_read)
|
||||
send_can_message(bus, can_id_read, packet_read)
|
||||
|
||||
# ======= 2. Получение и проверка ответа =======
|
||||
response = receive_response(bus)
|
||||
if response:
|
||||
data = response.data
|
||||
|
||||
if len(data) < 4:
|
||||
print("Слишком короткий ответ")
|
||||
|
||||
# Проверяем минимальную длину ответа (данные + CRC)
|
||||
else:
|
||||
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
|
||||
#buff with id and data without CRC
|
||||
full_data = list(id_bytes) + list(data[:-2])
|
||||
print(f"Received full_data: {list(full_data)}")
|
||||
received_crc = int.from_bytes(data[-2:], byteorder='little')
|
||||
#calc CRC
|
||||
calc_crc = validate_crc16(full_data)
|
||||
|
||||
print(f"Расчитанный CRC PYTHON : 0x{calc_crc:02X}")
|
||||
if received_crc == calc_crc:
|
||||
# Если CRC совпадает, проверяем структуру ответа:
|
||||
print(f"Текущий ID устройства: 0x{data[1]:02X}")
|
||||
else:
|
||||
print("Ошибка: CRC не совпадает")
|
||||
else:
|
||||
print("Устройство не ответило")
|
||||
|
||||
# Завершаем работу с шиной
|
||||
bus.shutdown()
|
||||
|
||||
if __name__ == "__main__":
|
||||
import sys
|
||||
if len(sys.argv) != 2:
|
||||
print("Использование: python3 can_flasher.py address")
|
||||
sys.exit(1)
|
67
controller/fw/embed/test/send_angle.py
Normal file
67
controller/fw/embed/test/send_angle.py
Normal file
|
@ -0,0 +1,67 @@
|
|||
from can.interface import Bus
|
||||
import can
|
||||
import struct
|
||||
import time
|
||||
import argparse
|
||||
|
||||
# Константы
|
||||
CAN_INTERFACE = 'can0'
|
||||
DEVICE_ID = 0x27 # ID ADDR for servo
|
||||
REG_WRITE = 0x8
|
||||
REG_POS = 0x72 # MOTOR+ANGLE = 0x72
|
||||
|
||||
def validate_crc16(data):
|
||||
# Calculate CRC16
|
||||
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_target_angle(bus, target_angle):
|
||||
# ID and cmd
|
||||
arbitration_id = (DEVICE_ID << 4) | REG_WRITE
|
||||
id_bytes = list(arbitration_id.to_bytes(2, byteorder='little'))
|
||||
|
||||
# cmd + parametrs
|
||||
data_write = [REG_POS] + list(struct.pack('<f', target_angle))
|
||||
|
||||
|
||||
full_data_for_crc = id_bytes + data_write
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
|
||||
|
||||
# Full packet
|
||||
packet = data_write + crc_bytes
|
||||
|
||||
|
||||
msg = can.Message(
|
||||
arbitration_id=arbitration_id,
|
||||
is_extended_id=False,
|
||||
data=packet
|
||||
)
|
||||
|
||||
try:
|
||||
bus.send(msg)
|
||||
print(f"[Отправка] CAN ID: 0x{arbitration_id:03X}, Угол: {target_angle} rad, Данные: {list(msg.data)}")
|
||||
except can.CanError:
|
||||
print("Ошибка отправки сообщения")
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(description="Отправка угла позиции по CAN.")
|
||||
parser.add_argument("--angle", type=float, required=True, help="Угол (в градусах)")
|
||||
args = parser.parse_args()
|
||||
|
||||
# Инициализация CAN
|
||||
bus = Bus(channel=CAN_INTERFACE, bustype='socketcan')
|
||||
print("CAN шина инициализирована.")
|
||||
|
||||
send_target_angle(bus, args.angle)
|
||||
|
||||
bus.shutdown()
|
||||
if __name__ == '__main__':
|
||||
main()
|
124
controller/fw/embed/test/set_id.py
Normal file
124
controller/fw/embed/test/set_id.py
Normal file
|
@ -0,0 +1,124 @@
|
|||
import can
|
||||
import time
|
||||
import sys
|
||||
# Конфигурация
|
||||
CAN_INTERFACE = 'can0'
|
||||
OLD_DEVICE_ID = int(sys.argv[1])
|
||||
NEW_DEVICE_ID = int(sys.argv[2])
|
||||
REG_WRITE = 0x8
|
||||
REG_READ = 0x7
|
||||
REG_ID = 0x1
|
||||
|
||||
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 receive_response(bus, timeout=1.0):
|
||||
"""Ожидание ответа"""
|
||||
start_time = time.time()
|
||||
while time.time() - start_time < timeout:
|
||||
msg = bus.recv(timeout=0.1)
|
||||
if msg:
|
||||
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
|
||||
return msg
|
||||
print("[Ошибка] Таймаут")
|
||||
return None
|
||||
|
||||
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
|
||||
|
||||
# Инициализация
|
||||
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
|
||||
|
||||
# ======= 1. Отправляем команду изменить ID =======
|
||||
|
||||
# Весь буфер: id + команда + параметры
|
||||
OLD_WITH_REG = (OLD_DEVICE_ID << 4) | REG_WRITE
|
||||
id_bytes = list(OLD_WITH_REG.to_bytes(2, byteorder='little'))
|
||||
|
||||
# Важные части сообщения: address (id), команда, параметры
|
||||
data_write = [REG_ID, NEW_DEVICE_ID] # команда изменить ID
|
||||
|
||||
# Полностью собираем массив для CRC (включая id и команду)
|
||||
full_data_for_crc = id_bytes + data_write
|
||||
|
||||
# Расчет CRC по всему пакету
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
|
||||
|
||||
# Итоговый пакет: команда + параметры + CRC
|
||||
packet_write = data_write + crc_bytes
|
||||
|
||||
print("Отправляем: команда изменить ID + CRC:", packet_write)
|
||||
# Отправляем с `OLD_DEVICE_ID` в качестве адреса
|
||||
send_can_message(bus, (OLD_DEVICE_ID << 4) | REG_WRITE, packet_write)
|
||||
|
||||
time.sleep(1.0)
|
||||
|
||||
# ======= 2. Запрашиваем текущий ID (используем новый адрес) =======
|
||||
|
||||
# Теперь для запроса используем **уже новый id**
|
||||
NEW_WITH_REG = (NEW_DEVICE_ID << 4) | REG_READ
|
||||
current_id_bytes = list(NEW_WITH_REG.to_bytes(2, byteorder='little'))
|
||||
data_read = [REG_ID, 0x00]
|
||||
|
||||
full_data_for_crc = current_id_bytes + data_read
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
|
||||
packet_read = data_read + crc_bytes
|
||||
|
||||
print("Запрос на чтение ID + CRC (после смены):", packet_read)
|
||||
send_can_message(bus, (NEW_DEVICE_ID << 4) | REG_READ, packet_read)
|
||||
|
||||
# ======= 3. Получение и проверка ответа =======
|
||||
|
||||
response = receive_response(bus)
|
||||
if response:
|
||||
data = response.data
|
||||
if len(data) < 4:
|
||||
print("Ответ слишком короткий")
|
||||
else:
|
||||
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
|
||||
#buff with id and data without CRC
|
||||
full_data = list(id_bytes) + list(data[:-2])
|
||||
print(f"Received full_data: {list(full_data)}")
|
||||
received_crc = int.from_bytes(data[-2:], byteorder='little')
|
||||
#calc CRC
|
||||
calc_crc = validate_crc16(full_data)
|
||||
if received_crc == calc_crc:
|
||||
if data[0] == ord('I') and data[1] == NEW_DEVICE_ID:
|
||||
print(f"\nУСПЕХ! ID устройства изменен на 0x{NEW_DEVICE_ID:02X}")
|
||||
else:
|
||||
print(f"Некорректный ответ: {list(data)}")
|
||||
else:
|
||||
print("CRC не совпадает, данные повреждены.")
|
||||
else:
|
||||
print("Нет ответа от устройства.")
|
||||
|
||||
bus.shutdown()
|
||||
|
||||
if __name__ == "__main__":
|
||||
import sys
|
||||
if len(sys.argv) != 3:
|
||||
print("Использование: python3 can_flasher.py old_addr new addr")
|
||||
sys.exit(1)
|
78
controller/fw/embed/test/st-link.py
Normal file
78
controller/fw/embed/test/st-link.py
Normal 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)
|
100
controller/fw/embed/test/st-link_full.py
Normal file
100
controller/fw/embed/test/st-link_full.py
Normal 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)
|
95
controller/fw/embed/test/writePID_angle_parametrs.py
Normal file
95
controller/fw/embed/test/writePID_angle_parametrs.py
Normal file
|
@ -0,0 +1,95 @@
|
|||
import can
|
||||
import time
|
||||
import struct
|
||||
import sys
|
||||
# Конфигурация
|
||||
CAN_INTERFACE = 'can0'
|
||||
DEVICE_ID = int(sys.argv[1]) # ID ADDR for servo
|
||||
REG_WRITE = 0x8 # Код команды записи
|
||||
REG_MOTOR_POSPID_Kp = 0x30
|
||||
REG_MOTOR_POSPID_Ki = 0x31
|
||||
REG_MOTOR_POSPID_Kd = 0x32
|
||||
|
||||
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
|
||||
|
||||
def send_pid_value(bus, device_id, reg, value):
|
||||
"""Отправка коэффициента PID на устройство"""
|
||||
# Формируем CAN ID для записи: (device_id << 4) | REG_WRITE
|
||||
can_id_write = (device_id << 4) | REG_WRITE
|
||||
|
||||
# Упаковываем значение в байты (little-endian)
|
||||
float_bytes = struct.pack('<f', value)
|
||||
|
||||
# Формируем часть данных (регистр + значение)
|
||||
data_part = [reg] + list(float_bytes)
|
||||
|
||||
# Полные данные для расчета CRC: CAN ID + данные
|
||||
full_data_for_crc = list(can_id_write.to_bytes(2, 'little')) + data_part
|
||||
|
||||
# Рассчитываем CRC и разбиваем на байты (little-endian)
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, 'little'))
|
||||
|
||||
# Собираем итоговый пакет данных
|
||||
can_data = data_part + crc_bytes
|
||||
|
||||
# Отправляем сообщение
|
||||
send_can_message(bus, can_id_write, can_data)
|
||||
|
||||
def main():
|
||||
# Запрос коэффициентов у пользователя
|
||||
try:
|
||||
p = float(input("Введите коэффициент P: "))
|
||||
i = float(input("Введите коэффициент I: "))
|
||||
d = float(input("Введите коэффициент D: "))
|
||||
except ValueError:
|
||||
print("Ошибка: Введите числовые значения.")
|
||||
return
|
||||
|
||||
# Инициализация CAN-интерфейса
|
||||
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
|
||||
|
||||
try:
|
||||
# Отправка коэффициентов с задержкой
|
||||
send_pid_value(bus, DEVICE_ID, REG_MOTOR_POSPID_Kp, p)
|
||||
time.sleep(1)
|
||||
|
||||
send_pid_value(bus, DEVICE_ID, REG_MOTOR_POSPID_Ki, i)
|
||||
time.sleep(1)
|
||||
|
||||
send_pid_value(bus, DEVICE_ID, REG_MOTOR_POSPID_Kd, d)
|
||||
|
||||
finally:
|
||||
# Завершение работы с шиной
|
||||
bus.shutdown()
|
||||
|
||||
if __name__ == "__main__":
|
||||
if len(sys.argv) != 2:
|
||||
print("Используйте python3 pid_set.py addr")
|
||||
sys.exit(1)
|
||||
main()
|
122
controller/fw/embed/test/write_pidP.py
Normal file
122
controller/fw/embed/test/write_pidP.py
Normal file
|
@ -0,0 +1,122 @@
|
|||
import can
|
||||
import time
|
||||
import struct
|
||||
# Конфигурация
|
||||
CAN_INTERFACE = 'can0'
|
||||
DEVICE_ID = 0x00
|
||||
SET_PID_P = 3.6
|
||||
REG_WRITE = 0x8
|
||||
REG_READ = 0x7
|
||||
REG_ID = 0x30 #REG_MOTOR_POSPID_Kp
|
||||
PID_P = 0x01
|
||||
|
||||
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 receive_response(bus, timeout=1.0):
|
||||
print("Ожидание ответа")
|
||||
start_time = time.time()
|
||||
while time.time() - start_time < timeout:
|
||||
msg = bus.recv(timeout=0.1)
|
||||
if msg:
|
||||
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
|
||||
return msg
|
||||
print("[Ошибка] Таймаут")
|
||||
return None
|
||||
|
||||
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
|
||||
|
||||
# Инициализация
|
||||
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
|
||||
# Перевод float -> hex -> int
|
||||
result = (struct.unpack('<I',struct.pack('<f', float(SET_PID_P)))[0])
|
||||
result_bytes = result.to_bytes(4, byteorder='little')
|
||||
# ======= 1. Отправляем команду изменить ID =======
|
||||
|
||||
# Весь буфер: id + команда + параметры
|
||||
OLD_WITH_REG = (DEVICE_ID << 4) | REG_WRITE
|
||||
id_bytes = list(OLD_WITH_REG.to_bytes(2, byteorder='little'))
|
||||
|
||||
# Важные части сообщения: address (id), команда, параметры
|
||||
data_write = [REG_ID] + list(result_bytes) # команда изменить PID_P
|
||||
|
||||
# Полностью собираем массив для CRC (включая id и команду)
|
||||
full_data_for_crc = id_bytes + data_write
|
||||
|
||||
# Расчет CRC по всему пакету
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
|
||||
|
||||
# Итоговый пакет: команда + параметры + CRC
|
||||
packet_write = data_write + crc_bytes
|
||||
|
||||
print("Отправляем: команда изменить PID_p + CRC:", packet_write)
|
||||
# Отправляем с `OLD_DEVICE_ID` в качестве адреса
|
||||
send_can_message(bus, (DEVICE_ID << 4) | REG_WRITE, packet_write)
|
||||
|
||||
time.sleep(1.0)
|
||||
|
||||
# ======= 2. Запрашиваем текущий ID (используем новый адрес) =======
|
||||
|
||||
# Теперь для запроса используем **уже новый id**
|
||||
NEW_WITH_REG = (DEVICE_ID << 4) | REG_READ
|
||||
current_id_bytes = list(NEW_WITH_REG.to_bytes(2, byteorder='little'))
|
||||
data_read = [REG_ID, 0x00]
|
||||
|
||||
full_data_for_crc = current_id_bytes + data_read
|
||||
crc = validate_crc16(full_data_for_crc)
|
||||
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
|
||||
packet_read = data_read + crc_bytes
|
||||
|
||||
print("Запрос на чтение ID + CRC (после смены):", packet_read)
|
||||
send_can_message(bus, (DEVICE_ID << 4) | REG_READ, packet_read)
|
||||
|
||||
# ======= 3. Получение и проверка ответа =======
|
||||
|
||||
response = receive_response(bus)
|
||||
if response:
|
||||
data = response.data
|
||||
if len(data) < 4:
|
||||
print("Ответ слишком короткий")
|
||||
else:
|
||||
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
|
||||
#buff with id and data without CRC
|
||||
full_data = list(id_bytes) + list(data[:-2])
|
||||
print(f"Received full_data: {list(full_data)}")
|
||||
received_crc = int.from_bytes(data[-2:], byteorder='little')
|
||||
#calc CRC
|
||||
calc_crc = validate_crc16(full_data)
|
||||
if received_crc == calc_crc:
|
||||
if data[0] == int(REG_ID):
|
||||
kp_val = struct.unpack('<f', bytes(data[1:5]))[0]
|
||||
print(f"\nУСПЕХ! PID_P = {kp_val:.3f}")
|
||||
else:
|
||||
print(f"Некорректный ответ: {list(data)}")
|
||||
else:
|
||||
print("CRC не совпадает, данные повреждены.")
|
||||
else:
|
||||
print("Нет ответа от устройства.")
|
||||
|
||||
bus.shutdown()
|
Loading…
Add table
Add a link
Reference in a new issue