Removed unnecessary fillets, surfaces, and construction elements from each part; Eliminated duplicate parts; Restructured file and folder organization.

This commit is contained in:
Igor Brylev 2025-01-13 15:09:31 +00:00
parent dcf22ec341
commit 328dd0e0aa
192 changed files with 130019 additions and 721896 deletions

5
controller/fw/embed/.gitignore vendored Normal file
View file

@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch

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,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,38 @@
#pragma once
#pragma region "Motor and sensor setup"
#define LED1 PC10
#define LED2 PC11
#define HARDWARE_SERIAL_RX_PIN PB7
#define HARDWARE_SERIAL_TX_PIN PB6
#define AS5045_CS PB15
#define AS5045_MISO PB14
#define AS5045_MOSI PC1
#define AS5045_SCLK PB10
#define CURRENT_SENSOR_1 PB1
#define CURRENT_SENSOR_2 PB0
#define CURRENT_SENSOR_3 PC5
#define TIM1_CH1 PA8
#define TIM1_CH2 PA9
#define TIM1_CH3 PA10
#define EN_W_GATE_DRIVER PC6
#define EN_U_GATE_DRIVER PA11
#define EN_V_GATE_DRIVER PA12
#define SLEEP_DRIVER PC9
#define RESET_DRIVER PC8
#define FAULT_DRIVER PC7
#define POLE_PAIRS 14
#define CAN2_TX PB13
#define CAN2_RX PB12
#define CAN1_TX PB9
#define CAN1_RX PB8
#define GM6208_RESISTANCE 31
#define OWN_RESISTANCE 26
#pragma endregion
#if !defined(HAL_CAN_MODULE_ENABLED)
#define HAL_CAN_MODULE_ENABLED
#endif
#include "stm32f4xx_hal.h"
#include "stm32f4xx_hal_can.h"
#include <STM32_CAN.h>

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,27 @@
; 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 = 115200
monitor_parity = N
build_flags =
-DSTM32F446xx
-D HAL_CAN_MODULE_ENABLED
-D SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
lib_deps =
askuric/Simple FOC@^2.3.2
pazi88/STM32_CAN@^1.1.0

View file

@ -0,0 +1,121 @@
// clang-format off
#include <Arduino.h>
#include <SimpleFOC.h>
#include <STM32_CAN.h>
#include <AS5045.h>
#include <DRV8313.h>
#include "hal_conf_extra.h"
// clang-format on
STM32_CAN Can(CAN2, DEF);
static CAN_message_t CAN_TX_msg;
static CAN_message_t CAN_inMsg;
SPIClass spi;
MagneticSensorAS5045 sensor(AS5045_CS, AS5045_MOSI, AS5045_MISO, AS5045_SCLK);
BLDCMotor motor(POLE_PAIRS);
DRV8313Driver driver(TIM1_CH1, TIM1_CH2, TIM1_CH3, EN_W_GATE_DRIVER,
EN_U_GATE_DRIVER, EN_V_GATE_DRIVER, SLEEP_DRIVER,
RESET_DRIVER, FAULT_DRIVER);
LowsideCurrentSense current_sense(0.0125, 20, CURRENT_SENSOR_1, CURRENT_SENSOR_2,
CURRENT_SENSOR_3);
Commander command(Serial);
void doMotor(char *cmd) {
command.motor(&motor, cmd);
digitalWrite(PC10, !digitalRead(PC10));
delayMicroseconds(2);
}
void setup_foc(MagneticSensorAS5045 *sensor, BLDCMotor *motor, DRV8313Driver *driver,
LowsideCurrentSense *current_sense, Commander *commander,
CommandCallback callback) {
sensor->init(&spi);
motor->linkSensor(sensor);
driver->pwm_frequency = 20000;
driver->voltage_power_supply = 20;
driver->voltage_limit = 40;
driver->init();
motor->linkDriver(driver);
current_sense->linkDriver(driver);
current_sense->init();
motor->linkCurrentSense(current_sense);
SimpleFOCDebug::enable(nullptr);
commander->add('M', callback, "motor");
motor->useMonitoring(Serial);
motor->monitor_start_char = 'M';
motor->monitor_end_char = 'M';
commander->verbose = VerboseMode::machine_readable;
motor->controller = MotionControlType::angle;
motor->torque_controller = TorqueControlType::voltage;
motor->foc_modulation = FOCModulationType::SinePWM;
motor->PID_velocity.P = 0.3;
motor->PID_velocity.I = 15;
motor->PID_velocity.D = 0.001;
motor->PID_velocity.output_ramp = 1000;
motor->LPF_velocity.Tf = 0.005;
motor->LPF_angle.Tf = 0.005;
motor->P_angle.P = 15;
motor->velocity_limit = 40;
motor->voltage_limit = 40;
motor->sensor_direction = Direction::CCW;
current_sense->skip_align = true;
motor->init();
motor->initFOC();
}
void send_data() {
// TODO(vanyabeat) add can functionability for ROS packets
CAN_TX_msg.id = 1;
CAN_TX_msg.buf[0] = 'A';
CAN_TX_msg.len = 5;
Can.write(CAN_TX_msg);
digitalWrite(PC11, !digitalRead(PC11));
}
void read_can_message() {
float angle;
memcpy(&angle, &CAN_inMsg.buf[1], sizeof(angle));
motor.target = angle;
digitalWrite(PC10, !digitalRead(PC10));
}
void run_foc(BLDCMotor *motor, Commander *commander) {
motor->loopFOC();
motor->move();
motor->monitor();
commander->run();
}
void setup() {
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
// setup led pin
pinMode(PC11, OUTPUT);
pinMode(PC10, OUTPUT);
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();
setup_foc(&sensor, &motor, &driver, &current_sense, &command, doMotor);
_delay(1000);
}
float current_angle = 0;
void loop() {
run_foc(&motor, &command);
current_angle = sensor.getAngle();
memcpy(&CAN_TX_msg.buf[1], &current_angle, sizeof(current_angle));
while (Can.read(CAN_inMsg)) {
read_can_message();
}
}

View file

@ -0,0 +1,11 @@
This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html

View file

@ -0,0 +1,4 @@
#!/bin/bash
ip link set can0 type can bitrate 1000000
ip link set up can0

View file

@ -0,0 +1,34 @@
#!/bin/bash
# Read 8 byte ascii from $1 and send it to CAN bus
# <can_id>:
# 3 (SFF) or 8 (EFF) hex chars
# {data}:
# 0..8 (0..64 CAN FD) ASCII hex-values (optionally separated by '.')
# {len}:
# an optional 0..8 value as RTR frames can contain a valid dlc field
# <flags>:
# a single ASCII Hex value (0 .. F) which defines canfd_frame.flags
can_id=$1
input=$2
if [[ ${#input} -gt 8 ]]; then
echo "Error: Input string must be no longer than 8 characters."
exit 1
fi
hex_output=""
for (( i=0; i<${#input}; i++ )); do
hex_char=$(printf "%02x" "'${input:$i:1}")
hex_output+="${hex_char}"
done
hex_output=$(printf "%-16s" "$hex_output")
hex_output=${hex_output// /0}
can_id=$(printf "%03X" $can_id)
cansend can0 $can_id#$hex_output

View file

@ -0,0 +1,30 @@
#!/bin/bash
/bin/bash $(pwd)/send_can.sh 1 E0
/bin/bash $(pwd)/send_can.sh 1 E1
/bin/bash $(pwd)/send_can.sh 1 C2
/bin/bash $(pwd)/send_can.sh 1 1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 -1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 -1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 2
sleep 1
/bin/bash $(pwd)/send_can.sh 1 C1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 0.5
sleep 5
/bin/bash $(pwd)/send_can.sh 1 2
sleep 5
/bin/bash $(pwd)/send_can.sh 1 5
sleep 5
/bin/bash $(pwd)/send_can.sh 1 -5
sleep 5
/bin/bash $(pwd)/send_can.sh 1 20
sleep 5
/bin/bash $(pwd)/send_can.sh 1 E0

View file

@ -0,0 +1,525 @@
(kicad_symbol_lib (version 20220914) (generator kicad_symbol_editor)
(symbol "+3.3V-power" (power) (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "#PWR" (at 0 -3.81 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "+3.3V-power" (at 0 3.556 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "+3.3V-power_0_1"
(polyline
(pts
(xy -0.762 1.27)
(xy 0 2.54)
)
(stroke (width 0) (type solid))
(fill (type none))
)
(polyline
(pts
(xy 0 0)
(xy 0 2.54)
)
(stroke (width 0) (type solid))
(fill (type none))
)
(polyline
(pts
(xy 0 2.54)
(xy 0.762 1.27)
)
(stroke (width 0) (type solid))
(fill (type none))
)
)
(symbol "+3.3V-power_1_1"
(pin power_in line (at 0 0 90) (length 0) hide
(name "+3V3" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "PROGRAMMATOR-kicad_Library" (pin_names (offset 1.016)) (in_bom yes) (on_board yes)
(property "Reference" "xp" (at -8.89 22.86 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "kicad_Library_PROGRAMMATOR" (at -10.16 5.08 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Connector_IDC:IDC-Header_2x05_P2.54mm_Vertical" (at -8.89 22.86 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (at -8.89 22.86 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "PROGRAMMATOR-kicad_Library_0_1"
(rectangle (start -17.78 20.32) (end 1.27 7.62)
(stroke (width 0) (type solid))
(fill (type background))
)
)
(symbol "PROGRAMMATOR-kicad_Library_1_1"
(pin passive line (at -20.32 19.05 0) (length 2.54)
(name "GND" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin power_out line (at 3.81 8.89 180) (length 2.54)
(name "+5V" (effects (font (size 1.27 1.27))))
(number "10" (effects (font (size 1.27 1.27))))
)
(pin power_out line (at 3.81 19.05 180) (length 2.54)
(name "+3V" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
(pin input line (at -20.32 16.51 0) (length 2.54)
(name "RESET" (effects (font (size 1.27 1.27))))
(number "3" (effects (font (size 1.27 1.27))))
)
(pin input line (at 3.81 16.51 180) (length 2.54)
(name "BOOT" (effects (font (size 1.27 1.27))))
(number "4" (effects (font (size 1.27 1.27))))
)
(pin input line (at -20.32 13.97 0) (length 2.54)
(name "RX" (effects (font (size 1.27 1.27))))
(number "5" (effects (font (size 1.27 1.27))))
)
(pin output line (at 3.81 13.97 180) (length 2.54)
(name "TX" (effects (font (size 1.27 1.27))))
(number "6" (effects (font (size 1.27 1.27))))
)
(pin input line (at -20.32 11.43 0) (length 2.54)
(name "SWDCLK" (effects (font (size 1.27 1.27))))
(number "7" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 3.81 11.43 180) (length 2.54)
(name "SWDDTA" (effects (font (size 1.27 1.27))))
(number "8" (effects (font (size 1.27 1.27))))
)
(pin passive line (at -20.32 8.89 0) (length 2.54)
(name "GND" (effects (font (size 1.27 1.27))))
(number "9" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "STM32F446RETx-MCU_ST_STM32F4" (in_bom yes) (on_board yes)
(property "Reference" "U" (at -15.24 41.91 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "MCU_ST_STM32F4_STM32F446RETx" (at 10.16 41.91 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Footprint" "Package_QFP:LQFP-64_10x10mm_P0.5mm" (at -15.24 -43.18 0)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
(property "Datasheet" "" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_fp_filters" "LQFP*10x10mm*P0.5mm*" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "STM32F446RETx-MCU_ST_STM32F4_0_1"
(rectangle (start -15.24 -43.18) (end 15.24 40.64)
(stroke (width 0.254) (type solid))
(fill (type background))
)
)
(symbol "STM32F446RETx-MCU_ST_STM32F4_1_1"
(pin power_in line (at -5.08 43.18 270) (length 2.54)
(name "VBAT" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -7.62 0) (length 2.54)
(name "PC2" (effects (font (size 1.27 1.27))))
(number "10" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -10.16 0) (length 2.54)
(name "PC3" (effects (font (size 1.27 1.27))))
(number "11" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 5.08 -45.72 90) (length 2.54)
(name "VSSA" (effects (font (size 1.27 1.27))))
(number "12" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 7.62 43.18 270) (length 2.54)
(name "VDDA" (effects (font (size 1.27 1.27))))
(number "13" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 38.1 180) (length 2.54)
(name "PA0" (effects (font (size 1.27 1.27))))
(number "14" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 35.56 180) (length 2.54)
(name "PA1" (effects (font (size 1.27 1.27))))
(number "15" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 33.02 180) (length 2.54)
(name "PA2" (effects (font (size 1.27 1.27))))
(number "16" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 30.48 180) (length 2.54)
(name "PA3" (effects (font (size 1.27 1.27))))
(number "17" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -5.08 -45.72 90) (length 2.54)
(name "VSS" (effects (font (size 1.27 1.27))))
(number "18" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -2.54 43.18 270) (length 2.54)
(name "VDD" (effects (font (size 1.27 1.27))))
(number "19" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -35.56 0) (length 2.54)
(name "PC13" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 27.94 180) (length 2.54)
(name "PA4" (effects (font (size 1.27 1.27))))
(number "20" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 25.4 180) (length 2.54)
(name "PA5" (effects (font (size 1.27 1.27))))
(number "21" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 22.86 180) (length 2.54)
(name "PA6" (effects (font (size 1.27 1.27))))
(number "22" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 20.32 180) (length 2.54)
(name "PA7" (effects (font (size 1.27 1.27))))
(number "23" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -12.7 0) (length 2.54)
(name "PC4" (effects (font (size 1.27 1.27))))
(number "24" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -15.24 0) (length 2.54)
(name "PC5" (effects (font (size 1.27 1.27))))
(number "25" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -5.08 180) (length 2.54)
(name "PB0" (effects (font (size 1.27 1.27))))
(number "26" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -7.62 180) (length 2.54)
(name "PB1" (effects (font (size 1.27 1.27))))
(number "27" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -10.16 180) (length 2.54)
(name "PB2" (effects (font (size 1.27 1.27))))
(number "28" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -30.48 180) (length 2.54)
(name "PB10" (effects (font (size 1.27 1.27))))
(number "29" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -38.1 0) (length 2.54)
(name "PC14" (effects (font (size 1.27 1.27))))
(number "3" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -17.78 27.94 0) (length 2.54)
(name "VCAP_1" (effects (font (size 1.27 1.27))))
(number "30" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -2.54 -45.72 90) (length 2.54)
(name "VSS" (effects (font (size 1.27 1.27))))
(number "31" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 0 43.18 270) (length 2.54)
(name "VDD" (effects (font (size 1.27 1.27))))
(number "32" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -33.02 180) (length 2.54)
(name "PB12" (effects (font (size 1.27 1.27))))
(number "33" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -35.56 180) (length 2.54)
(name "PB13" (effects (font (size 1.27 1.27))))
(number "34" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -38.1 180) (length 2.54)
(name "PB14" (effects (font (size 1.27 1.27))))
(number "35" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -40.64 180) (length 2.54)
(name "PB15" (effects (font (size 1.27 1.27))))
(number "36" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -17.78 0) (length 2.54)
(name "PC6" (effects (font (size 1.27 1.27))))
(number "37" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -20.32 0) (length 2.54)
(name "PC7" (effects (font (size 1.27 1.27))))
(number "38" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -22.86 0) (length 2.54)
(name "PC8" (effects (font (size 1.27 1.27))))
(number "39" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -40.64 0) (length 2.54)
(name "PC15" (effects (font (size 1.27 1.27))))
(number "4" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -25.4 0) (length 2.54)
(name "PC9" (effects (font (size 1.27 1.27))))
(number "40" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 17.78 180) (length 2.54)
(name "PA8" (effects (font (size 1.27 1.27))))
(number "41" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 15.24 180) (length 2.54)
(name "PA9" (effects (font (size 1.27 1.27))))
(number "42" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 12.7 180) (length 2.54)
(name "PA10" (effects (font (size 1.27 1.27))))
(number "43" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 10.16 180) (length 2.54)
(name "PA11" (effects (font (size 1.27 1.27))))
(number "44" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 7.62 180) (length 2.54)
(name "PA12" (effects (font (size 1.27 1.27))))
(number "45" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 5.08 180) (length 2.54)
(name "PA13" (effects (font (size 1.27 1.27))))
(number "46" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 0 -45.72 90) (length 2.54)
(name "VSS" (effects (font (size 1.27 1.27))))
(number "47" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 2.54 43.18 270) (length 2.54)
(name "VDD" (effects (font (size 1.27 1.27))))
(number "48" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 2.54 180) (length 2.54)
(name "PA14" (effects (font (size 1.27 1.27))))
(number "49" (effects (font (size 1.27 1.27))))
)
(pin input line (at -17.78 10.16 0) (length 2.54)
(name "PH0" (effects (font (size 1.27 1.27))))
(number "5" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 0 180) (length 2.54)
(name "PA15" (effects (font (size 1.27 1.27))))
(number "50" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -27.94 0) (length 2.54)
(name "PC10" (effects (font (size 1.27 1.27))))
(number "51" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -30.48 0) (length 2.54)
(name "PC11" (effects (font (size 1.27 1.27))))
(number "52" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -33.02 0) (length 2.54)
(name "PC12" (effects (font (size 1.27 1.27))))
(number "53" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 2.54 0) (length 2.54)
(name "PD2" (effects (font (size 1.27 1.27))))
(number "54" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -12.7 180) (length 2.54)
(name "PB3" (effects (font (size 1.27 1.27))))
(number "55" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -15.24 180) (length 2.54)
(name "PB4" (effects (font (size 1.27 1.27))))
(number "56" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -17.78 180) (length 2.54)
(name "PB5" (effects (font (size 1.27 1.27))))
(number "57" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -20.32 180) (length 2.54)
(name "PB6" (effects (font (size 1.27 1.27))))
(number "58" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -22.86 180) (length 2.54)
(name "PB7" (effects (font (size 1.27 1.27))))
(number "59" (effects (font (size 1.27 1.27))))
)
(pin input line (at -17.78 7.62 0) (length 2.54)
(name "PH1" (effects (font (size 1.27 1.27))))
(number "6" (effects (font (size 1.27 1.27))))
)
(pin input line (at -17.78 33.02 0) (length 2.54)
(name "BOOT0" (effects (font (size 1.27 1.27))))
(number "60" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -25.4 180) (length 2.54)
(name "PB8" (effects (font (size 1.27 1.27))))
(number "61" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 17.78 -27.94 180) (length 2.54)
(name "PB9" (effects (font (size 1.27 1.27))))
(number "62" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 2.54 -45.72 90) (length 2.54)
(name "VSS" (effects (font (size 1.27 1.27))))
(number "63" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 5.08 43.18 270) (length 2.54)
(name "VDD" (effects (font (size 1.27 1.27))))
(number "64" (effects (font (size 1.27 1.27))))
)
(pin input line (at -17.78 38.1 0) (length 2.54)
(name "NRST" (effects (font (size 1.27 1.27))))
(number "7" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -2.54 0) (length 2.54)
(name "PC0" (effects (font (size 1.27 1.27))))
(number "8" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at -17.78 -5.08 0) (length 2.54)
(name "PC1" (effects (font (size 1.27 1.27))))
(number "9" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "drv8313-Driver_Motor" (pin_names (offset 1.016)) (in_bom yes) (on_board yes)
(property "Reference" "U" (at -7.62 1.27 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "Driver_Motor_drv8313" (at 5.08 1.27 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (at -17.78 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (at -17.78 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "drv8313-Driver_Motor_0_1"
(rectangle (start -11.43 -1.27) (end 8.89 -39.37)
(stroke (width 0) (type solid))
(fill (type background))
)
)
(symbol "drv8313-Driver_Motor_1_1"
(pin input line (at -13.97 -3.81 0) (length 2.54)
(name "cpl" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -26.67 0) (length 2.54)
(name "pgnd3" (effects (font (size 1.27 1.27))))
(number "10" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -29.21 0) (length 2.54)
(name "vm" (effects (font (size 1.27 1.27))))
(number "11" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -31.75 0) (length 2.54)
(name "compp" (effects (font (size 1.27 1.27))))
(number "12" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -34.29 0) (length 2.54)
(name "compn" (effects (font (size 1.27 1.27))))
(number "13" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -13.97 -36.83 0) (length 2.54)
(name "gnd" (effects (font (size 1.27 1.27))))
(number "14" (effects (font (size 1.27 1.27))))
)
(pin power_out line (at 11.43 -36.83 180) (length 2.54)
(name "v3p3" (effects (font (size 1.27 1.27))))
(number "15" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -34.29 180) (length 2.54)
(name "nReset" (effects (font (size 1.27 1.27))))
(number "16" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -31.75 180) (length 2.54)
(name "nSleep" (effects (font (size 1.27 1.27))))
(number "17" (effects (font (size 1.27 1.27))))
)
(pin output line (at 11.43 -29.21 180) (length 2.54)
(name "nFault" (effects (font (size 1.27 1.27))))
(number "18" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -26.67 180) (length 2.54)
(name "nCompo" (effects (font (size 1.27 1.27))))
(number "19" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -6.35 0) (length 2.54)
(name "cph" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 11.43 -24.13 180) (length 2.54)
(name "gnd" (effects (font (size 1.27 1.27))))
(number "20" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -21.59 180) (length 2.54)
(name "nc" (effects (font (size 1.27 1.27))))
(number "21" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -19.05 180) (length 2.54)
(name "en3" (effects (font (size 1.27 1.27))))
(number "22" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -16.51 180) (length 2.54)
(name "in3" (effects (font (size 1.27 1.27))))
(number "23" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -13.97 180) (length 2.54)
(name "en2" (effects (font (size 1.27 1.27))))
(number "24" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -11.43 180) (length 2.54)
(name "in2" (effects (font (size 1.27 1.27))))
(number "25" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -8.89 180) (length 2.54)
(name "en1" (effects (font (size 1.27 1.27))))
(number "26" (effects (font (size 1.27 1.27))))
)
(pin input line (at 11.43 -6.35 180) (length 2.54)
(name "in1" (effects (font (size 1.27 1.27))))
(number "27" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 11.43 -3.81 180) (length 2.54)
(name "gnd" (effects (font (size 1.27 1.27))))
(number "28" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -8.89 0) (length 2.54)
(name "vcp" (effects (font (size 1.27 1.27))))
(number "3" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -11.43 0) (length 2.54)
(name "vm" (effects (font (size 1.27 1.27))))
(number "4" (effects (font (size 1.27 1.27))))
)
(pin output line (at -13.97 -13.97 0) (length 2.54)
(name "out1" (effects (font (size 1.27 1.27))))
(number "5" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -16.51 0) (length 2.54)
(name "pgnd1" (effects (font (size 1.27 1.27))))
(number "6" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -19.05 0) (length 2.54)
(name "pgnd2" (effects (font (size 1.27 1.27))))
(number "7" (effects (font (size 1.27 1.27))))
)
(pin output line (at -13.97 -21.59 0) (length 2.54)
(name "out2" (effects (font (size 1.27 1.27))))
(number "8" (effects (font (size 1.27 1.27))))
)
(pin output line (at -13.97 -24.13 0) (length 2.54)
(name "out3" (effects (font (size 1.27 1.27))))
(number "9" (effects (font (size 1.27 1.27))))
)
)
)
)

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,86 @@
{
"board": {
"active_layer": 36,
"active_layer_preset": "",
"auto_track_width": true,
"hidden_netclasses": [],
"hidden_nets": [],
"high_contrast_mode": 0,
"net_color_mode": 1,
"opacity": {
"images": 0.6,
"pads": 1.0,
"tracks": 1.0,
"vias": 1.0,
"zones": 0.6
},
"selection_filter": {
"dimensions": true,
"footprints": true,
"graphics": true,
"keepouts": true,
"lockedItems": false,
"otherItems": true,
"pads": true,
"text": true,
"tracks": true,
"vias": true,
"zones": true
},
"visible_items": [
0,
1,
2,
3,
4,
5,
6,
7,
8,
9,
10,
11,
12,
13,
14,
15,
16,
17,
18,
19,
20,
21,
22,
23,
24,
25,
26,
27,
28,
29,
30,
32,
33,
34,
35,
36,
39,
40
],
"visible_layers": "0001010_00000001",
"zone_display_mode": 0
},
"git": {
"repo_password": "",
"repo_type": "",
"repo_username": "",
"ssh_key": ""
},
"meta": {
"filename": "motor_controller_50mm.kicad_prl",
"version": 3
},
"project": {
"files": []
}
}

View file

@ -0,0 +1,971 @@
{
"board": {
"3dviewports": [],
"design_settings": {
"defaults": {
"apply_defaults_to_fp_fields": false,
"apply_defaults_to_fp_shapes": false,
"apply_defaults_to_fp_text": false,
"board_outline_line_width": 0.1,
"copper_line_width": 0.2,
"copper_text_italic": false,
"copper_text_size_h": 1.5,
"copper_text_size_v": 1.5,
"copper_text_thickness": 0.3,
"copper_text_upright": false,
"courtyard_line_width": 0.05,
"dimension_precision": 4,
"dimension_units": 3,
"dimensions": {
"arrow_length": 1270000,
"extension_offset": 500000,
"keep_text_aligned": true,
"suppress_zeroes": false,
"text_position": 0,
"units_format": 1
},
"fab_line_width": 0.1,
"fab_text_italic": false,
"fab_text_size_h": 1.0,
"fab_text_size_v": 1.0,
"fab_text_thickness": 0.15,
"fab_text_upright": false,
"other_line_width": 0.1,
"other_text_italic": false,
"other_text_size_h": 1.0,
"other_text_size_v": 1.0,
"other_text_thickness": 0.15,
"other_text_upright": false,
"pads": {
"drill": 0.0,
"height": 9.5,
"width": 2.4
},
"silk_line_width": 0.15,
"silk_text_italic": false,
"silk_text_size_h": 1.0,
"silk_text_size_v": 1.0,
"silk_text_thickness": 0.15,
"silk_text_upright": false,
"zones": {
"min_clearance": 0.4
}
},
"diff_pair_dimensions": [],
"drc_exclusions": [],
"meta": {
"filename": "board_design_settings.json",
"version": 2
},
"rule_severities": {
"annular_width": "error",
"clearance": "error",
"connection_width": "warning",
"copper_edge_clearance": "error",
"copper_sliver": "warning",
"courtyards_overlap": "error",
"diff_pair_gap_out_of_range": "error",
"diff_pair_uncoupled_length_too_long": "error",
"drill_out_of_range": "error",
"duplicate_footprints": "warning",
"extra_footprint": "warning",
"footprint": "error",
"footprint_symbol_mismatch": "warning",
"footprint_type_mismatch": "ignore",
"hole_clearance": "error",
"hole_near_hole": "error",
"holes_co_located": "warning",
"invalid_outline": "error",
"isolated_copper": "warning",
"item_on_disabled_layer": "error",
"items_not_allowed": "error",
"length_out_of_range": "error",
"lib_footprint_issues": "warning",
"lib_footprint_mismatch": "warning",
"malformed_courtyard": "error",
"microvia_drill_out_of_range": "error",
"missing_courtyard": "ignore",
"missing_footprint": "warning",
"net_conflict": "warning",
"npth_inside_courtyard": "ignore",
"padstack": "warning",
"pth_inside_courtyard": "ignore",
"shorting_items": "error",
"silk_edge_clearance": "warning",
"silk_over_copper": "warning",
"silk_overlap": "warning",
"skew_out_of_range": "error",
"solder_mask_bridge": "error",
"starved_thermal": "error",
"text_height": "warning",
"text_thickness": "warning",
"through_hole_pad_without_hole": "error",
"too_many_vias": "error",
"track_dangling": "warning",
"track_width": "error",
"tracks_crossing": "error",
"unconnected_items": "error",
"unresolved_variable": "error",
"via_dangling": "warning",
"zones_intersect": "error"
},
"rule_severitieslegacy_courtyards_overlap": true,
"rule_severitieslegacy_no_courtyard_defined": false,
"rules": {
"max_error": 0.005,
"min_clearance": 0.0,
"min_connection": 0.0,
"min_copper_edge_clearance": 0.05,
"min_hole_clearance": 0.15,
"min_hole_to_hole": 0.25,
"min_microvia_diameter": 0.2,
"min_microvia_drill": 0.1,
"min_resolved_spokes": 1,
"min_silk_clearance": 0.0,
"min_text_height": 0.6,
"min_text_thickness": 0.08,
"min_through_hole_diameter": 0.3,
"min_track_width": 0.15,
"min_via_annular_width": 0.1,
"min_via_diameter": 0.4,
"solder_mask_to_copper_clearance": 0.0,
"use_height_for_length_calcs": true
},
"teardrop_options": [
{
"td_onpadsmd": true,
"td_onroundshapesonly": false,
"td_ontrackend": false,
"td_onviapad": true
}
],
"teardrop_parameters": [
{
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0,
"td_height_ratio": 1.0,
"td_length_ratio": 0.5,
"td_maxheight": 2.0,
"td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_round_shape",
"td_width_to_size_filter_ratio": 0.9
},
{
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0,
"td_height_ratio": 1.0,
"td_length_ratio": 0.5,
"td_maxheight": 2.0,
"td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_rect_shape",
"td_width_to_size_filter_ratio": 0.9
},
{
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0,
"td_height_ratio": 1.0,
"td_length_ratio": 0.5,
"td_maxheight": 2.0,
"td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_track_end",
"td_width_to_size_filter_ratio": 0.9
}
],
"track_widths": [
0.0,
0.3,
0.4,
0.5,
1.0
],
"tuning_pattern_settings": {
"diff_pair_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 1.0
},
"diff_pair_skew_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 0.6
},
"single_track_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 0.6
}
},
"via_dimensions": [],
"zones_allow_external_fillets": false
},
"ipc2581": {
"dist": "",
"distpn": "",
"internal_id": "",
"mfg": "",
"mpn": ""
},
"layer_presets": [],
"viewports": []
},
"boards": [],
"cvpcb": {
"equivalence_files": []
},
"erc": {
"erc_exclusions": [],
"meta": {
"version": 0
},
"pin_map": [
[
0,
0,
0,
0,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
2,
0,
1,
0,
0,
1,
0,
2,
2,
2,
2
],
[
0,
0,
0,
0,
0,
0,
1,
0,
1,
0,
1,
2
],
[
0,
1,
0,
0,
0,
0,
1,
1,
2,
1,
1,
2
],
[
0,
0,
0,
0,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
2
],
[
1,
1,
1,
1,
1,
0,
1,
1,
1,
1,
1,
2
],
[
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
2,
1,
2,
0,
0,
1,
0,
2,
2,
2,
2
],
[
0,
2,
0,
1,
0,
0,
1,
0,
2,
0,
0,
2
],
[
0,
2,
1,
1,
0,
0,
1,
0,
2,
0,
0,
2
],
[
2,
2,
2,
2,
2,
2,
2,
2,
2,
2,
2,
2
]
],
"rule_severities": {
"bus_definition_conflict": "error",
"bus_entry_needed": "error",
"bus_to_bus_conflict": "error",
"bus_to_net_conflict": "error",
"conflicting_netclasses": "error",
"different_unit_footprint": "error",
"different_unit_net": "error",
"duplicate_reference": "error",
"duplicate_sheet_names": "error",
"endpoint_off_grid": "warning",
"extra_units": "error",
"global_label_dangling": "warning",
"hier_label_mismatch": "error",
"label_dangling": "error",
"lib_symbol_issues": "warning",
"missing_bidi_pin": "warning",
"missing_input_pin": "warning",
"missing_power_pin": "error",
"missing_unit": "warning",
"multiple_net_names": "warning",
"net_not_bus_member": "warning",
"no_connect_connected": "warning",
"no_connect_dangling": "warning",
"pin_not_connected": "error",
"pin_not_driven": "error",
"pin_to_pin": "error",
"power_pin_not_driven": "error",
"similar_labels": "warning",
"simulation_model_issue": "ignore",
"unannotated": "error",
"unit_value_mismatch": "error",
"unresolved_variable": "error",
"wire_dangling": "error"
}
},
"libraries": {
"pinned_footprint_libs": [],
"pinned_symbol_libs": []
},
"meta": {
"filename": "motor_controller_50mm.kicad_pro",
"version": 1
},
"net_settings": {
"classes": [
{
"bus_width": 12,
"clearance": 0.15,
"diff_pair_gap": 0.25,
"diff_pair_via_gap": 0.25,
"diff_pair_width": 0.25,
"line_style": 0,
"microvia_diameter": 0.3,
"microvia_drill": 0.1,
"name": "Default",
"pcb_color": "rgba(0, 0, 0, 0.000)",
"schematic_color": "rgba(0, 0, 0, 0.000)",
"track_width": 0.25,
"via_diameter": 0.8,
"via_drill": 0.4,
"wire_width": 6
}
],
"meta": {
"version": 3
},
"net_colors": null,
"netclass_assignments": null,
"netclass_patterns": [
{
"netclass": "Default",
"pattern": "+24V"
},
{
"netclass": "Default",
"pattern": "+3V3"
},
{
"netclass": "Default",
"pattern": "/A"
},
{
"netclass": "Default",
"pattern": "/B"
},
{
"netclass": "Default",
"pattern": "/BOOT"
},
{
"netclass": "Default",
"pattern": "/CANH"
},
{
"netclass": "Default",
"pattern": "/CANL"
},
{
"netclass": "Default",
"pattern": "/CAN_RX"
},
{
"netclass": "Default",
"pattern": "/CAN_TX"
},
{
"netclass": "Default",
"pattern": "/CLK1"
},
{
"netclass": "Default",
"pattern": "/CS1"
},
{
"netclass": "Default",
"pattern": "/DATA1"
},
{
"netclass": "Default",
"pattern": "/I"
},
{
"netclass": "Default",
"pattern": "/I2C_SCL"
},
{
"netclass": "Default",
"pattern": "/I2C_SDA"
},
{
"netclass": "Default",
"pattern": "/RESET"
},
{
"netclass": "Default",
"pattern": "/RX"
},
{
"netclass": "Default",
"pattern": "/SENSE1"
},
{
"netclass": "Default",
"pattern": "/SENSE2"
},
{
"netclass": "Default",
"pattern": "/SENSE3"
},
{
"netclass": "Default",
"pattern": "/SENSE4"
},
{
"netclass": "Default",
"pattern": "/SPI1_CS"
},
{
"netclass": "Default",
"pattern": "/SPI1_MISO"
},
{
"netclass": "Default",
"pattern": "/SPI1_MOSI"
},
{
"netclass": "Default",
"pattern": "/SPI1_SCK"
},
{
"netclass": "Default",
"pattern": "/SWD_CLK"
},
{
"netclass": "Default",
"pattern": "/SWD_DATA"
},
{
"netclass": "Default",
"pattern": "/TX"
},
{
"netclass": "Default",
"pattern": "/U"
},
{
"netclass": "Default",
"pattern": "/UL2"
},
{
"netclass": "Default",
"pattern": "/V"
},
{
"netclass": "Default",
"pattern": "/VL2"
},
{
"netclass": "Default",
"pattern": "/VLT_MTR"
},
{
"netclass": "Default",
"pattern": "/W"
},
{
"netclass": "Default",
"pattern": "/WL2"
},
{
"netclass": "Default",
"pattern": "/en1"
},
{
"netclass": "Default",
"pattern": "/en2"
},
{
"netclass": "Default",
"pattern": "/en3"
},
{
"netclass": "Default",
"pattern": "/led1"
},
{
"netclass": "Default",
"pattern": "/led2"
},
{
"netclass": "Default",
"pattern": "/nfault"
},
{
"netclass": "Default",
"pattern": "/nreset"
},
{
"netclass": "Default",
"pattern": "/nsleep"
},
{
"netclass": "Default",
"pattern": "GND"
},
{
"netclass": "Default",
"pattern": "Net-(C11-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(C20-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(C21-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(C3-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(C33-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(C33-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(C34-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(D1-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(D2-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(D3-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(DA1-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(DA1-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(DA1-Pad3)"
},
{
"netclass": "Default",
"pattern": "Net-(DA2-Pad10)"
},
{
"netclass": "Default",
"pattern": "Net-(DA2-Pad6)"
},
{
"netclass": "Default",
"pattern": "Net-(DA2-Pad7)"
},
{
"netclass": "Default",
"pattern": "Net-(DA3-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(DA4-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(DA5-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(DA6-Pad1)"
},
{
"netclass": "Default",
"pattern": "Net-(DA6-Pad12)"
},
{
"netclass": "Default",
"pattern": "Net-(DA6-Pad13)"
},
{
"netclass": "Default",
"pattern": "Net-(DA6-Pad14)"
},
{
"netclass": "Default",
"pattern": "Net-(DA6-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(DA6-Pad5)"
},
{
"netclass": "Default",
"pattern": "Net-(DD1-Pad5)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad10)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad11)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad17)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad2)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad23)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad24)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad28)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad3)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad4)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad5)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad50)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad51)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad52)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad53)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad55)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad56)"
},
{
"netclass": "Default",
"pattern": "Net-(DD2-Pad6)"
},
{
"netclass": "Default",
"pattern": "Net-(xp1-Pad10)"
}
]
},
"pcbnew": {
"last_paths": {
"gencad": "",
"idf": "",
"netlist": "",
"plot": "",
"pos_files": "",
"specctra_dsn": "",
"step": "../../../../motor_controller_50mm_new.step",
"svg": "",
"vrml": ""
},
"page_layout_descr_file": ""
},
"schematic": {
"annotate_start_num": 0,
"bom_fmt_presets": [],
"bom_fmt_settings": {
"field_delimiter": ",",
"keep_line_breaks": false,
"keep_tabs": false,
"name": "CSV",
"ref_delimiter": ",",
"ref_range_delimiter": "",
"string_delimiter": "\""
},
"bom_presets": [],
"bom_settings": {
"exclude_dnp": true,
"fields_ordered": [
{
"group_by": false,
"label": "Reference",
"name": "Reference",
"show": true
},
{
"group_by": true,
"label": "Value",
"name": "Value",
"show": true
},
{
"group_by": false,
"label": "Datasheet",
"name": "Datasheet",
"show": true
},
{
"group_by": false,
"label": "Footprint",
"name": "Footprint",
"show": true
},
{
"group_by": false,
"label": "Qty",
"name": "${QUANTITY}",
"show": false
},
{
"group_by": true,
"label": "DNP",
"name": "${DNP}",
"show": false
},
{
"group_by": false,
"label": "#",
"name": "${ITEM_NUMBER}",
"show": false
},
{
"group_by": false,
"label": "Description",
"name": "Description",
"show": true
},
{
"group_by": false,
"label": "manf#",
"name": "manf#",
"show": true
},
{
"group_by": false,
"label": "digikey#",
"name": "digikey#",
"show": false
}
],
"filter_string": "",
"group_symbols": true,
"name": "",
"sort_asc": true,
"sort_field": "Reference"
},
"connection_grid_size": 50.0,
"drawing": {
"dashed_lines_dash_length_ratio": 12.0,
"dashed_lines_gap_length_ratio": 3.0,
"default_line_thickness": 6.0,
"default_text_size": 50.0,
"field_names": [],
"intersheets_ref_own_page": false,
"intersheets_ref_prefix": "",
"intersheets_ref_short": false,
"intersheets_ref_show": false,
"intersheets_ref_suffix": "",
"junction_size_choice": 3,
"label_size_ratio": 0.25,
"operating_point_overlay_i_precision": 3,
"operating_point_overlay_i_range": "~A",
"operating_point_overlay_v_precision": 3,
"operating_point_overlay_v_range": "~V",
"overbar_offset_ratio": 1.23,
"pin_symbol_size": 0.0,
"text_offset_ratio": 0.08
},
"legacy_lib_dir": "",
"legacy_lib_list": [],
"meta": {
"version": 1
},
"net_format_name": "",
"page_layout_descr_file": "",
"plot_directory": "",
"spice_current_sheet_as_root": false,
"spice_external_command": "spice \"%I\"",
"spice_model_current_sheet_as_root": true,
"spice_save_all_currents": false,
"spice_save_all_dissipations": false,
"spice_save_all_voltages": false,
"subpart_first_id": 65,
"subpart_id_separator": 0
},
"sheets": [
[
"59b011af-aa16-42e7-b91d-08a229fb46fa",
"Root"
]
],
"text_variables": {
"rev": "0.4.2"
}
}

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,4 @@
(sym_lib_table
(version 7)
(lib (name "motor_controller_50mm-rescue")(type "KiCad")(uri "${KIPRJMOD}/motor_controller_50mm-rescue.kicad_sym")(options "")(descr ""))
)