pcb: v4 wip

This commit is contained in:
Nils Schulte 2024-08-09 00:18:18 +02:00
parent 64a00c5dde
commit 1a7ea09816
13 changed files with 22229 additions and 14356 deletions

View File

@ -10,7 +10,7 @@
[env:nilsdriverv1]
# platform = espressif32
platform = https://github.com/cziter15/platform-espressif32.git
platform = https://github.com/cziter15/platform-espressif32.git#68ad40f6df654fe4b8d0a50982b810df5b49b677
#platform = https://github.com/tasmota/platform-espressif32/releases/download/2023.10.10/platform-espressif32.zip
# board = adafruit_feather_esp32s3
board = lolin_s3_mini
@ -31,5 +31,6 @@ lib_deps =
; https://github.com/Tinyu-Zhao/INA3221.git
build_flags = -DRADIOLIB_EEPROM_UNSUPPORTED
; -DARDUINO_USB_MODE
;-DSIMPLEFOC_ESP32_USELEDC

View File

@ -1,6 +1,11 @@
#ifndef _DRV8323S_H
#define _DRV8323S_H
#include <Arduino.h>
#include <SPI.h>
#include <cstdint>
#include <drivers/BLDCDriver3PWM.h>
enum {
DRV8323S_FAULT_STATUS1_REG = 0x00,
DRV8323S_FAULT_STATUS2_REG = 0x01,
@ -87,4 +92,176 @@ enum /* 0x06 */ {
DRV8323S_CSA_CONTROL_SEN_LVL_MASK = 0b11 << 6, /* Sense OCP = 0.25V*(1+x)*/
};
enum drv8323s_ocp_mode_e {
DRV8323S_OCP_MODE_LATCHED = 0b00 << 6, // Overcurrent causes a latched fault
DRV8323S_OCP_MODE_RETRY =
0b01 << 6, // Overcurrent causes an automatic retrying fault
DRV8323S_OCP_MODE_REPORT_ONLY =
0b10 << 6, // Overcurrent is report only but no action is taken
DRV8323S_OCP_MODE_IGNORE =
0b11 << 6, // Overcurrent is not reported and no action is take};
};
enum drv8323s_pwm_mode_e {
DRV8323S_PWM_MODE_6PWM = 0b00 << 5,
DRV8323S_PWM_MODE_3PWM = 0b01 << 5,
DRV8323S_PWM_MODE_1PWM = 0b10 << 5,
DRV8323S_PWM_MODE_INDEPENDENT_PWM = 0b11 << 5,
};
enum drv8323s_sen_lvl_e {
DRV8323S_SEN_LVL_0_25V = 0b00 << 0,
DRV8323S_SEN_LVL_0_5V = 0b01 << 0,
DRV8323S_SEN_LVL_0_75V = 0b10 << 0,
DRV8323S_SEN_LVL_1V = 0b11 << 0,
};
enum drv8323s_lock_sequence_e {
DRV8323S_LOCK = 0b011 << 8,
DRV8323S_UNLOCK = 0b110 << 8,
};
enum drv8323s_idrive_shift_e {
DRV8323S_IDRIVEP = 4,
DRV8323S_IDRIVEN = 0,
};
unsigned int drv8323s_idrivep_mA_map[] = {
10, 30, 60, 80, 120, 140, 170, 190, 260, 330, 370, 440, 570, 680, 820, 1000,
};
unsigned int drv8323s_idriven_mA_map[] = {
20, 60, 120, 160, 240, 280, 340, 380,
520, 660, 740, 880, 1140, 1360, 1640, 2000,
};
struct drv8323s_foc_driver {
SPIClass *spi;
int CSn, en;
BLDCDriver3PWM *focdriver;
};
uint16_t drv8323s_read_spi(struct drv8323s_foc_driver *dev, uint8_t addr,
uint16_t *result) {
digitalWrite(dev->CSn, 0);
dev->spi->beginTransaction(SPISettings(500000, MSBFIRST, SPI_MODE1));
uint16_t data = ((uint16_t)(1 << 15)) | ((((uint16_t)addr)) << 11);
*result = dev->spi->transfer16(data);
// *result = data;
dev->spi->endTransaction();
digitalWrite(dev->CSn, 1);
// Serial.print("SPI Read Result: ");
// Serial.print(data, HEX);
// Serial.print(" -> ");
// Serial.println(result, HEX);
return 0;
}
uint16_t drv8323s_write_spi(struct drv8323s_foc_driver *dev, uint8_t addr,
uint16_t value, uint16_t *result) {
digitalWrite(dev->CSn, 0);
dev->spi->beginTransaction(SPISettings(500000, MSBFIRST, SPI_MODE1));
uint16_t data = ((addr & 0b1111) << 11) | (value & 0b1111111111);
*result = dev->spi->transfer16(data);
dev->spi->endTransaction();
digitalWrite(dev->CSn, 1);
// Serial.print("SPI Write Result: ");
// Serial.print(data, HEX);
// Serial.print(" -> ");
// Serial.println(result, HEX);
return 0;
}
void drv8323s_lock_spi(struct drv8323s_foc_driver *dev,
bool lock) {
uint16_t result = 0;
drv8323s_read_spi(dev, DRV8323S_GATE_DRIVE_HS_REG, &result);
result &= ~DRV8323S_GATE_DRIVE_HS_LOCK_MASK;
result |= (lock?DRV8323S_LOCK:DRV8323S_UNLOCK) & DRV8323S_GATE_DRIVE_HS_LOCK_MASK;
drv8323s_write_spi(dev, DRV8323S_GATE_DRIVE_HS_REG, result, &result);
};
void drv8323s_set_PWM_mode(struct drv8323s_foc_driver *dev,
enum drv8323s_pwm_mode_e mode) {
uint16_t result = 0;
drv8323s_read_spi(dev, DRV8323S_DRIVER_CONTROL_REG, &result);
result &= ~DRV8323S_DRIVER_CONTROL_PWM_MODE_MASK;
result |= mode & DRV8323S_DRIVER_CONTROL_PWM_MODE_MASK;
drv8323s_write_spi(dev, DRV8323S_DRIVER_CONTROL_REG, result, &result);
}
void drv8323s_set_OCP_mode(struct drv8323s_foc_driver *dev,
enum drv8323s_ocp_mode_e mode) {
uint16_t result = 0;
drv8323s_read_spi(dev, DRV8323S_OCP_CONTROL_REG, &result);
result &= ~DRV8323S_OCP_CONTROL_OCP_MODE_MASK;
result |= mode & DRV8323S_OCP_CONTROL_OCP_MODE_MASK;
drv8323s_write_spi(dev, DRV8323S_OCP_CONTROL_REG, result, &result);
}
void drv8323s_set_sen_lvl(struct drv8323s_foc_driver *dev,
enum drv8323s_sen_lvl_e level) {
uint16_t result = 0;
drv8323s_read_spi(dev, DRV8323S_CSA_CONTROL_REG, &result);
result &= ~DRV8323S_CSA_CONTROL_SEN_LVL_MASK;
result |= level & DRV8323S_CSA_CONTROL_SEN_LVL_MASK;
drv8323s_write_spi(dev, DRV8323S_CSA_CONTROL_REG, result, &result);
}
void drv8323s_init(struct drv8323s_foc_driver *dev, int phA, int phB, int phC,
int CSn, int en, SPIClass *spi) {
dev->CSn = CSn;
dev->spi = spi;
dev->en = en;
pinMode(dev->CSn, OUTPUT);
pinMode(dev->en, OUTPUT);
digitalWrite(dev->en, 1);
delay(1);
drv8323s_lock_spi(dev, false);
delay(1);
drv8323s_set_PWM_mode(dev, DRV8323S_PWM_MODE_3PWM);
delay(1);
drv8323s_set_OCP_mode(dev, DRV8323S_OCP_MODE_LATCHED);
delay(1);
drv8323s_set_sen_lvl(dev, DRV8323S_SEN_LVL_0_25V);
delay(1);
drv8323s_lock_spi(dev, true);
dev->focdriver = new BLDCDriver3PWM(phA, phB, phC);
dev->focdriver->init();
/* Set 3PWM Mode */
}
void drv8323s_set_idrive(struct drv8323s_foc_driver *dev, int positive_i,
int negative_i, bool high_side_fet) {
uint16_t reg_value = 0x0; // TODO get reg
uint16_t reg =
high_side_fet ? DRV8323S_GATE_DRIVE_HS_REG : DRV8323S_GATE_DRIVE_LS_REG;
drv8323s_read_spi(dev, reg, &reg_value);
if (high_side_fet) {
reg_value &= ~DRV8323S_GATE_DRIVE_HS_IDRIVEP_HS_MASK;
reg_value &= ~DRV8323S_GATE_DRIVE_HS_IDRIVEN_HS_MASK;
} else {
reg_value &= ~DRV8323S_GATE_DRIVE_LS_IDRIVEP_LS_MASK;
reg_value &= ~DRV8323S_GATE_DRIVE_LS_IDRIVEN_LS_MASK;
}
int i;
for (i = 0;
i < sizeof drv8323s_idrivep_mA_map / sizeof(drv8323s_idrivep_mA_map[0]);
i += 1) {
if (drv8323s_idrivep_mA_map[i] > positive_i)
break;
}
reg_value |= i << DRV8323S_IDRIVEP;
for (i = 0;
i < sizeof drv8323s_idriven_mA_map / sizeof(drv8323s_idriven_mA_map[0]);
i += 1) {
if (drv8323s_idriven_mA_map[i] > negative_i)
break;
}
reg_value |= i << DRV8323S_IDRIVEN;
uint16_t result;
drv8323s_write_spi(dev, reg, reg_value, &result);
// TODO SPI call
}
#endif /* _DRV8323S_H */

View File

@ -9,12 +9,15 @@
// #include <INA3221.h>
#include "SimpleFOCDrivers.h"
#include "comms/streams/BinaryIO.h"
#include "encoders/esp32hwencoder/ESP32HWEncoder.h"
#include "encoders/as5600/MagneticSensorAS5600.h"
#include "encoders/calibrated/CalibratedSensor.h"
#include "DRV8323S.hpp"
#include "esp32-hal-adc.h"
#include "esp32-hal-gpio.h"
#include "motors/HybridStepperMotor/HybridStepperMotor.h"
#include "drivers/drv8316/drv8316.h"
#include <cmath>
// #include "encoders/sc60228/MagneticSensorSC60228.h"
@ -33,6 +36,13 @@
#define DRVEN 15
#define TERMISTOR_PCB 3
#define TERMISTOR_EXT 9
#define TEMP(v0, b, rt, r1, vdd) \
((1.0 / \
((1.0 / 298.15) + ((1.0 / b) * log((v0 * r1) / (rt * (vdd - v0)))))) - \
273.15)
#define temp_pcb \
(TEMP(analogRead(TERMISTOR_PCB) * 3.3 / 4096.0, 3435.0, 10000.0, 10000.0, \
3.3))
#define SOA 1
#define SOB 2
@ -41,6 +51,7 @@
#define INHA 14
#define INHB 13
#define INHC 12
#define INLABC 46
#define CAN_TX 6
#define CAN_RX 7
@ -50,7 +61,13 @@
#define SPI_CLK 47
#define SPI_DRV_SC 21
// #define MOTOR
#define LED_PIN 16
#define VSENSE_PIN 5
#define CAL_PIN 17
#define vdrive_read (analogRead(VSENSE_PIN) * 20.08f / 845)
//* 20.8f/ 21033.75)
#define MOTOR
#define SSIF_USBSERIAL
#define FW_NO_WATCHDOG
@ -67,13 +84,17 @@
const int voltage_lpf = 50;
// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
ESP32HWEncoder encoder =
ESP32HWEncoder(ENC_A, ENC_B, 2048 / 2); // The Index pin can be omitted
// ESP32HWEncoder encoder =
// ESP32HWEncoder(ENC_A, ENC_B, 2048 / 4); // The Index pin can be omitted
// CalibratedSensor encoder_calibrated = CalibratedSensor(encoder);
MagneticSensorAS5600 encoder = MagneticSensorAS5600(0x36);
#ifdef MOTOR
BLDCMotor motor = BLDCMotor(11); // 24N22P
// HybridStepperMotor motor = HybridStepperMotor(50, 3.7, 10, 4.5 / 1000);
DRV8316Driver3PWM driver = DRV8316Driver3PWM(INHA, INHB, INHC, SPI_DRV_SC);
struct drv8323s_foc_driver drv8323s;
// BLDCMotor motor = BLDCMotor(100); // 24N22P
HybridStepperMotor motor = HybridStepperMotor(50);//, 3.7, 10, 4.5 / 1000);
// DRV8316Driver3PWM driver = DRV8316Driver3PWM(INHA, INHB, INHC, SPI_DRV_SC);
// BLDCDriver3PWM driver = BLDCDriver3PWM(INHA,INHB,INHC);
#endif
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
@ -108,6 +129,7 @@ void write_i2c(uint8_t addr, uint8_t reg_lsb, uint8_t val) {
return;
}
}
void write_dual_i2c(uint8_t addr, uint8_t reg_lsb, uint8_t val1, uint8_t val2) {
Wire.beginTransmission(addr);
uint8_t data[] = {reg_lsb, val1, val2};
@ -151,10 +173,17 @@ void comm_task(void *parameter) {
}
void setup() {
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, 1); // enable
delay(1000);
digitalWrite(LED_PIN, 0); // enable
mutex = xSemaphoreCreateMutex();
#ifdef SSIF_USBSERIAL
SSYNCIF.begin();
USB.begin();
SSYNCIF.setDebugOutput(
true); // sends all log_e(), log_i() messages to USB HW CDC
SSYNCIF.setTxTimeoutMs(0);
#else
SSYNCIF.begin(460800, SERIAL_8N1, 44, 43);
#endif
@ -162,35 +191,55 @@ void setup() {
// SSYNCIF.print(__cplusplus);
// Wire.setTimeOut(10);
Wire.begin(I2C_SDA, I2C_SCL, 400000);
Wire.begin(I2C_SDA, I2C_SCL, 1000000);
// pinMode(DRVOFF, OUTPUT);
// digitalWrite(DRVOFF, 0); // enable
// pinMode(INLA, OUTPUT);
// digitalWrite(INLA, 1); // enable
// pinMode(INLB, OUTPUT);
// digitalWrite(INLB, 1); // enable
// pinMode(INLC, OUTPUT);
// digitalWrite(INLC, 1); // enable
pinMode(SPI_DRV_SC, OUTPUT);
pinMode(INHA, OUTPUT);
// digitalWrite(INHA, 0); // enable
pinMode(INHB, OUTPUT);
// digitalWrite(INHB, 0); // enable
pinMode(INHC, OUTPUT);
// digitalWrite(INHC, 0); // enable
pinMode(INLABC, OUTPUT);
digitalWrite(INLABC, 0); // enable
pinMode(CAL_PIN, OUTPUT);
digitalWrite(CAL_PIN, 0); // enable
// write_i2c(0x36,0x07, 0b00000011);
write_i2c(0x36, 0x09, 0xFF);
encoder.init(&Wire);
encoder.init();
#ifdef MOTOR
driver.voltage_power_supply = 15;
SimpleFOCDebug::enable(&SSYNCIF);
// driver.voltage_power_supply = 15;
pinMode(SPI_MISO, INPUT_PULLUP);
SPI.begin(SPI_CLK, SPI_MISO, SPI_MOSI, SPI_DRV_SC);
driver.init(&SPI);
status();
motor.linkDriver(&driver);
// motor.linkSensor(&encoder);
drv8323s_init(&drv8323s, INHA, INHB, INHC, SPI_DRV_SC, DRVEN, &SPI);
digitalWrite(INLABC, 1); // enable
// driver.init(&SPI);
// status();
motor.linkDriver(drv8323s.focdriver);
motor.linkSensor(&encoder);
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor.voltage_sensor_align = 5;
motor.voltage_limit = 6;
motor.controller = MotionControlType::velocity_openloop;
motor.voltage_sensor_align = 4;
motor.voltage_limit = 7;
// motor.controller = MotionControlType::velocity_openloop;
motor.controller = MotionControlType::torque;
motor.torque_controller = TorqueControlType::voltage;
drv8323s.focdriver->voltage_power_supply = 12;
motor.init();
// motor.initFOC();
// // set voltage to run calibration
// encoder_calibrated.voltage_calibration = 3;
// // Running calibration
// encoder_calibrated.calibrate(motor);
// //Serial.println("Calibrating Sensor Done.");
// // Linking sensor to motor object
// motor.linkSensor(&encoder_calibrated);
motor.initFOC();
// sensor.init(&SPI);
// motors[i].linkSensor(&sensors[i]);
@ -308,13 +357,67 @@ void setup() {
void loop() {
#ifdef MOTOR
// motor.loopFOC();
motor.loopFOC();
// motor.move(3);
motor.move(3);
#endif
#else
encoder.update(); // optional: Update manually if not using loopfoc()
SSYNCIF.println(encoder.getAngle());
delay(100);
#endif
static float angle = 0;
static float old_angle = 0;
angle = encoder.getAngle();
// SSYNCIF.print(angle * 180.0 / 3.1415);
#ifdef MOTOR
// SSYNCIF.print(" ");
// uint16_t result = 0;
// SSYNCIF.print(" ");
// result = 0;
// delay(1);
// drv8323s_read_spi(&drv8323s, 0x01, &result);
// SSYNCIF.print(result, HEX);
// SSYNCIF.print(" ");
// result = 0;
// delay(1);
// drv8323s_read_spi(&drv8323s, 0x02, &result);
// SSYNCIF.print(result, HEX);
// result = 0;
// SSYNCIF.print(" ");
// drv8323s_read_spi(&drv8323s, 0x03, &result);
// SSYNCIF.print(result, HEX);
// SSYNCIF.print(" ");
// result = 0;
// delay(1);
// drv8323s_read_spi(&drv8323s, 0x04, &result);
// SSYNCIF.print(result, HEX);
// SSYNCIF.print(" ");
// result = 0;
// delay(1);
// drv8323s_read_spi(&drv8323s, 0x05, &result);
// SSYNCIF.print(result, HEX);
// SSYNCIF.print(" ");
// result = 0;
// delay(1);
// drv8323s_read_spi(&drv8323s, 0x06, &result);
// SSYNCIF.print(result, HEX);
#endif
// SSYNCIF.print(" ");
// SSYNCIF.print(analogRead(TERMISTOR_PCB));
// SSYNCIF.print(" ");
// SSYNCIF.print(analogRead(SOA));
// SSYNCIF.print(" ");
// SSYNCIF.print(analogRead(SOB));
// SSYNCIF.print(" ");
// SSYNCIF.print(analogRead(SOC));
// SSYNCIF.print(" ");
static float t = temp_pcb;
t = t * 0.95 + 0.05 * temp_pcb;
// SSYNCIF.print(t);
// SSYNCIF.print(" ");
// SSYNCIF.println(vdrive_read);
// analogWrite(INHA, 255/3);
// analogWrite(INHB, 255/2);
// analogWrite(INHC, 255*2/3);
// static int i = 0;
// if (i++ % 100 == 0)
// status();

View File

@ -1,4 +1,4 @@
23717734582233081
24074546142079
Audio_Module
Reverb_BTDR-1H
Digital Reverberation Unit, http://www.belton.co.kr/inc/downfile.php?seq=17&file=pdf (footprint from http://www.uk-electronic.de/PDF/BTDR-1.pdf)
@ -57581,6 +57581,13 @@ heatsink
0
0
0
ICM-42670-P
LGA-14_2.5x3x0.76mm
0
14
14
Inductor_SMD
L_6.3x6.3_H3
Choke, SMD, 6.3x6.3mm 3mm height
@ -68235,307 +68242,6 @@ DIL DIP PDIP 2.54mm 7.62mm 300mil
0
4
4
PCM_Espressif
ESP32-C3-DevKitC-02
0
30
30
PCM_Espressif
ESP32-C3-DevKitM-1
0
30
30
PCM_Espressif
ESP32-C3-MINI-1
ESP32-C3-MINI-1: https://www.espressif.com/sites/default/files/documentation/esp32-c3-mini-1_datasheet_en.pdf
ESP32-C3
0
61
53
PCM_Espressif
ESP32-C3-MINI-1U
ESP32-C3-MINI-1U: https://www.espressif.com/sites/default/files/documentation/esp32-c3-mini-1_datasheet_en.pdf
ESP32-C3
0
61
53
PCM_Espressif
ESP32-C3-MINI-1_HandSoldering
ESP32-C3-MINI-1: https://www.espressif.com/sites/default/files/documentation/esp32-c3-mini-1_datasheet_en.pdf
ESP32-C3
0
61
53
PCM_Espressif
ESP32-C3-WROOM-02
ESP32-C3-WROOM-02: https://www.espressif.com/sites/default/files/documentation/esp32-c3-wroom-02_datasheet_en.pdf
ESP32-C3
0
27
19
PCM_Espressif
ESP32-C3-WROOM-02U
ESP32-C3-WROOM-02: https://www.espressif.com/sites/default/files/documentation/esp32-c3-wroom-02_datasheet_en.pdf
ESP32-C3
0
27
19
PCM_Espressif
ESP32-C6-DevKitC-1
ESP32-C6 general-purpose development board, based on ESP32-2-WROOM-1,It has all the ESP32-C6 pins exposed and is easy to connect and use.
ESP32-C6
0
32
32
PCM_Espressif
ESP32-C6-DevKitM-1
ESP32-C6 general-purpose development board, based on ESP32-2-WROOM-1,It has all the ESP32-C6 pins exposed and is easy to connect and use.
ESP32-C6
0
30
30
PCM_Espressif
ESP32-C6-MINI-1
ESP32-C6-MINI-1: https://www.espressif.com/sites/default/files/documentation/esp32-c6-mini-1_datasheet_en.pdf
ESP32-C6
0
61
53
PCM_Espressif
ESP32-C6-MINI-1U
ESP32-C6-MINI-1U: https://www.espressif.com/sites/default/files/documentation/esp32-c6-mini-1_datasheet_en.pdf
ESP32-C6
0
61
53
PCM_Espressif
ESP32-C6-WROOM-1
ESP32-C6-WROOM-1: https://www.espressif.com/sites/default/files/documentation/esp32-c6-wroom-1_datasheet_en.pdf
esp32-c6
0
37
29
PCM_Espressif
ESP32-C6-WROOM-1U
ESP32-C6-WROOM-1U: https://www.espressif.com/sites/default/files/documentation/esp32-c6-wroom-1_wroom-1u_datasheet_en.pdf
esp32-c6
0
37
29
PCM_Espressif
ESP32-DevKitC
ESP32-DevKitC: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/hw-reference/esp32/get-started-devkitc.html
ESP32
0
38
38
PCM_Espressif
ESP32-H2-MINI-1
ESP32-H2-MINI-1: https://www.espressif.com/sites/default/files/documentation/esp32-h2-mini-1_mini-1u_datasheet_en.pdf
ESP32-H2
0
61
53
PCM_Espressif
ESP32-MINI-1
ESP32-MINI-1: https://www.espressif.com/sites/default/files/documentation/esp32-mini-1_datasheet_en.pdf
ESP32-MINI-1
0
63
55
PCM_Espressif
ESP32-MINI-1U
ESP32-MINI-1U: https://www.espressif.com/sites/default/files/documentation/esp32-mini-1_datasheet_en.pdf
ESP32-MINI-1U
0
63
55
PCM_Espressif
ESP32-PICO-MINI-02
ESP32-PICO-MINI-02: https://www.espressif.com/sites/default/files/documentation/esp32-pico-mini-02_datasheet_en.pdf
ESP32-PICO-MINI-02
0
61
53
PCM_Espressif
ESP32-PICO-MINI-02U
ESP32-PICO-MINI-02U: https://www.espressif.com/sites/default/files/documentation/esp32-pico-mini-02_datasheet_en.pdf
ESP32-PICO-MINI-02U
0
61
53
PCM_Espressif
ESP32-PICO-MINI-02_HandSoldering
ESP32-PICO-MINI-02: https://www.espressif.com/sites/default/files/documentation/esp32-pico-mini-02_datasheet_en.pdf
ESP32-PICO-MINI-02
0
61
53
PCM_Espressif
ESP32-S2-DevKitC-1
ESP32-S2 general-purpose development board, based on ESP32-S2-SOLO or ESP32-S2-SOLO-U,It has all the ESP32-S2 pins exposed and is easy to connect and use.
ESP32-S2
0
44
44
PCM_Espressif
ESP32-S2-DevKitM
ESP32-S2 general-purpose development board
ESP32-S2
0
42
42
PCM_Espressif
ESP32-S2-MINI-1
ESP32-S2-MINI-1 and ESP32-S2-MINI-1U: https://www.espressif.com/sites/default/files/documentation/esp32-s2-mini-1_esp32-s2-mini-1u_datasheet_en.pdf
ESP32-S2
0
73
65
PCM_Espressif
ESP32-S2-MINI-1U
ESP32-S2-MINI-1 and ESP32-S2-MINI-1U: https://www.espressif.com/sites/default/files/documentation/esp32-s2-mini-1_esp32-s2-mini-1u_datasheet_en.pdf
ESP32-S2
0
73
65
PCM_Espressif
ESP32-S2-MINI-1_HandSoldering
ESP32-S2-MINI-1 and ESP32-S2-MINI-1U: https://www.espressif.com/sites/default/files/documentation/esp32-s2-mini-1_esp32-s2-mini-1u_datasheet_en.pdf
ESP32-S2 Hand Soldering
0
73
65
PCM_Espressif
ESP32-S2-SOLO
ESP32-S2-SOLO https://www.espressif.com/sites/default/files/documentation/esp32-s2-solo_esp32-s2-solo-u_datasheet_en.pdf
esp32-s2 module
0
49
41
PCM_Espressif
ESP32-S2-SOLO-2U
ESP32-S2-SOLO-2U https://www.espressif.com/sites/default/files/documentation/esp32-s2-solo-2_esp32-s2-solo-2u_datasheet_en.pdf
esp32-s2 module
0
49
41
PCM_Espressif
ESP32-S2-Saola-1
Espressif ESP32-S2-Saola-1 Development Kit: https://docs.espressif.com/projects/esp-idf/en/latest/esp32s2/hw-reference/esp32s2/user-guide-saola-1-v1.2.html
esp32-s2 devkit
0
42
42
PCM_Espressif
ESP32-S2-WROOM
ESP32-S2-WROOM and ESP32-S2-WROOM-I: https://www.espressif.com/sites/default/files/documentation/esp32-s2-wroom_esp32-s2-wroom-i_datasheet_en.pdf
ESP32-S2
0
51
43
PCM_Espressif
ESP32-S2-WROVER
ESP32-S2-WROVER and ESP32-S2-WROVER-I: https://www.espressif.com/sites/default/files/documentation/esp32-s2-wrover_esp32-s2-wrover-i_datasheet_en.pdf
ESP32-S2
0
55
43
PCM_Espressif
ESP32-S3-DevKitC
ESP32-S3 general-purpose development board, based on ESP32-S3-WROOM-1 or ESP32-S3-WROOM-1U,It has all the ESP32-S3 pins exposed and is easy to connect and use.
ESP32-S3
0
44
44
PCM_Espressif
ESP32-S3-MINI-1
ESP32-S3-MINI-1
esp32-s3
0
73
65
PCM_Espressif
ESP32-S3-MINI-1U
ESP32-S3-MINI-1 and ESP32-S3-MINI-1U
esp32-s3
0
73
65
PCM_Espressif
ESP32-S3-WROOM-1
ESP32-S3-WROOM-1 is a powerful, generic Wi-Fi + Bluetooth LE MCU modules that have Dual core CPU , a rich set of peripherals, provides acceleration for neural network computing and signal processing workloads. They are an ideal choice for a wide variety of application scenarios related to AI + Internet of Things (AIoT), such as wake word detection and speech commands recognition , face detection and recognition, smart home, smart appliance, smart control panel, smart speaker etc.
esp32-s3
0
51
41
PCM_Espressif
ESP32-S3-WROOM-1U
ESP32-S3-WROOM-1 is a powerful, generic Wi-Fi + Bluetooth LE MCU modules that have Dual core CPU , a rich set of peripherals, provides acceleration for neural network computing and signal processing workloads. They are an ideal choice for a wide variety of application scenarios related to AI + Internet of Things (AIoT), such as wake word detection and speech commands recognition , face detection and recognition, smart home, smart appliance, smart control panel, smart speaker etc.
esp32-s3
0
49
41
PCM_Espressif
ESP32-S3-WROOM-2
ESP32-S3-WROOM-2 is a powerful, generic Wi-Fi + Bluetooth LE MCU modules that have Dual core CPU , a rich set of peripherals, provides acceleration for neural network computing and signal processing workloads. They are an ideal choice for a wide variety of application scenarios related to AI + Internet of Things (AIoT), such as wake word detection and speech commands recognition , face detection and recognition, smart home, smart appliance, smart control panel, smart speaker etc.
esp32-s3
0
51
41
PCM_Espressif
ESP32-WROOM-32E
ESP32-WROOM-32E and ESP32-WROOM-32UE: https://www.espressif.com/sites/default/files/documentation/esp32-wroom-32e_esp32-wroom-32ue_datasheet_en.pdf
ESP32
0
50
39
PCM_Espressif
ESP32-WROOM-32UE
ESP32-WROOM-32E and ESP32-WROOM-32UE: https://www.espressif.com/sites/default/files/documentation/esp32-wroom-32e_esp32-wroom-32ue_datasheet_en.pdf
ESP32
0
47
39
PCM_Espressif
ESP32-WROOM-DA
ESP32-WROOM-DA: https://www.espressif.com/sites/default/files/documentation/esp32-wroom-da_datasheet_en.pdf
ESP32 Dual Antenna DA
0
49
41
PCM_Espressif
ESP32-WROVER-E
ESP32-WROVER-E: https://www.espressif.com/sites/default/files/documentation/esp32-wroom-32e_esp32-wroom-32ue_datasheet_en.pdf
esp32 module
0
47
39
PCM_Espressif
ESP32-WROVER-E_ThermalVias
ESP32-WROVER-E: https://www.espressif.com/sites/default/files/documentation/esp32-wroom-32e_esp32-wroom-32ue_datasheet_en.pdf
esp32 module thermal vias
0
59
39
PCM_Espressif
ESP8685-WROOM-06
ESP32-WROOM-06: https://www.espressif.com/sites/default/files/documentation/esp8685-wroom-06_datasheet_en.pdf
esp32 module
0
31
22
PCM_Espressif
QFN-32-1EP_4x4mm_P0.4mm_EP2.9x2.9mm
QFN, 32 Pin (http://ww1.microchip.com/downloads/en/DeviceDoc/atmel-8153-8-and-16-bit-avr-microcontroller-xmega-e-atxmega8e5-atxmega16e5-atxmega32e5_datasheet.pdf#page=70), generated with kicad-footprint-generator ipc_noLead_generator.py
QFN NoLead
0
37
33
Package_BGA
Alliance_TFBGA-54_8x8mm_Layout9x9_P0.8mm
Alliance TFBGA 54 pins, 8x8mm, 54 Ball, 9x9 Layout, 0.8mm Pitch, https://www.alliancememory.com/wp-content/uploads/pdf/dram/Alliance_Memory_64M-AS4C4M16SA-CI_v5.0_October_2018.pdf#page=54

View File

@ -5,4 +5,5 @@
(lib (name "TPS54331")(type "KiCad")(uri "${KIPRJMOD}/libs/TPS54331.pretty")(options "")(descr ""))
(lib (name "CUI_TS21")(type "KiCad")(uri "${KIPRJMOD}/libs/CUI_TS21.pretty")(options "")(descr ""))
(lib (name "DUALMOSFETS")(type "KiCad")(uri "${KIPRJMOD}/libs/DUALMOSFETS")(options "")(descr ""))
(lib (name "ICM-42670-P")(type "KiCad")(uri "${KIPRJMOD}/libs/ICM-42670-P.pretty")(options "")(descr ""))
)

View File

@ -0,0 +1,336 @@
(kicad_symbol_lib
(version 20231120)
(generator "kicad_symbol_editor")
(generator_version "8.0")
(symbol "ICM-42670-P"
(exclude_from_sim no)
(in_bom yes)
(on_board yes)
(property "Reference" "U"
(at 0 8.89 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Value" "ICM-42670-P"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Footprint" "ICM-42670-P:LGA-14_2.5x3x0.76mm"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Datasheet" "https://product.tdk.com/system/files/dam/doc/product/sensor/mortion-inertial/imu/data_sheet/ds-000451-icm-42670-p.pdf"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Description" "High performance 6-axis MEMS MotionTracking device. 3-axis gyroscope & 3-axis accelerometer"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(symbol "ICM-42670-P_1_1"
(rectangle
(start -8.89 7.62)
(end 8.89 -7.62)
(stroke
(width 0)
(type default)
)
(fill
(type background)
)
)
(text "if I2C/I3C \nAP_CS=VDDIO\nADDR=0x(AP_SDO?69:68)"
(at -8.382 3.556 0)
(effects
(font
(size 0.5 0.5)
)
(justify left)
)
)
(text "unused\nFSYNC=GND "
(at 3.81 -3.048 0)
(effects
(font
(size 0.5 0.5)
)
(justify left)
)
)
(pin bidirectional line
(at -11.43 -6.35 0)
(length 2.54)
(name "AP_SDO"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "1"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "10"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "11"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin input line
(at -11.43 1.27 0)
(length 2.54)
(name "AP_CS"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "12"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin input line
(at -11.43 -1.27 0)
(length 2.54)
(name "AP_SCLK"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "13"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin bidirectional line
(at -11.43 -3.81 0)
(length 2.54)
(name "AP_SDA/SDI"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "14"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "2"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "3"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin bidirectional line
(at 11.43 1.27 180)
(length 2.54)
(name "INT1"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "4"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin power_in line
(at -11.43 6.35 0)
(length 2.54)
(name "VDDIO"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "5"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin power_out line
(at 11.43 -6.35 180)
(length 2.54)
(name "GND"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "6"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin input line
(at 11.43 -1.27 180)
(length 2.54)
(name "FSYNC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "7"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin power_in line
(at 11.43 6.35 180)
(length 2.54)
(name "VDD"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "8"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin bidirectional line
(at 11.43 3.81 180)
(length 2.54)
(name "INT2"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "9"
(effects
(font
(size 1.27 1.27)
)
)
)
)
)
)
)

View File

@ -0,0 +1,336 @@
(kicad_symbol_lib
(version 20231120)
(generator "kicad_symbol_editor")
(generator_version "8.0")
(symbol "ICM-42670-P"
(exclude_from_sim no)
(in_bom yes)
(on_board yes)
(property "Reference" "U"
(at 0 8.89 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Value" "ICM-42670-P"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Footprint" "ICM-42670-P:LGA-14_2.5x3x0.76mm"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Datasheet" "https://product.tdk.com/system/files/dam/doc/product/sensor/mortion-inertial/imu/data_sheet/ds-000451-icm-42670-p.pdf"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Description" "High performance 6-axis MEMS MotionTracking device. 3-axis gyroscope & 3-axis accelerometer"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(symbol "ICM-42670-P_1_1"
(rectangle
(start -8.89 7.62)
(end 8.89 -7.62)
(stroke
(width 0)
(type default)
)
(fill
(type background)
)
)
(text "if I2C/I3C \nAP_CS=VDDIO\nADDR=0x(AP_SDO?69:68)"
(at -8.382 3.556 0)
(effects
(font
(size 0.5 0.5)
)
(justify left)
)
)
(text "unused\nFSYNC=GND "
(at 3.81 -3.048 0)
(effects
(font
(size 0.5 0.5)
)
(justify left)
)
)
(pin bidirectional line
(at -11.43 -6.35 0)
(length 2.54)
(name "AP_SDO"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "1"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "10"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "11"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin input line
(at -11.43 1.27 0)
(length 2.54)
(name "AP_CS"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "12"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin input line
(at -11.43 -1.27 0)
(length 2.54)
(name "AP_SCLK"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "13"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin bidirectional line
(at -11.43 -3.81 0)
(length 2.54)
(name "AP_SDA/SDI"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "14"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "2"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin no_connect line
(at 11.43 -3.81 180)
(length 2.54) hide
(name "NC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "3"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin bidirectional line
(at 11.43 1.27 180)
(length 2.54)
(name "INT1"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "4"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin power_in line
(at -11.43 6.35 0)
(length 2.54)
(name "VDDIO"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "5"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin power_out line
(at 11.43 -6.35 180)
(length 2.54)
(name "GND"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "6"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin input line
(at 11.43 -1.27 180)
(length 2.54)
(name "FSYNC"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "7"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin power_in line
(at 11.43 6.35 180)
(length 2.54)
(name "VDD"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "8"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin bidirectional line
(at 11.43 3.81 180)
(length 2.54)
(name "INT2"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "9"
(effects
(font
(size 1.27 1.27)
)
)
)
)
)
)
)

View File

@ -0,0 +1,336 @@
(footprint "LGA-14_2.5x3x0.76mm"
(version 20240108)
(generator "pcbnew")
(generator_version "8.0")
(layer "F.Cu")
(property "Reference" "REF**"
(at 3.3 0 -90)
(layer "F.SilkS")
(uuid "de8d8166-506e-45ca-ade4-5f453aa40416")
(effects
(font
(size 1 1)
(thickness 0.15)
)
)
)
(property "Value" "LGA-14_2.5x3x0.76mm"
(at 0 3.3 0)
(layer "F.Fab")
(uuid "4191ce5d-fbe2-4bcb-8a06-b7704306ff8d")
(effects
(font
(size 1 1)
(thickness 0.15)
)
)
)
(property "Footprint" ""
(at 0 0 -90)
(layer "F.Fab")
(hide yes)
(uuid "7697cf6c-be47-4bd0-821d-3d588b395971")
(effects
(font
(size 1.27 1.27)
(thickness 0.15)
)
)
)
(property "Datasheet" ""
(at 0 0 -90)
(layer "F.Fab")
(hide yes)
(uuid "65764036-5398-44f3-b170-74ffcf552b9e")
(effects
(font
(size 1.27 1.27)
(thickness 0.15)
)
)
)
(property "Description" ""
(at 0 0 -90)
(layer "F.Fab")
(hide yes)
(uuid "a223f18a-f8b4-4d71-b450-9624a6648987")
(effects
(font
(size 1.27 1.27)
(thickness 0.15)
)
)
)
(solder_paste_margin -0.03)
(solder_paste_ratio -0.05)
(attr smd)
(fp_line
(start -1.65 -1.25)
(end -1.65 -1.78)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "8b21d4f4-5f9e-4e24-b168-f4aa02b8c13f")
)
(fp_line
(start -1.65 1.25)
(end -1.65 1.4)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "c7d5ffbf-2c75-46a9-8fba-82d9a472366d")
)
(fp_line
(start -1.65 1.4)
(end -1 1.4)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "bb4e8dca-1d2a-45da-a1b8-9a6b11e9120e")
)
(fp_line
(start 1.65 -1.4)
(end 1 -1.4)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "4e8f08a3-7807-4e4d-8643-c191a847b794")
)
(fp_line
(start 1.65 -1.25)
(end 1.65 -1.4)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "5d9f8797-58af-436f-9ec4-a32e652b4e83")
)
(fp_line
(start 1.65 1.25)
(end 1.65 1.4)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "cdbdcc0c-b76c-4583-9c03-374dbe2f104d")
)
(fp_line
(start 1.65 1.4)
(end 1 1.4)
(stroke
(width 0.12)
(type default)
)
(layer "F.SilkS")
(uuid "4c5cadc4-77e0-4105-8c31-20882697e103")
)
(fp_line
(start -2.3 -2.05)
(end 2.3 -2.05)
(stroke
(width 0.05)
(type default)
)
(layer "F.CrtYd")
(uuid "a9f6c601-e9a7-48e0-b40d-9208b834ec26")
)
(fp_line
(start -2.3 2.05)
(end -2.3 -2.05)
(stroke
(width 0.05)
(type default)
)
(layer "F.CrtYd")
(uuid "af9baf3d-130d-48a7-ac41-c1fa1abeeed4")
)
(fp_line
(start 2.3 -2.05)
(end 2.3 2.05)
(stroke
(width 0.05)
(type default)
)
(layer "F.CrtYd")
(uuid "e00c1407-edd9-482b-a1c4-97979a97fbe0")
)
(fp_line
(start 2.3 2.05)
(end -2.3 2.05)
(stroke
(width 0.05)
(type default)
)
(layer "F.CrtYd")
(uuid "706f8e43-6bfc-4245-a4aa-dbfe40c708da")
)
(fp_line
(start -1.5 -0.25)
(end -0.5 -1.25)
(stroke
(width 0.15)
(type default)
)
(layer "F.Fab")
(uuid "77694995-a681-4fa7-964f-428eb2f8ffec")
)
(fp_line
(start -1.5 1.25)
(end -1.5 -0.25)
(stroke
(width 0.15)
(type default)
)
(layer "F.Fab")
(uuid "460704c7-abcd-4abe-acb8-992c42baa2b0")
)
(fp_line
(start -1.5 1.25)
(end 1.5 1.25)
(stroke
(width 0.15)
(type default)
)
(layer "F.Fab")
(uuid "e51503ef-ff87-454c-a3cc-07ff34a264a0")
)
(fp_line
(start -0.5 -1.25)
(end 1.5 -1.25)
(stroke
(width 0.15)
(type default)
)
(layer "F.Fab")
(uuid "a5dde9d2-a29b-4dc0-80e1-5e01fcb03aa1")
)
(fp_line
(start 1.5 -1.25)
(end 1.5 1.25)
(stroke
(width 0.15)
(type default)
)
(layer "F.Fab")
(uuid "37376a1d-da81-48d1-b103-b317a24cdb1a")
)
(fp_text user "${REFERENCE}"
(at 0 0 0)
(layer "F.Fab")
(uuid "427884c8-4558-4799-9310-fa9cd3a2a716")
(effects
(font
(size 1 1)
(thickness 0.15)
)
)
)
(pad "1" smd rect
(at -1.595 -0.75 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "71538814-7bfb-43c1-a1c8-7a8191f38500")
)
(pad "2" smd rect
(at -1.595 -0.25 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "b800844d-f322-4c6b-99d9-2f806f8ded0b")
)
(pad "3" smd rect
(at -1.595 0.25 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "fddadff3-34df-4839-8afe-ed5947b56525")
)
(pad "4" smd rect
(at -1.595 0.75 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "fe736c38-bda5-4dd8-a9bf-8d4d73224e23")
)
(pad "5" smd rect
(at -0.5 1.345)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "f67d7090-dd9d-4325-b953-c52174cda83b")
)
(pad "6" smd rect
(at 0 1.345)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "db152a36-375d-4123-a911-132643041ccb")
)
(pad "7" smd rect
(at 0.5 1.345)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "7b8618eb-32b1-4149-aa11-5b314affd3d7")
)
(pad "8" smd rect
(at 1.595 0.7625 270)
(size 0.225 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "2ba97761-ca82-4519-a1b1-de0b58b27a77")
)
(pad "9" smd rect
(at 1.595 0.25 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "e8ba81e2-f8b4-4b4f-8c86-5c54ce91becd")
)
(pad "10" smd rect
(at 1.595 -0.25 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "9222d527-aafd-4776-8112-4418243b04d5")
)
(pad "11" smd rect
(at 1.595 -0.75 270)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "ec2e0f62-ed28-4f72-98f9-baee7bd1be80")
)
(pad "12" smd rect
(at 0.5 -1.345)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "76bf2651-bee1-4750-b670-42fb1eeabd25")
)
(pad "13" smd rect
(at 0 -1.345)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "fa077ac8-18ec-4af9-9d95-4a6dc7b08c2f")
)
(pad "14" smd rect
(at -0.5 -1.345)
(size 0.25 1.31)
(layers "F.Cu" "F.Paste" "F.Mask")
(thermal_bridge_angle 45)
(uuid "3e2a126e-7d21-4a69-9a5e-c8e9150663a0")
)
)

File diff suppressed because it is too large Load Diff

View File

@ -1,6 +1,6 @@
{
"board": {
"active_layer": 37,
"active_layer": 47,
"active_layer_preset": "",
"auto_track_width": false,
"hidden_netclasses": [],

View File

@ -48,7 +48,7 @@
"silk_text_thickness": 0.1,
"silk_text_upright": false,
"zones": {
"min_clearance": 0.2
"min_clearance": 0.1
}
},
"diff_pair_dimensions": [

File diff suppressed because it is too large Load Diff

View File

@ -7,4 +7,5 @@
(lib (name "DRV8323R")(type "KiCad")(uri "${KIPRJMOD}/libs/DRV8323R.kicad_sym")(options "")(descr ""))
(lib (name "SiZ250DT")(type "KiCad")(uri "${KIPRJMOD}/libs/DUALMOSFETS/SiZ250DT.kicad_sym")(options "")(descr ""))
(lib (name "DIO6605B")(type "KiCad")(uri "${KIPRJMOD}/libs/DIO6605B/DIO6605B.kicad_sym")(options "")(descr ""))
(lib (name "ICM-42670-P")(type "KiCad")(uri "${KIPRJMOD}/libs/ICM-42670-P.pretty/ICM-42670-P.kicad_sym")(options "")(descr ""))
)