start working on current sense

This commit is contained in:
2023-11-06 18:22:35 -05:00
parent d4948a7b3a
commit 1bec8bc5b7
15 changed files with 2878 additions and 3070 deletions

View File

@@ -0,0 +1,189 @@
#include "adc.h"
ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
DMA_HandleTypeDef hdma_adc1;
DMA_HandleTypeDef hdma_adc2;
uint32_t HAL_RCC_ADC12_CLK_ENABLED = 0;
void MX_ADC1_Init(void)
{
ADC_MultiModeTypeDef multimode = {0};
ADC_ChannelConfTypeDef sConfig = {0};
hadc1.Instance = ADC1;
hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV16;
hadc1.Init.Resolution = ADC_RESOLUTION_12B;
hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc1.Init.GainCompensation = 0;
hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc1.Init.LowPowerAutoWait = DISABLE;
hadc1.Init.ContinuousConvMode = DISABLE;
hadc1.Init.NbrOfConversion = 1;
hadc1.Init.DiscontinuousConvMode = DISABLE;
hadc1.Init.ExternalTrigConv = ADC_EXTERNALTRIG_T3_TRGO;
hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
hadc1.Init.DMAContinuousRequests = ENABLE;
hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
hadc1.Init.OversamplingMode = DISABLE;
if (HAL_ADC_Init(&hadc1) != HAL_OK)
{
SIMPLEFOC_DEBUG("HAL ADC1 Init fail.");
}
multimode.Mode = ADC_MODE_INDEPENDENT;
if (HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode) != HAL_OK)
{
SIMPLEFOC_DEBUG("HAL ADC1 Multimode configuration fail.");
}
sConfig.Channel = ADC_CHANNEL_VOPAMP1;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
{
Error_Handler();
}
}
void MX_ADC2_Init(void)
{
ADC_ChannelConfTypeDef sConfig = {0};
hadc2.Instance = ADC2;
hadc2.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV16;
hadc2.Init.Resolution = ADC_RESOLUTION_12B;
hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc2.Init.GainCompensation = 0;
hadc2.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc2.Init.LowPowerAutoWait = DISABLE;
hadc2.Init.ContinuousConvMode = DISABLE;
hadc2.Init.NbrOfConversion = 2;
hadc2.Init.DiscontinuousConvMode = DISABLE;
hadc2.Init.ExternalTrigConv = ADC_EXTERNALTRIG_T3_TRGO;
hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
hadc2.Init.DMAContinuousRequests = ENABLE;
hadc2.Init.Overrun = ADC_OVR_DATA_PRESERVED;
hadc2.Init.OversamplingMode = DISABLE;
if (HAL_ADC_Init(&hadc2) != HAL_OK)
{
Error_Handler();
}
sConfig.Channel = ADC_CHANNEL_VOPAMP2;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
{
Error_Handler();
}
sConfig.Channel = ADC_CHANNEL_VOPAMP3_ADC2;
sConfig.Rank = ADC_REGULAR_RANK_2;
if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
{
Error_Handler();
}
}
void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle)
{
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
if(adcHandle->Instance==ADC1)
{
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC12;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_SYSCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
HAL_RCC_ADC12_CLK_ENABLED++;
if(HAL_RCC_ADC12_CLK_ENABLED==1){
__HAL_RCC_ADC12_CLK_ENABLE();
}
/* ADC1 DMA Init */
/* ADC1 Init */
hdma_adc1.Instance = DMA1_Channel1;
hdma_adc1.Init.Request = DMA_REQUEST_ADC1;
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc1.Init.Mode = DMA_NORMAL;
hdma_adc1.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_adc1) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(adcHandle,DMA_Handle,hdma_adc1);
}
else if(adcHandle->Instance==ADC2)
{
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC12;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_SYSCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
HAL_RCC_ADC12_CLK_ENABLED++;
if(HAL_RCC_ADC12_CLK_ENABLED==1){
__HAL_RCC_ADC12_CLK_ENABLE();
}
/* ADC2 DMA Init */
/* ADC2 Init */
hdma_adc2.Instance = DMA1_Channel2;
hdma_adc2.Init.Request = DMA_REQUEST_ADC2;
hdma_adc2.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc2.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc2.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc2.Init.Mode = DMA_CIRCULAR;
hdma_adc2.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_adc2) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(adcHandle,DMA_Handle,hdma_adc2);
}
}
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle)
{
if(adcHandle->Instance==ADC1)
{
HAL_RCC_ADC12_CLK_ENABLED--;
if(HAL_RCC_ADC12_CLK_ENABLED==0){
__HAL_RCC_ADC12_CLK_DISABLE();
}
HAL_DMA_DeInit(adcHandle->DMA_Handle);
}
else if(adcHandle->Instance==ADC2)
{
HAL_RCC_ADC12_CLK_ENABLED--;
if(HAL_RCC_ADC12_CLK_ENABLED==0){
__HAL_RCC_ADC12_CLK_DISABLE();
}
HAL_DMA_DeInit(adcHandle->DMA_Handle);
}
}

View File

@@ -0,0 +1,25 @@
#ifndef __ADC_H__
#define __ADC_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32g4xx_hal.h"
#include "stm32g4xx_hal_adc.h"
extern ADC_HandleTypeDef hadc1;
extern ADC_HandleTypeDef hadc2;
extern DMA_HandleTypeDef hdma_adc1;
extern DMA_HandleTypeDef hdma_adc2;
void MX_ADC1_Init(void);
void MX_ADC2_Init(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,26 @@
#include "dma.h"
void MX_DMA_Init(void)
{
__HAL_RCC_DMAMUX1_CLK_ENABLE();
__HAL_RCC_DMA1_CLK_ENABLE();
HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn);
HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn);
}
extern "C" {
void DMA1_Channel1_IRQHandler(void)
{
HAL_DMA_IRQHandler(&hdma_adc1);
}
void DMA1_Channel2_IRQHandler(void)
{
HAL_DMA_IRQHandler(&hdma_adc2);
}
}

View File

@@ -0,0 +1,20 @@
#ifndef __DMA_H__
#define __DMA_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32g4xx_hal.h"
#include "stm32g4xx_hal_dma.h"
void MX_DMA_Init(void);
void DMA1_Channel1_IRQHandler(void);
void DMA2_Channel2_IRQHandler(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,77 @@
#include "opamp.h"
OPAMP_HandleTypeDef hopamp1;
OPAMP_HandleTypeDef hopamp2;
OPAMP_HandleTypeDef hopamp3;
void opamp_init(OPAMP_HandleTypeDef *hopamp, OPAMP_TypeDef *opamp)
{
hopamp1.Instance = opamp;
hopamp1.Init.PowerMode = OPAMP_POWERMODE_NORMALSPEED;
hopamp1.Init.Mode = OPAMP_PGA_MODE;
hopamp1.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO1;
hopamp1.Init.InternalOutput = ENABLE;
hopamp1.Init.TimerControlledMuxmode = OPAMP_TIMERCONTROLLEDMUXMODE_DISABLE;
hopamp1.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp1.Init.PgaGain = OPAMP_PGA_GAIN_16_OR_MINUS_15; // Adjust this to change the gains of the opamp.
hopamp1.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if (HAL_OPAMP_Init(&hopamp) != HAL_OK)
{
Error_Handler();
}
}
void configureOPAMPs(void)
{
opamp_init(&hopamp1, OPAMP1); // PA3
opamp_init(&hopamp2, OPAMP2); // PB0
opamp_init(&hopamp3, OPAMP3); // PA1
}
void HAL_OPAMP_MspInit(OPAMP_HandleTypeDef* opampHandle)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(opampHandle->Instance==OPAMP1)
{
__HAL_RCC_GPIOA_CLK_ENABLE();
GPIO_InitStruct.Pin = GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}
else if(opampHandle->Instance==OPAMP2)
{
__HAL_RCC_GPIOB_CLK_ENABLE();
GPIO_InitStruct.Pin = GPIO_PIN_0;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
else if(opampHandle->Instance==OPAMP3)
{
__HAL_RCC_GPIOA_CLK_ENABLE();
GPIO_InitStruct.Pin = GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}
}
void HAL_OPAMP_MspDeInit(OPAMP_HandleTypeDef* opampHandle)
{
if(opampHandle->Instance==OPAMP1)
{
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_3);
}
else if(opampHandle->Instance==OPAMP2)
{
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_0);
}
else if(opampHandle->Instance==OPAMP3)
{
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1);
}
}

View File

@@ -0,0 +1,22 @@
#ifndef __OPAMP_H__
#define __OPAMP_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32g4xx_hal.h"
#include "stm32g4xx_hal_opamp.h"
extern OPAMP_HandleTypeDef hopamp1;
extern OPAMP_HandleTypeDef hopamp2;
extern OPAMP_HandleTypeDef hopamp3;
void configureOPAMP(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,79 @@
#include "adc.h"
#include "opamp.h"
#include "dma.h"
#include "../stm32_mcu.h"
#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
#include "communication/SimpleFOCDebug.h"
volatile uint16_t adc1Result = {0};
volatile uint16_t adc2Result[2] = {0};
float adcSens = 3.3f * 1.440f / 4096.0f;
float _readVoltageInline(const uint8_t pin, const void *cs_params)
{
switch (pin)
{
case PA3:
return adc1Result * adcSens;
break;
case PB0:
return adc2Result[0] * adcSens;
break;
case PA1:
return adc2Result[1] * adcSens;
break;
default:
return 0.0f;
break;
}
}
void *_configureADCInline(const void *driver_params, const int pinA, const int pinB, const int pinC)
{
_UNUSED(driver_params);
HAL_Init();
MX_GPIO_Init();
MX_DMA_Init();
MX_ADC1_Init(&hadc1);
MX_ADC2_Init(&hadc2);
configureOPAMPs();
MX_DMA1_Init(&hadc1, &hdma_adc1, DMA1_Channel1, DMA_REQUEST_ADC1);
MX_DMA1_Init(&hadc2, &hdma_adc2, DMA1_Channel2, DMA_REQUEST_ADC2);
if (HAL_ADC_Start_DMA(&hadc1, (uint32_t *)adc1Result, 1) != HAL_OK)
{
SIMPLEFOC_DEBUG("DMA read init failed");
}
if (HAL_ADC_Start_DMA(&hadc2, (uint32_t *)adc2Result, 2) != HAL_OK)
{
SIMPLEFOC_DEBUG("DMA read init failed");
}
HAL_OPAMP_Start(&hopamp1);
HAL_OPAMP_Start(&hopamp2);
HAL_OPAMP_Start(&hopamp3);
Stm32CurrentSenseParams *params = new Stm32CurrentSenseParams{
.pins = {pinA, pinB, pinC},
.adc_voltage_conv = (_ADC_VOLTAGE) / (_ADC_RESOLUTION),
.timer_handle = (HardwareTimer *)(HardwareTimer_Handle[get_timer_index(TIM3)]->__this)};
return params;
}
void *_configureADCInline(const void *driver_params, const int pinA, const int pinB, const int pinC)
{
_UNUSED(driver_params);
_UNUSED(pinA);
_UNUSED(pinB);
_UNUSED(pinC);
SIMPLEFOC_DEBUG("Lemon-Pepper does not use lowside sensing. Use inline current sense instead.");
return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
}

View File

@@ -36,14 +36,23 @@ extern uint8_t RxData[8];
// simpleFOC things // simpleFOC things
#define POLEPAIRS 50 #define POLEPAIRS 50
#define RPHASE 3 #define RPHASE 3
#define MOTORKV 200 #define MOTORKV 40
#define ENC_PPR 0xFFFD // 65533 -> 65534 ppr (65535 cause overflow on 16 bit timer) #define ENC_PPR 16383 // max 16384
SPIClass spi1(ENC_COPI, ENC_CIPO, ENC_SCK); /**
* SPI clockdiv of 16 gives ~10.5MHz clock. May still be stable with lower divisor.
* The HW encoder is configured using PPR, which is then *4 for CPR (full 12384 gives overflow on 16 bit timer.)
*/
SPISettings myMT6835SPISettings(168000000/16, MT6835_BITORDER, SPI_MODE3); SPISettings myMT6835SPISettings(168000000/16, MT6835_BITORDER, SPI_MODE3);
MagneticSensorMT6835 sensor = MagneticSensorMT6835(ENC_CS, myMT6835SPISettings); MagneticSensorMT6835 sensor = MagneticSensorMT6835(ENC_CS, myMT6835SPISettings);
STM32HWEncoder enc = STM32HWEncoder(ENC_PPR, ENC_A, ENC_B, ENC_Z); STM32HWEncoder enc = STM32HWEncoder(ENC_PPR, ENC_A, ENC_B, ENC_Z);
/**
* The current sense amps have a gain of 90mA/V -> over 1.5A this is 135mA so we need gain of 24 to get full-scale.
* Actually we are limited to powers of 2 for gain. So it should be 16. This gives sensitivity of 1440mV/A.
* */
InlineCurrentSense currentsense = InlineCurrentSense(1440, ISENSE_U, ISENSE_V, ISENSE_W);
StepperDriver4PWM driver = StepperDriver4PWM(MOT_A1, MOT_A2, MOT_B1, MOT_B2); StepperDriver4PWM driver = StepperDriver4PWM(MOT_A1, MOT_A2, MOT_B1, MOT_B2);
StepperMotor motor = StepperMotor(POLEPAIRS, RPHASE, MOTORKV); StepperMotor motor = StepperMotor(POLEPAIRS, RPHASE, MOTORKV);
Commander commander = Commander(SerialUSB); Commander commander = Commander(SerialUSB);
@@ -53,6 +62,7 @@ uint16_t counter = 0;
// Prototypes // Prototypes
void configureFOC(void); void configureFOC(void);
void configureCAN(void); void configureCAN(void);
void calibrateEncoder(void);
void setup() void setup()
{ {
@@ -68,11 +78,16 @@ void setup()
digitalWrite(MOT_EN, HIGH); digitalWrite(MOT_EN, HIGH);
digitalWrite(CAL_EN, LOW); digitalWrite(CAL_EN, LOW);
// configureCAN(); configureCAN();
// configureEncoder(); configureFOC();
// configureFOC();
sensor.init(&spi1);
if(sensor.getABZResolution() != ENC_PPR){
digitalWrite(LED_FAULT, HIGH);
}
if(false){
calibrateEncoder();
}
// if(boardData.canID == 0x000) // if(boardData.canID == 0x000)
// { // {
// // If the can ID is not initialized, then we'll look for a free ID. // // If the can ID is not initialized, then we'll look for a free ID.
@@ -89,13 +104,15 @@ void setup()
void loop() void loop()
{ {
// motor.loopFOC(); motor.loopFOC();
// motor.move(); motor.move();
// commander.run(); commander.run();
sensor.update(); if(counter == 0){
delay(10); motor.target = -motor.target;
SerialUSB.printf("%#06x\n", sensor.readRawAngle21()); }
counter++;
#ifdef HAS_MONITOR #ifdef HAS_MONITOR
motor.monitor(); motor.monitor();
@@ -117,30 +134,34 @@ void configureFOC(void){
// Encoder initialization. // Encoder initialization.
// Ideally configuring the sensor over SPI then use STM32HWEncoder // Ideally configuring the sensor over SPI then use STM32HWEncoder
sensor.init(&spi1); sensor.init();
sensor.setABZResolution(ENC_PPR); sensor.setABZResolution(ENC_PPR);
enc.init(); enc.init();
// Driver initialization. // Driver initialization.
driver.pwm_frequency = 32000; driver.pwm_frequency = 32000;
driver.voltage_power_supply = 9; driver.voltage_power_supply = 12;
driver.voltage_limit = driver.voltage_power_supply/2; driver.voltage_limit = driver.voltage_power_supply/2;
driver.init(); driver.init();
// Motor PID parameters. // Motor PID parameters.
motor.PID_velocity.P = 0.2; motor.PID_velocity.P = 5;
motor.PID_velocity.I = 3; motor.PID_velocity.I = 24;
motor.PID_velocity.D = 0.002; motor.PID_velocity.D = 0.01;
motor.PID_velocity.output_ramp = 100; motor.PID_velocity.output_ramp = 750;
motor.LPF_velocity.Tf = 0.5; motor.PID_velocity.limit = 10;
motor.LPF_velocity.Tf = 4;
motor.P_angle.P = 600;
motor.P_angle.limit = 10000;
motor.LPF_angle.Tf = 0; // try to avoid motor.LPF_angle.Tf = 0; // try to avoid
// Motor initialization. // Motor initialization.
motor.voltage_sensor_align = 2; // motor.voltage_sensor_align = 2;
motor.current_limit = 0.35; motor.current_limit = 1;
motor.velocity_limit = 50; motor.velocity_limit = 500;
motor.controller = MotionControlType::velocity_openloop; motor.controller = MotionControlType::angle;
motor.foc_modulation = FOCModulationType::SpaceVectorPWM; motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// Monitor initialization // Monitor initialization
@@ -151,10 +172,15 @@ void configureFOC(void){
motor.monitor_downsample = 250; motor.monitor_downsample = 250;
#endif #endif
motor.linkSensor(&enc); motor.linkSensor(&sensor);
motor.linkDriver(&driver); motor.linkDriver(&driver);
motor.target = 10; // currentsense.linkDriver(&driver);
// currentsense.init();
// motor.linkCurrentSense(&currentsense);
motor.target = 3;
motor.zero_electric_angle = NOT_SET; motor.zero_electric_angle = NOT_SET;
motor.sensor_direction = Direction::UNKNOWN; motor.sensor_direction = Direction::UNKNOWN;
@@ -183,4 +209,33 @@ void configureCAN(void){
FDCAN_Start(0x000); FDCAN_Start(0x000);
} }
void calibrateEncoder(void){
uint16_t calTime = micros();
motor.target = 35; // roughly 2000rpm -> need to write 0x1 to Reg. AUTOCAL_FREQ
MT6835Options4 currentSettings = sensor.getOptions4();
currentSettings.autocal_freq = 0x1;
sensor.setOptions4(currentSettings);
while (calTime - micros() < 2000000)
{
motor.loopFOC();
motor.move();
if(calTime - micros() > 2000){
// after motor is spinning at constant speed, enable calibration.
digitalWrite(CAL_EN, HIGH);
}
}
digitalWrite(CAL_EN, LOW);
uint8_t calibrationState = sensor.getCalibrationStatus();
if(calibrationState != 0x3){
digitalWrite(LED_FAULT, HIGH);
}
}

View File

@@ -712,12 +712,12 @@
(property "LCSC Part" "C146412" (at 125.73 87.63 0) (property "LCSC Part" "C146412" (at 125.73 87.63 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(pin "1" (uuid d60ea7da-e95d-4c22-ad65-def1505307db)) (pin "1" (uuid d60ea7da-e95d-4c22-ad65-def1505307dd))
(pin "1" (uuid d60ea7da-e95d-4c22-ad65-def1505307db)) (pin "1" (uuid d60ea7da-e95d-4c22-ad65-def1505307dd))
(pin "11" (uuid e8d3a338-a773-49b8-a716-d1ab18131472)) (pin "11" (uuid e8d3a338-a773-49b8-a716-d1ab18131472))
(pin "12" (uuid 8c659ecd-ac7a-4f4a-9995-9dcc08bc6ebc)) (pin "12" (uuid 8c659ecd-ac7a-4f4a-9995-9dcc08bc6ebc))
(pin "2" (uuid e042e7b2-9853-43dd-9d84-0a27309e347c)) (pin "2" (uuid e042e7b2-9853-43dd-9d84-0a27309e347e))
(pin "2" (uuid e042e7b2-9853-43dd-9d84-0a27309e347c)) (pin "2" (uuid e042e7b2-9853-43dd-9d84-0a27309e347e))
(pin "6" (uuid 2c89c0c4-ec2f-42de-81b6-e62c8d188968)) (pin "6" (uuid 2c89c0c4-ec2f-42de-81b6-e62c8d188968))
(pin "10" (uuid 95506ff9-4ec7-44f1-b5f7-87c53697753f)) (pin "10" (uuid 95506ff9-4ec7-44f1-b5f7-87c53697753f))
(pin "5" (uuid d5cf600e-4c97-43db-818b-ea3248045403)) (pin "5" (uuid d5cf600e-4c97-43db-818b-ea3248045403))
@@ -776,12 +776,12 @@
(property "LCSC Part" "C146412" (at 125.73 158.75 0) (property "LCSC Part" "C146412" (at 125.73 158.75 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(pin "1" (uuid f3a4724f-c83e-4357-93f5-de2b64412a0c)) (pin "1" (uuid f3a4724f-c83e-4357-93f5-de2b64412a0e))
(pin "1" (uuid f3a4724f-c83e-4357-93f5-de2b64412a0c)) (pin "1" (uuid f3a4724f-c83e-4357-93f5-de2b64412a0e))
(pin "11" (uuid 381951b5-9e1d-46d9-9fdd-5023089bf34f)) (pin "11" (uuid 381951b5-9e1d-46d9-9fdd-5023089bf34f))
(pin "12" (uuid 4a0f3bdc-1b3f-4b5a-9fdd-ad98ac9347e8)) (pin "12" (uuid 4a0f3bdc-1b3f-4b5a-9fdd-ad98ac9347e8))
(pin "2" (uuid e061c3c4-4715-4c93-a856-a0881bf59bad)) (pin "2" (uuid e061c3c4-4715-4c93-a856-a0881bf59baf))
(pin "2" (uuid e061c3c4-4715-4c93-a856-a0881bf59bad)) (pin "2" (uuid e061c3c4-4715-4c93-a856-a0881bf59baf))
(pin "6" (uuid c4b7cfc6-3923-4e8e-beab-8edfebf00db1)) (pin "6" (uuid c4b7cfc6-3923-4e8e-beab-8edfebf00db1))
(pin "10" (uuid 2f7d9d6f-7117-437c-a6f9-ab265c02086b)) (pin "10" (uuid 2f7d9d6f-7117-437c-a6f9-ab265c02086b))
(pin "5" (uuid 040e7810-ff19-4cb2-8089-e98a109dca74)) (pin "5" (uuid 040e7810-ff19-4cb2-8089-e98a109dca74))
@@ -940,12 +940,12 @@
(property "LCSC Part" "C146412" (at 125.73 123.19 0) (property "LCSC Part" "C146412" (at 125.73 123.19 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(pin "1" (uuid ac305c0b-c868-41dc-8758-5dddab10c0b4)) (pin "1" (uuid ac305c0b-c868-41dc-8758-5dddab10c0b6))
(pin "1" (uuid ac305c0b-c868-41dc-8758-5dddab10c0b4)) (pin "1" (uuid ac305c0b-c868-41dc-8758-5dddab10c0b6))
(pin "11" (uuid 5f952846-310c-40d4-879c-8b224fb60661)) (pin "11" (uuid 5f952846-310c-40d4-879c-8b224fb60661))
(pin "12" (uuid 9720c386-328c-42a4-97c9-f29be92781fd)) (pin "12" (uuid 9720c386-328c-42a4-97c9-f29be92781fd))
(pin "2" (uuid 81d43ea9-5248-42eb-8446-126bd3fa7bc5)) (pin "2" (uuid 81d43ea9-5248-42eb-8446-126bd3fa7bc7))
(pin "2" (uuid 81d43ea9-5248-42eb-8446-126bd3fa7bc5)) (pin "2" (uuid 81d43ea9-5248-42eb-8446-126bd3fa7bc7))
(pin "6" (uuid 15056b44-bd76-49d3-97b1-8f239c766f7b)) (pin "6" (uuid 15056b44-bd76-49d3-97b1-8f239c766f7b))
(pin "10" (uuid 43fa4b5b-1368-473b-a20c-160035bf6d2e)) (pin "10" (uuid 43fa4b5b-1368-473b-a20c-160035bf6d2e))
(pin "5" (uuid 9f25a38a-708f-427f-b757-bac5c276de82)) (pin "5" (uuid 9f25a38a-708f-427f-b757-bac5c276de82))

File diff suppressed because it is too large Load Diff

View File

@@ -1,6 +1,6 @@
{ {
"board": { "board": {
"active_layer": 0, "active_layer": 31,
"active_layer_preset": "", "active_layer_preset": "",
"auto_track_width": true, "auto_track_width": true,
"hidden_netclasses": [], "hidden_netclasses": [],
@@ -21,7 +21,7 @@
"keepouts": true, "keepouts": true,
"lockedItems": true, "lockedItems": true,
"otherItems": true, "otherItems": true,
"pads": true, "pads": false,
"text": true, "text": true,
"tracks": true, "tracks": true,
"vias": true, "vias": true,
@@ -63,7 +63,7 @@
39, 39,
40 40
], ],
"visible_layers": "fffffff_ffffffff", "visible_layers": "fffffef_ffffffff",
"zone_display_mode": 0 "zone_display_mode": 0
}, },
"meta": { "meta": {

View File

@@ -1423,7 +1423,7 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 9975e605-ba9e-4e9c-9204-4cd27b0982ab) (uuid 9975e605-ba9e-4e9c-9204-4cd27b0982ab)
) )
(wire (pts (xy 127 90.17) (xy 116.84 90.17)) (wire (pts (xy 128.27 90.17) (xy 116.84 90.17))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 999afe51-81af-4de8-ad1c-b54fb6e08e3d) (uuid 999afe51-81af-4de8-ad1c-b54fb6e08e3d)
) )
@@ -1729,7 +1729,7 @@
(effects (font (size 1.27 1.27)) (justify left)) (effects (font (size 1.27 1.27)) (justify left))
(uuid a19c3557-9fdf-4507-a59d-8b25daa91599) (uuid a19c3557-9fdf-4507-a59d-8b25daa91599)
) )
(hierarchical_label "TIM3_CH1" (shape input) (at 73.66 115.57 180) (fields_autoplaced) (hierarchical_label "TIM3_CH1" (shape input) (at 73.66 118.11 180) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
(uuid abba505e-e6e4-43c1-976d-628b1593ec96) (uuid abba505e-e6e4-43c1-976d-628b1593ec96)
) )
@@ -1741,11 +1741,11 @@
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
(uuid b2e2e711-bf4e-4c2c-8542-d341b63162b1) (uuid b2e2e711-bf4e-4c2c-8542-d341b63162b1)
) )
(hierarchical_label "TIM3_ETR" (shape input) (at 73.66 120.65 180) (fields_autoplaced) (hierarchical_label "TIM3_ETR" (shape input) (at 73.66 115.57 180) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
(uuid b431fb32-a08c-4eb8-89f2-23b466b1f8bd) (uuid b431fb32-a08c-4eb8-89f2-23b466b1f8bd)
) )
(hierarchical_label "TIM3_CH2" (shape input) (at 73.66 118.11 180) (fields_autoplaced) (hierarchical_label "TIM3_CH2" (shape input) (at 73.66 120.65 180) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
(uuid d358859b-ec8e-4c3a-bf01-3644c8c83381) (uuid d358859b-ec8e-4c3a-bf01-3644c8c83381)
) )
@@ -1753,7 +1753,7 @@
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
(uuid f75268da-ac5b-49c4-973b-54d7afbaa945) (uuid f75268da-ac5b-49c4-973b-54d7afbaa945)
) )
(hierarchical_label "DIR" (shape input) (at 127 90.17 0) (fields_autoplaced) (hierarchical_label "DIR" (shape input) (at 128.27 90.17 0) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify left)) (effects (font (size 1.27 1.27)) (justify left))
(uuid f7b629f6-08f3-41ef-8c7d-8ac6dab2ecbf) (uuid f7b629f6-08f3-41ef-8c7d-8ac6dab2ecbf)
) )

View File

@@ -563,7 +563,7 @@
(junction (at 146.05 99.06) (diameter 0) (color 0 0 0 0) (junction (at 146.05 99.06) (diameter 0) (color 0 0 0 0)
(uuid 49e213cb-6f8a-45d7-92de-afa8696e3499) (uuid 49e213cb-6f8a-45d7-92de-afa8696e3499)
) )
(junction (at 114.3 74.93) (diameter 0) (color 0 0 0 0) (junction (at 113.03 74.93) (diameter 0) (color 0 0 0 0)
(uuid 4cf2e7f3-d96e-4b8b-a1b2-7507c3bae1a1) (uuid 4cf2e7f3-d96e-4b8b-a1b2-7507c3bae1a1)
) )
(junction (at 173.99 74.93) (diameter 0) (color 0 0 0 0) (junction (at 173.99 74.93) (diameter 0) (color 0 0 0 0)
@@ -606,7 +606,7 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 12b4d185-50bb-48aa-9540-0eb8590132d3) (uuid 12b4d185-50bb-48aa-9540-0eb8590132d3)
) )
(wire (pts (xy 114.3 74.93) (xy 114.3 91.44)) (wire (pts (xy 113.03 74.93) (xy 113.03 91.44))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 131dcf5d-e8c2-4a1c-b30d-f263034d8952) (uuid 131dcf5d-e8c2-4a1c-b30d-f263034d8952)
) )
@@ -666,11 +666,11 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 4f6e7932-fe2b-442c-b0a5-454b594665aa) (uuid 4f6e7932-fe2b-442c-b0a5-454b594665aa)
) )
(wire (pts (xy 114.3 96.52) (xy 114.3 99.06)) (wire (pts (xy 113.03 96.52) (xy 113.03 99.06))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 531f6e61-0184-4587-82ca-d6e30e36c203) (uuid 531f6e61-0184-4587-82ca-d6e30e36c203)
) )
(wire (pts (xy 114.3 74.93) (xy 123.19 74.93)) (wire (pts (xy 113.03 74.93) (xy 123.19 74.93))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 55eb581a-5f35-43df-b8a4-28768df07191) (uuid 55eb581a-5f35-43df-b8a4-28768df07191)
) )
@@ -678,7 +678,7 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 574524db-273d-4208-b55a-0d316d625a29) (uuid 574524db-273d-4208-b55a-0d316d625a29)
) )
(wire (pts (xy 114.3 99.06) (xy 123.19 99.06)) (wire (pts (xy 113.03 99.06) (xy 123.19 99.06))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 5c052775-0e24-45ed-96db-8d81123a8e55) (uuid 5c052775-0e24-45ed-96db-8d81123a8e55)
) )
@@ -738,7 +738,7 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid bb1a91e4-65b9-4787-9076-17770805c1f8) (uuid bb1a91e4-65b9-4787-9076-17770805c1f8)
) )
(wire (pts (xy 114.3 71.12) (xy 114.3 74.93)) (wire (pts (xy 113.03 71.12) (xy 113.03 74.93))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid d39136ce-e4bb-4d8b-8040-82d9cf6c1deb) (uuid d39136ce-e4bb-4d8b-8040-82d9cf6c1deb)
) )
@@ -767,8 +767,8 @@
(effects (font (size 1.27 1.27)) (justify left bottom)) (effects (font (size 1.27 1.27)) (justify left bottom))
(uuid 3ed50f4c-bb0e-492c-888f-523b07f8b5fa) (uuid 3ed50f4c-bb0e-492c-888f-523b07f8b5fa)
) )
(text "Ra = Rb(Vout/0.9 - 1)\n3.36V (closest to 3v3 with basic parts)" (text "For MAX15062AATA+T (C2846801): \nR501: 0R\nR502, R503: DNP\n\nFor MAX15062CATA+T (C1121853):\nR501: 200k\nR502, R503: 51k, 22k\n\nRa = Rb(Vout/0.9 - 1)\n3.36V (closest to 3v3 with basic parts)"
(at 195.58 87.63 0) (at 195.58 96.52 0)
(effects (font (size 1.27 1.27)) (justify left bottom)) (effects (font (size 1.27 1.27)) (justify left bottom))
(uuid 4d457700-0f26-4182-b9c8-e87ac9edf932) (uuid 4d457700-0f26-4182-b9c8-e87ac9edf932)
) )
@@ -777,19 +777,19 @@
(uuid 4d9f6cb8-0fea-4ab0-96c8-d8e869b904c3) (uuid 4d9f6cb8-0fea-4ab0-96c8-d8e869b904c3)
) )
(symbol (lib_id "matei:Vmot") (at 114.3 71.12 0) (unit 1) (symbol (lib_id "matei:Vmot") (at 113.03 71.12 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced) (in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 0f88b24d-bacd-40e7-a4b6-69f653212543) (uuid 0f88b24d-bacd-40e7-a4b6-69f653212543)
(property "Reference" "#PWR0501" (at 109.22 74.93 0) (property "Reference" "#PWR0501" (at 107.95 74.93 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(property "Value" "Vmot" (at 114.3 66.04 0) (property "Value" "Vmot" (at 113.03 66.04 0)
(effects (font (size 1.27 1.27))) (effects (font (size 1.27 1.27)))
) )
(property "Footprint" "" (at 114.3 71.12 0) (property "Footprint" "" (at 113.03 71.12 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(property "Datasheet" "" (at 114.3 71.12 0) (property "Datasheet" "" (at 113.03 71.12 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(pin "1" (uuid 64b5325f-b096-44d4-b26f-140153030d35)) (pin "1" (uuid 64b5325f-b096-44d4-b26f-140153030d35))
@@ -1204,22 +1204,22 @@
) )
) )
(symbol (lib_id "Device:C_Small") (at 114.3 93.98 0) (unit 1) (symbol (lib_id "Device:C_Small") (at 113.03 93.98 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (in_bom yes) (on_board yes) (dnp no)
(uuid c2e248dc-262a-4629-a710-625bec428a81) (uuid c2e248dc-262a-4629-a710-625bec428a81)
(property "Reference" "C501" (at 111.76 92.7163 0) (property "Reference" "C501" (at 110.49 92.7163 0)
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
) )
(property "Value" "10u" (at 111.76 95.2563 0) (property "Value" "10u" (at 110.49 95.2563 0)
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
) )
(property "Footprint" "Capacitor_SMD:C_0805_2012Metric" (at 114.3 93.98 0) (property "Footprint" "Capacitor_SMD:C_0805_2012Metric" (at 113.03 93.98 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(property "Datasheet" "~" (at 114.3 93.98 0) (property "Datasheet" "~" (at 113.03 93.98 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(property "LCSC Part" "C440198" (at 114.3 93.98 0) (property "LCSC Part" "C440198" (at 113.03 93.98 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
) )
(pin "1" (uuid db63675f-4a64-405c-903a-43db0df0c925)) (pin "1" (uuid db63675f-4a64-405c-903a-43db0df0c925))

View File

@@ -296,73 +296,6 @@
) )
) )
) )
(symbol "Device:D" (pin_numbers hide) (pin_names (offset 1.016) hide) (in_bom yes) (on_board yes)
(property "Reference" "D" (at 0 2.54 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "D" (at 0 -2.54 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)
)
(property "Sim.Device" "D" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Sim.Pins" "1=K 2=A" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_keywords" "diode" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "Diode" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_fp_filters" "TO-???* *_Diode_* *SingleDiode* D_*" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "D_0_1"
(polyline
(pts
(xy -1.27 1.27)
(xy -1.27 -1.27)
)
(stroke (width 0.254) (type default))
(fill (type none))
)
(polyline
(pts
(xy 1.27 0)
(xy -1.27 0)
)
(stroke (width 0) (type default))
(fill (type none))
)
(polyline
(pts
(xy 1.27 1.27)
(xy 1.27 -1.27)
(xy -1.27 0)
(xy 1.27 1.27)
)
(stroke (width 0.254) (type default))
(fill (type none))
)
)
(symbol "D_1_1"
(pin passive line (at -3.81 0 0) (length 2.54)
(name "K" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin passive line (at 3.81 0 180) (length 2.54)
(name "A" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "Power_Protection:SRV05-4" (pin_names (offset 0)) (in_bom yes) (on_board yes) (symbol "Power_Protection:SRV05-4" (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "U" (at -5.08 11.43 0) (property "Reference" "U" (at -5.08 11.43 0)
(effects (font (size 1.27 1.27)) (justify right)) (effects (font (size 1.27 1.27)) (justify right))
@@ -683,58 +616,6 @@
) )
) )
) )
(symbol "matei:Vmot" (power) (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "#PWR" (at -5.08 -3.81 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "Vmot" (at 0 3.81 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)
)
(property "ki_keywords" "global power" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "Power symbol creates a global label with name \"Vmot\"" (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "Vmot_0_1"
(polyline
(pts
(xy -0.762 1.27)
(xy 0 2.54)
)
(stroke (width 0) (type default))
(fill (type none))
)
(polyline
(pts
(xy 0 0)
(xy 0 2.54)
)
(stroke (width 0) (type default))
(fill (type none))
)
(polyline
(pts
(xy 0 2.54)
(xy 0.762 1.27)
)
(stroke (width 0) (type default))
(fill (type none))
)
)
(symbol "Vmot_1_1"
(pin power_in line (at 0 0 90) (length 0) hide
(name "Vmot" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "power:GND" (power) (pin_names (offset 0)) (in_bom yes) (on_board yes) (symbol "power:GND" (power) (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "#PWR" (at 0 -6.35 0) (property "Reference" "#PWR" (at 0 -6.35 0)
(effects (font (size 1.27 1.27)) hide) (effects (font (size 1.27 1.27)) hide)
@@ -783,9 +664,6 @@
(junction (at 182.88 115.57) (diameter 0) (color 0 0 0 0) (junction (at 182.88 115.57) (diameter 0) (color 0 0 0 0)
(uuid 7f829efe-2549-4b4f-90e8-0852a4a099b6) (uuid 7f829efe-2549-4b4f-90e8-0852a4a099b6)
) )
(junction (at 182.88 74.93) (diameter 0) (color 0 0 0 0)
(uuid 88593d01-2247-428d-90be-d1303e2afca7)
)
(junction (at 133.35 87.63) (diameter 0) (color 0 0 0 0) (junction (at 133.35 87.63) (diameter 0) (color 0 0 0 0)
(uuid 9aafd402-ac62-47f2-ae12-2053d8ddf9fb) (uuid 9aafd402-ac62-47f2-ae12-2053d8ddf9fb)
) )
@@ -819,11 +697,6 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 0a14d4da-021c-4d9e-9679-6c4310bab1e5) (uuid 0a14d4da-021c-4d9e-9679-6c4310bab1e5)
) )
(polyline (pts (xy 205.74 78.74) (xy 205.74 57.15))
(stroke (width 0) (type dash))
(uuid 113a1c01-3880-457c-b8d2-a322d976f3eb)
)
(wire (pts (xy 129.54 87.63) (xy 133.35 87.63)) (wire (pts (xy 129.54 87.63) (xy 133.35 87.63))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 189a4a91-86d9-4c15-b8a3-52fe3bc43652) (uuid 189a4a91-86d9-4c15-b8a3-52fe3bc43652)
@@ -844,11 +717,6 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 27844c04-3d11-4309-84f5-54db6ebdb4f4) (uuid 27844c04-3d11-4309-84f5-54db6ebdb4f4)
) )
(polyline (pts (xy 187.96 57.15) (xy 187.96 78.74))
(stroke (width 0) (type dash))
(uuid 28c3b3eb-96a9-4dd7-abd6-f07914b20eb2)
)
(wire (pts (xy 149.86 105.41) (xy 160.02 105.41)) (wire (pts (xy 149.86 105.41) (xy 160.02 105.41))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 2f8faf9e-0eca-4d3b-b618-2d2541be2cb8) (uuid 2f8faf9e-0eca-4d3b-b618-2d2541be2cb8)
@@ -873,18 +741,10 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 5ce767fc-dbe5-40e4-9e44-c72b35d2bd48) (uuid 5ce767fc-dbe5-40e4-9e44-c72b35d2bd48)
) )
(wire (pts (xy 182.88 74.93) (xy 193.04 74.93))
(stroke (width 0) (type default))
(uuid 7b0a80c6-a7c8-4760-8461-97ec7cd2522b)
)
(wire (pts (xy 129.54 80.01) (xy 135.89 80.01)) (wire (pts (xy 129.54 80.01) (xy 135.89 80.01))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 7e89535e-57a8-4efc-8386-a47a38a5c010) (uuid 7e89535e-57a8-4efc-8386-a47a38a5c010)
) )
(wire (pts (xy 200.66 74.93) (xy 210.82 74.93))
(stroke (width 0) (type default))
(uuid 7eaa406d-3ca7-4d29-9f00-240038370acb)
)
(wire (pts (xy 160.02 102.87) (xy 160.02 105.41)) (wire (pts (xy 160.02 102.87) (xy 160.02 105.41))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 8b4a695f-7d13-4eb2-9dcc-16c2356aaeaa) (uuid 8b4a695f-7d13-4eb2-9dcc-16c2356aaeaa)
@@ -905,19 +765,10 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 924ac973-8620-473f-a942-9d5f8ba6a69e) (uuid 924ac973-8620-473f-a942-9d5f8ba6a69e)
) )
(polyline (pts (xy 187.96 57.15) (xy 205.74 57.15))
(stroke (width 0) (type dash))
(uuid 934f6af3-25d2-4464-865c-3380099b47e3)
)
(wire (pts (xy 160.02 93.98) (xy 170.18 93.98)) (wire (pts (xy 160.02 93.98) (xy 170.18 93.98))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 940e3e0b-4c9a-42fb-8b5c-a42c8008ec1c) (uuid 940e3e0b-4c9a-42fb-8b5c-a42c8008ec1c)
) )
(wire (pts (xy 210.82 74.93) (xy 210.82 69.85))
(stroke (width 0) (type default))
(uuid 95a2635d-92c4-4fc9-8f40-af48ec2bb2e5)
)
(wire (pts (xy 160.02 93.98) (xy 160.02 97.79)) (wire (pts (xy 160.02 93.98) (xy 160.02 97.79))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid 9f0edadd-0571-4b2e-b4a0-84447677e15c) (uuid 9f0edadd-0571-4b2e-b4a0-84447677e15c)
@@ -942,11 +793,6 @@
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid bdc95b9b-cec6-4f4f-a442-91b4b1fcb098) (uuid bdc95b9b-cec6-4f4f-a442-91b4b1fcb098)
) )
(polyline (pts (xy 187.96 78.74) (xy 205.74 78.74))
(stroke (width 0) (type dash))
(uuid c6ecf75e-e0e5-47af-b010-cc57251b582b)
)
(wire (pts (xy 129.54 82.55) (xy 135.89 82.55)) (wire (pts (xy 129.54 82.55) (xy 135.89 82.55))
(stroke (width 0) (type default)) (stroke (width 0) (type default))
(uuid d5ebe916-192c-4adf-9cd5-109115062f48) (uuid d5ebe916-192c-4adf-9cd5-109115062f48)
@@ -980,11 +826,6 @@
(uuid f955368a-83b4-45d0-b05e-385531054e24) (uuid f955368a-83b4-45d0-b05e-385531054e24)
) )
(text "not sure if\ngood idea" (at 191.77 63.5 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
(uuid 094e3f22-7dfb-4ec5-9d75-4dad2b796bfb)
)
(label "USB_5V" (at 151.13 74.93 0) (fields_autoplaced) (label "USB_5V" (at 151.13 74.93 0) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify left bottom)) (effects (font (size 1.27 1.27)) (justify left bottom))
(uuid 3309461f-9ec9-4f09-8ce5-3188505d8775) (uuid 3309461f-9ec9-4f09-8ce5-3188505d8775)
@@ -1061,41 +902,6 @@
) )
) )
(symbol (lib_id "Device:D") (at 196.85 74.93 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 68b1a8c4-1258-4055-9cf5-0723ea413e16)
(property "Reference" "D201" (at 196.85 68.58 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "1N4148WS" (at 196.85 71.12 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Diode_SMD:D_SOD-323" (at 196.85 74.93 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (at 196.85 74.93 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Sim.Device" "D" (at 196.85 74.93 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Sim.Pins" "1=K 2=A" (at 196.85 74.93 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "LCSC Part" "C2128" (at 196.85 74.93 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid e555ab3b-eb30-4349-9c23-402619def6cc))
(pin "2" (uuid 1efac732-ac4b-4e69-b1bc-4ad87a05b9a8))
(instances
(project "lemon-pepper"
(path "/0306e2fa-4433-4288-91d9-65a3484207ad/3af4e77c-61b4-4c93-bd22-ce60f55b568c"
(reference "D201") (unit 1)
)
)
)
)
(symbol (lib_id "Connector:USB_C_Receptacle_USB2.0") (at 114.3 90.17 0) (unit 1) (symbol (lib_id "Connector:USB_C_Receptacle_USB2.0") (at 114.3 90.17 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced) (in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 7dadba43-7b05-4cb5-aa6a-7b6320a6123d) (uuid 7dadba43-7b05-4cb5-aa6a-7b6320a6123d)
@@ -1218,31 +1024,6 @@
) )
) )
(symbol (lib_id "matei:Vmot") (at 210.82 69.85 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid b9dba828-f517-41cc-8de1-0faef402be40)
(property "Reference" "#PWR0202" (at 205.74 73.66 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "Vmot" (at 210.82 64.77 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (at 210.82 69.85 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (at 210.82 69.85 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid f1d6e431-3a02-4643-9c81-2852037ee064))
(instances
(project "lemon-pepper"
(path "/0306e2fa-4433-4288-91d9-65a3484207ad/3af4e77c-61b4-4c93-bd22-ce60f55b568c"
(reference "#PWR0202") (unit 1)
)
)
)
)
(symbol (lib_id "Device:C_Small") (at 149.86 100.33 0) (unit 1) (symbol (lib_id "Device:C_Small") (at 149.86 100.33 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (in_bom yes) (on_board yes) (dnp no)
(uuid cb323398-3b6f-4a42-a847-71234d3d92ba) (uuid cb323398-3b6f-4a42-a847-71234d3d92ba)

View File

@@ -23,7 +23,8 @@ board_build.f_cpu = 168000000
framework = arduino framework = arduino
upload_protocol = stlink upload_protocol = stlink
debug_tool = stlink debug_tool = stlink
monitor_port = /dev/cu.usbmodem208A318D42531 ; monitor_port = /dev/cu.usbmodem208A318D42531
monitor_port = /dev/cu.usbmodem208B316742531
monitor_speed = 115200 monitor_speed = 115200
monitor_eol = LF monitor_eol = LF
build_flags = build_flags =
@@ -31,10 +32,12 @@ build_flags =
-D SIMPLEFOC_STM32_DEBUG -D SIMPLEFOC_STM32_DEBUG
-D PIO_FRAMEWORK_ARDUINO_ENABLE_CDC -D PIO_FRAMEWORK_ARDUINO_ENABLE_CDC
-D HAL_FDCAN_MODULE_ENABLED -D HAL_FDCAN_MODULE_ENABLED
-D HAL_OPAMP_MODULE_ENABLED
-D FDCAN_ALT1 -D FDCAN_ALT1
-D SN65HVD23x -D SN65HVD23x
-D ARDUINO_GENERIC_G431CBUX -D ARDUINO_GENERIC_G431CBUX
-D PCB_REV1 ; or PCB_REV2 -D PCB_REV1 ; or PCB_REV2
; -D HAS_MONITOR
lib_deps = lib_deps =
askuric/Simple FOC@^2.3.1 askuric/Simple FOC@^2.3.1