Add bootloader

This commit is contained in:
Valentin Dabstep 2025-05-22 18:03:43 +03:00
parent 4f42094b0e
commit 6844ca9a8d
35 changed files with 27266 additions and 13 deletions

View file

@ -0,0 +1 @@
Checks: '-*, -misc-definitions-in-headers'

View file

@ -0,0 +1,18 @@
CompileFlags:
Add:
[
# -mlong-calls,
-DSSIZE_MAX,
-DLWIP_NO_UNISTD_H=1,
-Dssize_t=long,
-D_SSIZE_T_DECLARED,
]
Remove:
[
-fno-tree-switch-conversion,
-mtext-section-literals,
-mlongcalls,
-fstrict-volatile-bitfields,
-free,
-fipa-pta,
]

9
controller/fw/bootloader/.gitignore vendored Normal file
View file

@ -0,0 +1,9 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch
.cache/
.metadata/
cubemx_config/
compile_commands.json

View file

@ -0,0 +1,20 @@
# Встроенное ПО для сервипривода на 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
```

View file

@ -0,0 +1,19 @@
Import("env")
# Получаем путь к компилятору из окружения PlatformIO
gcc_path = env.subst("$CC")
# Выполняем команду для получения версии компилятора
import subprocess
try:
result = subprocess.run([gcc_path, "--version"], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
if result.returncode == 0:
print(f"GCC version: {result.stdout}")
else:
print(f"Failed to get GCC version: {result.stderr}")
except Exception as e:
print(f"Error while getting GCC version: {e}")
# Дополнительно проверяем путь к компилятору
print(f"Compiler path: {gcc_path}")

View file

@ -0,0 +1,299 @@
#MicroXplorer Configuration settings - do not modify
ADC2.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_15
ADC2.Channel-5\#ChannelRegularConversion=ADC_CHANNEL_8
ADC2.Channel-6\#ChannelRegularConversion=ADC_CHANNEL_9
ADC2.EOCSelection=ADC_EOC_SEQ_CONV
ADC2.IPParameters=Rank-1\#ChannelRegularConversion,Channel-1\#ChannelRegularConversion,SamplingTime-1\#ChannelRegularConversion,NbrOfConversionFlag,InjNumberOfConversion,NbrOfConversion,Rank-5\#ChannelRegularConversion,Channel-5\#ChannelRegularConversion,SamplingTime-5\#ChannelRegularConversion,Rank-6\#ChannelRegularConversion,Channel-6\#ChannelRegularConversion,SamplingTime-6\#ChannelRegularConversion,EOCSelection
ADC2.InjNumberOfConversion=0
ADC2.NbrOfConversion=3
ADC2.NbrOfConversionFlag=1
ADC2.Rank-1\#ChannelRegularConversion=1
ADC2.Rank-5\#ChannelRegularConversion=2
ADC2.Rank-6\#ChannelRegularConversion=3
ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC2.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC2.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
FREERTOS.IPParameters=Tasks01,configENABLE_FPU,configTIMER_TASK_PRIORITY
FREERTOS.Tasks01=defaultTask,24,128,StartDefaultTask,Default,NULL,Dynamic,NULL,NULL
FREERTOS.configENABLE_FPU=1
FREERTOS.configTIMER_TASK_PRIORITY=1
File.Version=6
GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=false
Mcu.CPN=STM32F446RET6
Mcu.Family=STM32F4
Mcu.IP0=ADC2
Mcu.IP1=FREERTOS
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI2
Mcu.IP5=SYS
Mcu.IP6=TIM1
Mcu.IP7=TIM3
Mcu.IP8=TIM5
Mcu.IP9=USART1
Mcu.IPNb=10
Mcu.Name=STM32F446R(C-E)Tx
Mcu.Package=LQFP64
Mcu.Pin0=PC1
Mcu.Pin1=PC5
Mcu.Pin10=PC9
Mcu.Pin11=PA8
Mcu.Pin12=PA9
Mcu.Pin13=PA10
Mcu.Pin14=PA11
Mcu.Pin15=PA12
Mcu.Pin16=PA13
Mcu.Pin17=PA14
Mcu.Pin18=PC10
Mcu.Pin19=PC11
Mcu.Pin2=PB0
Mcu.Pin20=PC12
Mcu.Pin21=PD2
Mcu.Pin22=PB6
Mcu.Pin23=PB7
Mcu.Pin24=VP_FREERTOS_VS_CMSIS_V2
Mcu.Pin25=VP_SYS_VS_tim2
Mcu.Pin26=VP_TIM1_VS_ClockSourceINT
Mcu.Pin27=VP_TIM3_VS_ClockSourceINT
Mcu.Pin28=VP_TIM5_VS_ClockSourceINT
Mcu.Pin3=PB1
Mcu.Pin4=PB10
Mcu.Pin5=PB14
Mcu.Pin6=PB15
Mcu.Pin7=PC6
Mcu.Pin8=PC7
Mcu.Pin9=PC8
Mcu.PinsNb=29
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F446RETx
MxCube.Version=6.5.0
MxDb.Version=DB.6.0.50
NVIC.ADC_IRQn=true\:5\:0\:true\:true\:true\:1\:true\:true\:true\:true
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.PendSV_IRQn=true\:15\:0\:false\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SPI2_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:false\:false\:false\:false\:false
NVIC.SavedPendsvIrqHandlerGenerated=true
NVIC.SavedSvcallIrqHandlerGenerated=true
NVIC.SavedSystickIrqHandlerGenerated=true
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:false\:true\:false\:true\:false
NVIC.TIM2_IRQn=true\:15\:0\:true\:false\:true\:false\:false\:true\:true
NVIC.TIM3_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.TimeBase=TIM2_IRQn
NVIC.TimeBaseIP=TIM2
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
PA10.Signal=S_TIM1_CH3
PA11.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PA11.GPIO_Label=EN_U
PA11.GPIO_PuPd=GPIO_PULLDOWN
PA11.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PA11.Locked=true
PA11.Signal=GPIO_Output
PA12.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PA12.GPIO_Label=EN_V
PA12.GPIO_PuPd=GPIO_PULLDOWN
PA12.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PA12.Locked=true
PA12.Signal=GPIO_Output
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
PA14.Signal=SYS_JTCK-SWCLK
PA8.Signal=S_TIM1_CH1
PA9.Signal=S_TIM1_CH2
PB0.GPIOParameters=GPIO_Label
PB0.GPIO_Label=SENSE2
PB0.Locked=true
PB0.Signal=ADCx_IN8
PB1.GPIOParameters=GPIO_Label
PB1.GPIO_Label=SENSE1
PB1.Locked=true
PB1.Signal=ADCx_IN9
PB10.Locked=true
PB10.Mode=Full_Duplex_Master
PB10.Signal=SPI2_SCK
PB14.Locked=true
PB14.Mode=Full_Duplex_Master
PB14.Signal=SPI2_MISO
PB15.GPIOParameters=GPIO_Speed,PinState,GPIO_PuPd,GPIO_Label
PB15.GPIO_Label=AS5045_CS
PB15.GPIO_PuPd=GPIO_PULLUP
PB15.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
PB15.Locked=true
PB15.PinState=GPIO_PIN_SET
PB15.Signal=GPIO_Output
PB6.Mode=Asynchronous
PB6.Signal=USART1_TX
PB7.Mode=Asynchronous
PB7.Signal=USART1_RX
PC1.Mode=Full_Duplex_Master
PC1.Signal=SPI2_MOSI
PC10.GPIOParameters=GPIO_Label
PC10.GPIO_Label=LED1
PC10.Locked=true
PC10.Signal=GPIO_Output
PC11.GPIOParameters=GPIO_Label
PC11.GPIO_Label=LED2
PC11.Locked=true
PC11.Signal=GPIO_Output
PC12.GPIOParameters=GPIO_Label
PC12.GPIO_Label=LED3
PC12.Locked=true
PC12.Signal=GPIO_Output
PC5.GPIOParameters=GPIO_Label
PC5.GPIO_Label=SENSE3
PC5.Locked=true
PC5.Signal=ADCx_IN15
PC6.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PC6.GPIO_Label=EN_W
PC6.GPIO_PuPd=GPIO_PULLDOWN
PC6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PC6.Locked=true
PC6.Signal=GPIO_Output
PC7.GPIOParameters=GPIO_Label
PC7.GPIO_Label=DRV_FAULT
PC7.Locked=true
PC7.Signal=GPIO_Input
PC8.GPIOParameters=GPIO_Label
PC8.GPIO_Label=DRV_RESET
PC8.Locked=true
PC8.Signal=GPIO_Output
PC9.GPIOParameters=GPIO_Label
PC9.GPIO_Label=DRV_SLEEP
PC9.Locked=true
PC9.Signal=GPIO_Output
PD2.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PD2.GPIO_Label=spi1_cs
PD2.GPIO_PuPd=GPIO_PULLDOWN
PD2.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
PD2.Locked=true
PD2.Signal=GPIO_Output
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=true
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F446RETx
ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.27.1
ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=STM32CubeIDE
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=cubemx_config.ioc
ProjectManager.ProjectName=cubemx_config
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=Other Toolchains (GPDSC)
ProjectManager.ToolChainLocation=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_TIM1_Init-TIM1-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-HAL-true,5-MX_SPI2_Init-SPI2-false-HAL-true,6-MX_TIM3_Init-TIM3-false-HAL-true,7-MX_ADC2_Init-ADC2-false-HAL-true,8-MX_TIM5_Init-TIM5-false-HAL-true
RCC.AHBFreq_Value=180000000
RCC.APB1CLKDivider=RCC_HCLK_DIV4
RCC.APB1Freq_Value=45000000
RCC.APB1TimFreq_Value=90000000
RCC.APB2CLKDivider=RCC_HCLK_DIV2
RCC.APB2Freq_Value=90000000
RCC.APB2TimFreq_Value=180000000
RCC.CECFreq_Value=32786.88524590164
RCC.CortexFreq_Value=180000000
RCC.FCLKCortexFreq_Value=180000000
RCC.FMPI2C1Freq_Value=45000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=180000000
RCC.HSE_VALUE=8000000
RCC.I2S1Freq_Value=96000000
RCC.I2S2Freq_Value=96000000
RCC.IPParameters=AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CECFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FMPI2C1Freq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,I2S1Freq_Value,I2S2Freq_Value,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLI2SPCLKFreq_Value,PLLI2SQCLKFreq_Value,PLLI2SRCLKFreq_Value,PLLI2SoutputFreq_Value,PLLM,PLLN,PLLQCLKFreq_Value,PLLRCLKFreq_Value,PLLSAIPCLKFreq_Value,PLLSAIQCLKFreq_Value,PLLSAIoutputFreq_Value,PWRFreq_Value,SAIAFreq_Value,SAIBFreq_Value,SDIOFreq_Value,SPDIFRXFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,USBFreq_Value,VCOI2SInputFreq_Value,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAIInputFreq_Value,VCOSAIOutputFreq_Value
RCC.MCO2PinFreq_Value=180000000
RCC.PLLCLKFreq_Value=180000000
RCC.PLLI2SPCLKFreq_Value=96000000
RCC.PLLI2SQCLKFreq_Value=96000000
RCC.PLLI2SRCLKFreq_Value=96000000
RCC.PLLI2SoutputFreq_Value=96000000
RCC.PLLM=8
RCC.PLLN=180
RCC.PLLQCLKFreq_Value=180000000
RCC.PLLRCLKFreq_Value=180000000
RCC.PLLSAIPCLKFreq_Value=96000000
RCC.PLLSAIQCLKFreq_Value=96000000
RCC.PLLSAIoutputFreq_Value=96000000
RCC.PWRFreq_Value=180000000
RCC.SAIAFreq_Value=96000000
RCC.SAIBFreq_Value=96000000
RCC.SDIOFreq_Value=180000000
RCC.SPDIFRXFreq_Value=180000000
RCC.SYSCLKFreq_VALUE=180000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.USBFreq_Value=180000000
RCC.VCOI2SInputFreq_Value=1000000
RCC.VCOI2SOutputFreq_Value=192000000
RCC.VCOInputFreq_Value=2000000
RCC.VCOOutputFreq_Value=360000000
RCC.VCOSAIInputFreq_Value=1000000
RCC.VCOSAIOutputFreq_Value=192000000
SH.ADCx_IN15.0=ADC2_IN15,IN15
SH.ADCx_IN15.ConfNb=1
SH.ADCx_IN8.0=ADC2_IN8,IN8
SH.ADCx_IN8.ConfNb=1
SH.ADCx_IN9.0=ADC2_IN9,IN9
SH.ADCx_IN9.ConfNb=1
SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1
SH.S_TIM1_CH1.ConfNb=1
SH.S_TIM1_CH2.0=TIM1_CH2,PWM Generation2 CH2
SH.S_TIM1_CH2.ConfNb=1
SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3
SH.S_TIM1_CH3.ConfNb=1
SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_64
SPI2.CLKPhase=SPI_PHASE_1EDGE
SPI2.CLKPolarity=SPI_POLARITY_LOW
SPI2.CalculateBaudRate=703.125 KBits/s
SPI2.DataSize=SPI_DATASIZE_16BIT
SPI2.Direction=SPI_DIRECTION_2LINES
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,CLKPhase,BaudRatePrescaler,CLKPolarity
SPI2.Mode=SPI_MODE_MASTER
SPI2.VirtualType=VM_MASTER
TIM1.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
TIM1.BreakState=TIM_BREAK_DISABLE
TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM1.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
TIM1.CounterMode=TIM_COUNTERMODE_CENTERALIGNED1
TIM1.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,TIM_MasterOutputTrigger,AutoReloadPreload,BreakState,OffStateRunMode,OffStateIDLEMode,CounterMode,Period
TIM1.OffStateIDLEMode=TIM_OSSI_DISABLE
TIM1.OffStateRunMode=TIM_OSSR_DISABLE
TIM1.Period=2399
TIM1.TIM_MasterOutputTrigger=TIM_TRGO_RESET
TIM3.IPParameters=Period,Prescaler
TIM3.Period=99
TIM3.Prescaler=89
USART1.IPParameters=VirtualMode
USART1.VirtualMode=VM_ASYNC
VP_FREERTOS_VS_CMSIS_V2.Mode=CMSIS_V2
VP_FREERTOS_VS_CMSIS_V2.Signal=FREERTOS_VS_CMSIS_V2
VP_SYS_VS_tim2.Mode=TIM2
VP_SYS_VS_tim2.Signal=SYS_VS_tim2
VP_TIM1_VS_ClockSourceINT.Mode=Internal
VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
VP_TIM3_VS_ClockSourceINT.Mode=Internal
VP_TIM3_VS_ClockSourceINT.Signal=TIM3_VS_ClockSourceINT
VP_TIM5_VS_ClockSourceINT.Mode=Internal
VP_TIM5_VS_ClockSourceINT.Signal=TIM5_VS_ClockSourceINT
board=custom

View file

@ -0,0 +1,8 @@
import os
Import("env")
# include toolchain paths
env.Replace(COMPILATIONDB_INCLUDE_TOOLCHAIN=True)
# override compilation DB path
env.Replace(COMPILATIONDB_PATH="compile_commands.json")

@ -0,0 +1 @@
Subproject commit 01e1b2f27e07936f3b700e2d02c28ba75c32179d

File diff suppressed because one or more lines are too long

Binary file not shown.

Binary file not shown.

View file

@ -0,0 +1,44 @@
#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

@ -0,0 +1,32 @@
#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

@ -0,0 +1,10 @@
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

@ -0,0 +1,42 @@
#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

@ -0,0 +1,20 @@
#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

@ -0,0 +1,10 @@
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

@ -0,0 +1,46 @@
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

@ -0,0 +1,28 @@
; 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
framework = arduino
upload_protocol = stlink
debug_tool = stlink
monitor_speed = 19200
monitor_parity = N
build_flags =
-DSTM32F446xx
-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

View file

@ -0,0 +1,272 @@
#include "flash.h"
#include <stdbool.h>
#include "hal_conf_extra.h"
void flash_unlock(){
// Check if flash is locked
if(!(FLASH->CR & FLASH_CR_LOCK)) {
return; // Already unlocked
}
// Write flash key sequence to unlock
FLASH->KEYR = 0x45670123; // First key
FLASH->KEYR = 0xCDEF89AB; // Second key
}
void flash_lock() {
if(FLASH->CR & FLASH_CR_LOCK) {
return; // Already locked
}
FLASH->CR |= FLASH_CR_LOCK; // Lock flash memory
}
void erase_sector(uint8_t sector){
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set sector erase bit and sector number
FLASH->CR |= FLASH_CR_SER;
FLASH->CR &= ~FLASH_CR_SNB;
FLASH->CR |= (sector << FLASH_CR_SNB_Pos) & FLASH_CR_SNB_Msk;
// Start erase
FLASH->CR |= FLASH_CR_STRT;
// Wait for erase to complete
while(FLASH_BUSY);
// Clear sector erase bit
FLASH->CR &= ~FLASH_CR_SER;
}
void flash_program_word(uint32_t address,uint32_t data,uint32_t byte_len){
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set program bit 32bit programm size and Write data to address
if(byte_len == 1) {
FLASH_8BYTE;
FLASH->CR |= FLASH_CR_PG;
*(volatile uint8_t*)address = (uint8_t)data;
} else {
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
*(volatile uint32_t*)address = data;
}
// Wait for programming to complete
while(FLASH_BUSY);
// Clear program bit
FLASH->CR &= ~FLASH_CR_PG;
}
void flash_write(uint32_t addr, FLASH_RECORD* record){
uint32_t* data = (uint32_t*)record;
uint32_t size = FLASH_RECORD_SIZE / 4; //count words in struct
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set program bit and write data to flash
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
for(int i = 0;i < size;i++){
*(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();
}
uint8_t flash_read_word(uint32_t address){
// Check if address is valid
if(address < FLASH_BASE || address > FLASH_END) {
return 0;
}
// Read byte from flash memory
return *((volatile uint8_t*)address);
}
// Wait if flash
// 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; // start value for CRC MODBUS
while (length--) {
crc ^= *data++; // XOR
for (uint8_t i = 0; i < 8; i++) {
if (crc & 0x0001) {
crc = (crc >> 1) ^ 0xA001; // polynome 0x8005 (reverse)
} else {
crc >>= 1;
}
}
}
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;
}
/* read struct from FLASH */
void flash_read(uint32_t addr,FLASH_RECORD* ptr){
uint8_t* flash_ptr = (uint8_t*)addr;
uint8_t* dest = (uint8_t*)ptr;
for(int i = 0;i < FLASH_RECORD_SIZE;i++)
dest[i] = flash_ptr[i];
}
void compact_page(){
FLASH_RECORD latest[PARAM_COUNT] = {0};
for(int i = (uint32_t)SECTOR_6;i < (uint32_t)SECTOR_6_END;i += FLASH_RECORD_SIZE) {
FLASH_RECORD rec;
flash_read(i,&rec);
uint16_t calculated_crc = calc_crc_struct(&rec);
if (calculated_crc == rec.crc && rec.data_id < PARAM_COUNT) {
// if the crc does not match, we check further
latest[rec.data_id] = rec;
}
else
// if
continue;
}
erase_sector(6);
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));
}
flash_write(write_ptr, &latest[i]);
}
}
}
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(&param_flash);
// 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(); // after compact_page update
// alignment
if (write_ptr % 8 != 0) {
write_ptr += (8 - (write_ptr % 8));
}
}
flash_write(write_ptr, &param_flash); //inside the function, the write_ptr pointer is automatically incremented by the size of the structure
// __enable_irq(); // Interrupt on
}
void write_flash_page(const uint8_t* data, uint16_t len) { // Добавлен const
flash_unlock();
uint32_t word = 0;
for (uint16_t i = 0; i < len; i += 4) {
memcpy(&word, &data[i], 4); // Безопасное копирование
HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, ptr_fl + i, word);
}
ptr_fl += len;
flash_lock();
}
void erase_flash_pages() {
FLASH_EraseInitTypeDef erase;
erase.TypeErase = FLASH_TYPEERASE_SECTORS;
erase.Sector = FLASH_SECTOR_2;
erase.NbSectors = 4;
erase.VoltageRange = FLASH_VOLTAGE_RANGE_3;
uint32_t error;
flash_unlock();
HAL_FLASHEx_Erase(&erase, &error);
flash_lock();
}
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);
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;
}
}
__enable_irq();
return latest;
}

View file

@ -0,0 +1,161 @@
#include "Arduino.h"
#include <STM32_CAN.h>
#include "flash.h"
STM32_CAN Can(CAN2, DEF);
volatile bool fw_update = false;
volatile uint32_t fw_size = 0;
volatile uint16_t fw_crc = 0;
volatile uint32_t jump;
static FLASH_RECORD *flash_record = {0};
static uint32_t ptr_flash;
volatile uint32_t msg_id;
volatile uint16_t id_x;
volatile uint8_t msg_ch;
// Прототипы функций
void jump_to_app();
void process_can_message(const CAN_message_t &msg);
void erase_flash_pages();
bool verify_firmware();
void send_ack(uint8_t status);
void setup() {
// Инициализация периферии
SystemInit();
SystemClock_Config();
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
Can.begin();
Can.setBaudRate(1000000);
TIM_TypeDef *Instance = TIM2;
HardwareTimer *SendTimer = new HardwareTimer(Instance);
SendTimer->setOverflow(100, HERTZ_FORMAT); // 50 Hz
// SendTimer->attachInterrupt(process_can_message);
SendTimer->resume();
// Разрешить все ID (маска 0x00000000)
Can.setFilter(0, 0, STD);
// Настройка GPIO
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
GPIOC->MODER |= GPIO_MODER_MODE10_0 | GPIO_MODER_MODE11_0;
GPIOC->ODR &= ~GPIO_ODR_OD11;
GPIOC->ODR |= GPIO_ODR_OD10;
// // Проверка флага обновления
// erase_sector(7);
// flash_program_word(FLAG_BOOT,0xDEADBEEF,BYTE32);
flash_record = load_params();
// write_param(addr_id,33);
// flash_record = load_params();
/* Добавить проверку адреса, т.е во время отправки запроса прошивки по CAN
мы сохраняем как флаг, так и аддрес устройства к которому будет обращатлься во
время прошивки */
if(*(volatile uint32_t*)(FLAG_BOOT) == UPDATE_FLAG) {
fw_update = true;
for(int i = 0; i < 5;i++){
GPIOC->ODR ^= GPIO_ODR_OD10; // Индикация обновления
delay(100);
}
erase_flash_pages();
} else {
jump_to_app();
}
GPIOC->ODR |= GPIO_ODR_OD10;
}
void process_can_message(const CAN_message_t &msg) {
msg_id = msg.id;
/* 0x691
69 - адрес устройства
1 - что делать дальше с данными */
id_x = (msg_id >> 4) & 0xFFFF; //получение адреса устройства страшие 2 бита
msg_ch = msg_id & 0xF; // получения id, чтобы выбрать, что делать
if(id_x == flash_record[addr_id].value){
switch(msg_ch) {
case BOOT_CAN_ID:
if(msg.buf[0] == 0x01) { // Старт передачи
fw_size = *(uint32_t*)&msg.buf[1]; //размер прошивки тип 4 байта
fw_crc = *(uint16_t*)&msg.buf[5]; //crc
ptr_flash = APP_ADDRESS;
send_ack(0x01);
}
break;
case DATA_CAN_ID: // Пакет данных
if(ptr_flash < (APP_ADDRESS + fw_size)) {
write_flash_page((const uint8_t*)msg.buf, msg.len);
ptr_flash += msg.len;
send_ack(0x02);
}
break;
case BOOT_CAN_END: // Завершение передачи
if(verify_firmware()) {
send_ack(0xAA);
erase_sector(7); // Сброс флага
NVIC_SystemReset();
} else {
send_ack(0x55);
}
break;
}
}
}
void jump_to_app() {
__disable_irq();
jump = *(volatile uint32_t*)(APP_ADDRESS + 4);
void (*app_entry)(void);
app_entry = (void (*)(void))jump;
for (uint32_t i = 0; i < 8; i++) {
NVIC->ICPR[i] = 0xFFFFFFFF;
}
__set_MSP(*(volatile uint32_t*)APP_ADDRESS);
// SCB->VTOR = (uint32_t)0x08008004;
app_entry();
}
volatile uint32_t add = (uint32_t)APP_ADDRESS;
bool verify_firmware() {
uint16_t calculated_crc = 0;
calculated_crc = validate_crc16((uint8_t*)add,fw_size);
return (calculated_crc == fw_crc);
}
void send_ack(uint8_t status) {
CAN_message_t ack;
ack.id = ACK_CAN_ID;
ack.len = 1;
ack.buf[0] = status;
Can.write(ack);
}
void loop() {
if(fw_update) {
CAN_message_t msg;
while(Can.read(msg))
process_can_message(msg);
}
}

View file

@ -0,0 +1,86 @@
# 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,47 @@
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

@ -0,0 +1,54 @@
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

@ -0,0 +1,37 @@
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

@ -0,0 +1,76 @@
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

@ -0,0 +1,73 @@
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

@ -0,0 +1,35 @@
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

@ -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")

View 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")
)

View file

@ -18,11 +18,17 @@ upload_protocol = stlink
debug_tool = stlink
monitor_speed = 19200
monitor_parity = N
build_flags =
-DSTM32F446xx
-D HAL_CAN_MODULE_ENABLED
-D SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
-Wl,-T"${platformio.packages_dir}/framework-arduinoststm32/variants/STM32F4xx/F446R(C-E)T/ldscript.ld"
-Wl,--defsym=LD_FLASH_OFFSET=0x8000
-DAPP_OFFSET=0x8000
lib_deps =
askuric/Simple FOC@^2.3.4
pazi88/STM32_CAN@^1.1.2
extra_scripts = pre:gen_compile_commands.py
extra_scripts =
post:hex_compile.py
pre:gen_compile_commands.py

View file

@ -34,11 +34,11 @@ void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
// PID Configuration
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;
motor->PID_velocity.P = 0.75f;
motor->PID_velocity.I = 20.0f;
motor->LPF_velocity.Tf = 0.005f;
motor->P_angle.P = 0.5f;
motor->LPF_angle.Tf = 0.001f;
// Motor limits
motor->velocity_limit = 40; // Speed limit in rad/s (382 rpm)

View file

@ -145,16 +145,22 @@ uint16_t calc_crc_struct(FLASH_RECORD* res){
/* from 32 to 8 bit */
for(int i = 0;i < 4;i++)
arr_res[i + 2] = (uint8_t)(res->value >> i * 4);
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++)

View file

@ -63,8 +63,7 @@ volatile uint32_t ipsr_value = 0;
void setup(){
// Vector table initialization (commented out)
// __set_MSP(*(volatile uintф32_t*)0x08008000);
// SCB->VTOR = (volatile uint32_t)0x08008000;
SCB->VTOR = (uint32_t)0x08008004;
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
@ -78,8 +77,9 @@ volatile uint32_t ipsr_value = 0;
Can.setBaudRate(1000000);
// Настройка прерываний CAN
CAN2->IER |= CAN_IER_FMPIE0;
flash_rec = load_params();
flash_rec = load_params(); //for update write_ptr
// write_param(addr_id,39);
// flash_rec = load_params();
// Initialize FOC system
setup_foc(&encoder, &motor, &driver, &current_sense, &command, doMotor);
@ -87,7 +87,7 @@ volatile uint32_t ipsr_value = 0;
CAN2->IER |= CAN_IER_FMPIE0 | // Сообщение в FIFO0
CAN_IER_FFIE0 | // FIFO0 full
CAN_IER_FOVIE0; // FIFO0 overflow
HAL_NVIC_SetPriority(CAN2_RX0_IRQn, 1, 0);
// HAL_NVIC_SetPriority(CAN2_RX0_IRQn, 1, 0);
// HAL_NVIC_EnableIRQ(CAN2_RX0_IRQn);
// Default motor configuration
@ -101,6 +101,7 @@ volatile uint32_t ipsr_value = 0;
void loop() {
__enable_irq();
foc_step(&motor, &command);
CAN_message_t msg;
@ -114,6 +115,7 @@ void loop() {
/* If receive data from CAN */
if(CAN_GET) {
listen_can(msg);
CAN_GET = false;
}
}