65 Commits

Author SHA1 Message Date
Håkan Båstedt
a99d0f0eda Update README.md 2024-02-19 22:16:27 +01:00
Hakan Bastedt
c21d42cf0b Updated readme pending video release. 2024-02-19 21:51:31 +01:00
Hakan Bastedt
7ffd757fb5 After building the first board. 2024-02-19 18:02:48 +01:00
Hakan Bastedt
934f3cb028 Octave files not commited 2024-01-29 12:08:01 +01:00
Hakan Bastedt
d60822388e ordered 2024-01-26 22:02:32 +01:00
Hakan Bastedt
31d24e2676 Fab from this version 2024-01-26 16:38:10 +01:00
Hakan Bastedt
c444f9a496 Getting ready for fab 2024-01-26 16:27:17 +01:00
Hakan Bastedt
e234ea7a97 morfe copper in +5V leads 2024-01-26 13:44:45 +01:00
Hakan Bastedt
eb63adbdc2 all leds are now 0603 2024-01-26 13:21:14 +01:00
Hakan Bastedt
70014d3b1d Added 4k7 pullup onm scs_func. Think not needed since it is to a pin on stm32, but in case 2024-01-26 12:38:11 +01:00
Hakan Bastedt
990801f2d0 4.7k to 4k7 2024-01-26 01:10:08 +01:00
Hakan Bastedt
329474309d Might be in final shape. 2024-01-25 22:35:25 +01:00
Hakan Bastedt
da2b1f6376 resistor overhaul 2024-01-25 13:08:04 +01:00
Hakan Bastedt
a88090a853 wip 2024-01-25 11:31:48 +01:00
Hakan Bastedt
aa955aec67 Two-layer now 2024-01-25 00:30:19 +01:00
Hakan Bastedt
e641fd04b7 First component placement 2024-01-25 00:27:56 +01:00
Hakan Bastedt
ac711cd168 Assigned footprints 2024-01-24 20:10:20 +01:00
Hakan Bastedt
ee56f85c53 Steppers, encoders, IO, etc remapped 2024-01-24 19:44:33 +01:00
Hakan Bastedt
69357d35a4 Wip optocoupler input and outputs 2024-01-23 23:42:32 +01:00
Hakan Bastedt
84d790c687 Cleaning old gerber files. 2024-01-23 23:00:09 +01:00
Hakan Bastedt
e7fc20fec5 micros() in irq is suspicous. Some optomization of stepper parameters. Comments. 2024-01-23 22:40:15 +01:00
Hakan Bastedt
f8cec1ac69 How many times to fix it? 2024-01-23 17:51:44 +01:00
Hakan Bastedt
ddffbe5f8b Actually don't run ecat-slv_poll() 2024-01-23 15:48:59 +01:00
Håkan Båstedt
e95a098367 Update README.md 2024-01-23 13:27:26 +01:00
Hakan Bastedt
1d36ffbf69 Pending video7 release 2024-01-23 13:16:31 +01:00
Hakan Bastedt
c97e1fa96a Moved ESCvar.PrevTime. It's not used though 2024-01-23 11:22:09 +01:00
Hakan Bastedt
ef84d552e4 Debug comments 2024-01-23 11:17:00 +01:00
Hakan Bastedt
d93adac4a2 Don't run ecat_slv_poll() when expecting to serve interrupt 2024-01-23 11:00:47 +01:00
Hakan Bastedt
ca3ceac5c6 wip inputs with photodiodes etc 2024-01-21 23:31:45 +01:00
Hakan Bastedt
b534e3d4da Kludge with 'tone' of steppers. Gives ferror, but nice tone 2024-01-21 23:29:59 +01:00
Hakan Bastedt
6ac0949f26 Added optional pull-down to step generators 2024-01-21 00:24:36 +01:00
Hakan Bastedt
1f97534133 New pwmCycleTime different from sync0CycleTime 2024-01-20 12:37:42 +01:00
Hakan Bastedt
e6bfe4f880 Tests for growling. That 10xcycle time seems to do it, but it's not right. 2024-01-19 21:31:15 +01:00
Hakan Bastedt
8f05f33e58 Both steppers work in simulated environment 2024-01-18 18:21:21 +01:00
Hakan Bastedt
9e311038c1 TIM8 replaced with TIM3. TIM3,chan4 works on PC9. TIM8,chan4 should work but doesn't. How should one know? 2024-01-18 17:21:12 +01:00
Hakan Bastedt
9ab4afabe4 New enable input. Add dc ability. Set only SM2 synchronization. Various to make lathe work 2024-01-18 14:26:51 +01:00
Hakan Bastedt
38825bbaf3 Trying to make stepper suing tim8 work 2024-01-18 14:25:19 +01:00
Hakan Bastedt
0a04124b35 Remove TIM8, TIM8 is stepper generator timer. 2024-01-17 00:29:06 +01:00
Hakan Bastedt
760944afe5 Various improvements. New pdo variable stepsPerMM. 2024-01-17 00:24:17 +01:00
Hakan Bastedt
044e8fd2c5 Removed unnecessary condition in timerCB, was aleady test on ´steps´ 2024-01-15 23:10:25 +01:00
Hakan Bastedt
697ea19dae Bug, digitalWrite of stepPin should be dirPin in timerCB. Reshuffling 2024-01-15 23:07:46 +01:00
Hakan Bastedt
20ca9d4974 Maybe works better now. Using G0 can not provoke the scrape sound. Jogging for a long while can provoke still. 2024-01-15 21:12:23 +01:00
Hakan Bastedt
c6857d0be2 Still problem with overlapping cycles in stepgen. TIM8 works for stepgen now. 2024-01-15 20:21:14 +01:00
Hakan Bastedt
f14b0160f6 Spelling 2024-01-15 15:54:11 +01:00
Hakan Bastedt
deadd488dd Two stepgens active pending lathe test 2024-01-13 22:44:08 +01:00
Hakan Bastedt
25c2aa7b3c Some cleanup. 2024-01-12 14:37:25 +01:00
Hakan Bastedt
7a63d27303 Two encoders and two steppers declared. Encoder is 64-bit again 2024-01-11 21:10:27 +01:00
Hakan Bastedt
6176166b3a More encapsulation of timer info. 2024-01-11 16:44:28 +01:00
Hakan Bastedt
5df911296c sync0CycleTime static member of StepGen 2024-01-11 10:54:13 +01:00
Hakan Bastedt
a4488da9fa Cleanup encoder code 2024-01-11 10:42:29 +01:00
Hakan Bastedt
cd8388ea58 Reshuffle in main.cpp 2024-01-10 23:42:05 +01:00
Hakan Bastedt
6f29a0d492 Further cleanup and modularization 2024-01-10 22:27:04 +01:00
Hakan Bastedt
3bbf089d01 MyEncoder split into cpp and h file 2024-01-10 22:05:38 +01:00
Hakan Bastedt
2e4e768d5e Raw classified encoder. Compiles, untested 2024-01-10 21:58:11 +01:00
Hakan Bastedt
6c168d96d9 Test with different stepscale. ok 2024-01-10 20:25:26 +01:00
Hakan Bastedt
f8fc5fccd6 Max step-rate introduced - solves initial step storm 2024-01-10 20:08:30 +01:00
Hakan Bastedt
f6abd73c58 Split class into cpp and h file. Works at commands, but initial isn't ok 2024-01-10 18:59:16 +01:00
Hakan Bastedt
c5a95074dc Moved stepper into C++ class. Seems to work. Basic 2024-01-10 18:44:58 +01:00
Hakan Bastedt
8614d1dfd3 Moved stepper into C++ class. Seems to work. Basic 2024-01-10 18:44:40 +01:00
Hakan Bastedt
251fd29d23 wip 2024-01-10 15:32:45 +01:00
Hakan Bastedt
5ad02fae03 New gerber files for ax58100 for pcb quotations 2024-01-10 15:30:41 +01:00
Hakan Bastedt
9adae08b98 It seems to work now, with reload in the timer_CB. Avoid micros() 2024-01-09 22:20:20 +01:00
Hakan Bastedt
0b9ce37200 Reloading in irq might possibly work 2024-01-09 10:39:56 +01:00
Hakan Bastedt
120b423f59 Restructure, makes pulses again 2024-01-08 21:13:34 +01:00
Hakan Bastedt
222e5857dc Reorganize 2024-01-07 19:38:22 +01:00
33 changed files with 41266 additions and 52126 deletions

1
.gitignore vendored
View File

@@ -3,3 +3,4 @@
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch
Octave

View File

@@ -9,8 +9,9 @@ Mcu.CPN=STM32F407VGT6
Mcu.Family=STM32F4
Mcu.IP0=DAC
Mcu.IP1=I2C2
Mcu.IP10=TIM8
Mcu.IP11=USART1
Mcu.IP10=TIM5
Mcu.IP11=TIM9
Mcu.IP12=USART1
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI1
@@ -19,48 +20,44 @@ Mcu.IP6=TIM1
Mcu.IP7=TIM2
Mcu.IP8=TIM3
Mcu.IP9=TIM4
Mcu.IPNb=12
Mcu.IPNb=13
Mcu.Name=STM32F407V(E-G)Tx
Mcu.Package=LQFP100
Mcu.Pin0=PA0-WKUP
Mcu.Pin1=PA1
Mcu.Pin10=PB1
Mcu.Pin11=PE7
Mcu.Pin12=PE8
Mcu.Pin13=PE9
Mcu.Pin14=PE10
Mcu.Pin15=PE11
Mcu.Pin16=PE12
Mcu.Pin17=PE13
Mcu.Pin18=PE14
Mcu.Pin19=PE15
Mcu.Pin2=PA2
Mcu.Pin20=PB10
Mcu.Pin21=PB11
Mcu.Pin22=PD11
Mcu.Pin23=PD12
Mcu.Pin24=PD13
Mcu.Pin25=PC6
Mcu.Pin26=PC7
Mcu.Pin27=PC9
Mcu.Pin28=PA8
Mcu.Pin29=PA9
Mcu.Pin3=PA4
Mcu.Pin30=PA10
Mcu.Pin31=PA11
Mcu.Pin32=PA12
Mcu.Pin33=PC10
Mcu.Pin34=PB4
Mcu.Pin35=PB5
Mcu.Pin36=PB6
Mcu.Pin37=VP_SYS_VS_Systick
Mcu.Pin4=PA5
Mcu.Pin5=PA6
Mcu.Pin6=PA7
Mcu.Pin7=PC4
Mcu.Pin8=PC5
Mcu.Pin9=PB0
Mcu.PinsNb=38
Mcu.Pin0=PE5
Mcu.Pin1=PA0-WKUP
Mcu.Pin10=PB0
Mcu.Pin11=PB1
Mcu.Pin12=PE7
Mcu.Pin13=PE8
Mcu.Pin14=PE9
Mcu.Pin15=PE10
Mcu.Pin16=PE11
Mcu.Pin17=PE12
Mcu.Pin18=PE13
Mcu.Pin19=PE14
Mcu.Pin2=PA1
Mcu.Pin20=PE15
Mcu.Pin21=PB10
Mcu.Pin22=PB11
Mcu.Pin23=PD11
Mcu.Pin24=PD12
Mcu.Pin25=PC9
Mcu.Pin26=PA8
Mcu.Pin27=PA9
Mcu.Pin28=PA10
Mcu.Pin29=PA11
Mcu.Pin3=PA2
Mcu.Pin30=PA12
Mcu.Pin31=PC10
Mcu.Pin32=PB6
Mcu.Pin33=VP_SYS_VS_Systick
Mcu.Pin4=PA4
Mcu.Pin5=PA5
Mcu.Pin6=PA6
Mcu.Pin7=PA7
Mcu.Pin8=PC4
Mcu.Pin9=PC5
Mcu.PinsNb=34
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F407VGTx
@@ -84,8 +81,7 @@ PA10.Signal=USART1_RX
PA11.Signal=S_TIM1_CH4
PA12.Locked=true
PA12.Signal=GPIO_Output
PA2.Locked=true
PA2.Signal=GPIO_Input
PA2.Signal=S_TIM5_CH3
PA4.Signal=COMP_DAC1_group
PA5.Mode=Full_Duplex_Master
PA5.Signal=SPI1_SCK
@@ -105,8 +101,6 @@ PB10.Mode=I2C
PB10.Signal=I2C2_SCL
PB11.Mode=I2C
PB11.Signal=I2C2_SDA
PB4.Signal=S_TIM3_CH1
PB5.Signal=S_TIM3_CH2
PB6.Locked=true
PB6.Signal=GPIO_Input
PC10.Locked=true
@@ -115,13 +109,10 @@ PC4.Locked=true
PC4.Signal=GPIO_Output
PC5.Locked=true
PC5.Signal=GPIO_Input
PC6.Signal=S_TIM8_CH1
PC7.Signal=S_TIM8_CH2
PC9.Signal=S_TIM8_CH4
PC9.Signal=S_TIM3_CH4
PD11.Locked=true
PD11.Signal=GPIO_Input
PD12.Signal=S_TIM4_CH1
PD13.Signal=S_TIM4_CH2
PE10.Locked=true
PE10.Signal=GPIO_Output
PE11.Locked=true
@@ -134,6 +125,7 @@ PE14.Locked=true
PE14.Signal=GPIO_Input
PE15.Locked=true
PE15.Signal=GPIO_Input
PE5.Signal=S_TIM9_CH1
PE7.Locked=true
PE7.Signal=GPIO_Output
PE8.Locked=true
@@ -200,20 +192,14 @@ SH.S_TIM2_CH1_ETR.0=TIM2_CH1,Encoder_Interface
SH.S_TIM2_CH1_ETR.ConfNb=1
SH.S_TIM2_CH2.0=TIM2_CH2,Encoder_Interface
SH.S_TIM2_CH2.ConfNb=1
SH.S_TIM3_CH1.0=TIM3_CH1,Encoder_Interface
SH.S_TIM3_CH1.ConfNb=1
SH.S_TIM3_CH2.0=TIM3_CH2,Encoder_Interface
SH.S_TIM3_CH2.ConfNb=1
SH.S_TIM4_CH1.0=TIM4_CH1,Encoder_Interface
SH.S_TIM3_CH4.0=TIM3_CH4,PWM Generation4 CH4
SH.S_TIM3_CH4.ConfNb=1
SH.S_TIM4_CH1.0=TIM4_CH1,PWM Generation1 CH1
SH.S_TIM4_CH1.ConfNb=1
SH.S_TIM4_CH2.0=TIM4_CH2,Encoder_Interface
SH.S_TIM4_CH2.ConfNb=1
SH.S_TIM8_CH1.0=TIM8_CH1,Encoder_Interface
SH.S_TIM8_CH1.ConfNb=1
SH.S_TIM8_CH2.0=TIM8_CH2,Encoder_Interface
SH.S_TIM8_CH2.ConfNb=1
SH.S_TIM8_CH4.0=TIM8_CH4,PWM Generation4 CH4
SH.S_TIM8_CH4.ConfNb=1
SH.S_TIM5_CH3.0=TIM5_CH3,Input_Capture3_from_TI3
SH.S_TIM5_CH3.ConfNb=1
SH.S_TIM9_CH1.0=TIM9_CH1,PWM Generation1 CH1
SH.S_TIM9_CH1.ConfNb=1
SPI1.CalculateBaudRate=8.0 MBits/s
SPI1.Direction=SPI_DIRECTION_2LINES
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
@@ -221,8 +207,14 @@ SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM1.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM1.IPParameters=Channel-PWM Generation4 CH4
TIM8.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM8.IPParameters=Channel-PWM Generation4 CH4
TIM3.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM3.IPParameters=Channel-PWM Generation4 CH4
TIM4.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM4.IPParameters=Channel-PWM Generation1 CH1
TIM5.Channel-Input_Capture3_from_TI3=TIM_CHANNEL_3
TIM5.IPParameters=Channel-Input_Capture3_from_TI3
TIM9.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM9.IPParameters=Channel-PWM Generation1 CH1
USART1.IPParameters=VirtualMode
USART1.VirtualMode=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick

View File

@@ -1,6 +1,6 @@
<head>
<meta charset="UTF-8">
<title>🔁 EEPROM Generator | ESI, EEPORM, SOES C code configuration tool</title>
<title>🔁 EEPROM Generator | ESI, EEPROM, SOES C code configuration tool</title>
<!--
* SOES EEPROM generator
* This tool serves as:

View File

@@ -8,7 +8,10 @@
"string": "cpp",
"unordered_map": "cpp",
"vector": "cpp",
"system_error": "cpp"
"system_error": "cpp",
"numeric": "cpp",
"ostream": "cpp"
},
"C_Cpp.errorSquiggles": "disabled"
"C_Cpp.errorSquiggles": "disabled",
"cmake.configureOnOpen": false
}

37
Firmware/include/MyEncoder.h Executable file
View File

@@ -0,0 +1,37 @@
#ifndef MYENCODER
#define MYENCODER
#include "Stm32F4_Encoder.h"
#include <CircularBuffer.h>
#define RINGBUFFERLEN 101
class MyEncoder
{
public:
MyEncoder(TIM_TypeDef *_tim_base, uint8_t _indexPin, void irq(void));
int64_t unwrapEncoder(uint16_t in);
void indexPulse(void);
uint8_t indexHappened();
double currentPos();
double frequency(uint64_t time);
uint8_t getIndexState();
void setScale(double scale);
void setLatch(uint8_t latchEnable);
private:
int64_t previousEncoderCounterValue = 0;
double PosScaleRes = 1.0;
uint32_t CurPosScale = 1;
uint8_t oldLatchCEnable = 0;
volatile uint8_t indexPulseFired = 0;
volatile uint8_t pleaseZeroTheCounter = 0;
Encoder EncoderInit;
uint8_t indexPin;
CircularBuffer<double_t, RINGBUFFERLEN> Pos;
CircularBuffer<uint32_t, RINGBUFFERLEN> TDelta;
double curPos;
TIM_TypeDef *tim_base;
};
#endif

42
Firmware/include/StepGen.h Executable file
View File

@@ -0,0 +1,42 @@
#ifndef STEPGEN
#define STEPGEN
#include <HardwareTimer.h>
class StepGen
{
private:
volatile uint8_t timerIsRunning;
volatile int32_t timerStepPosition;
volatile int32_t timerStepDirection;
volatile int32_t timerStepPositionAtEnd;
volatile int32_t timerNewEndStepPosition;
volatile uint32_t timerNewCycleTime;
volatile double_t actualPosition;
volatile double_t requestedPosition;
volatile uint8_t enabled;
HardwareTimer *MyTim;
uint16_t stepsPerMM;
uint8_t dirPin;
PinName stepPin;
uint32_t timerChan;
const uint32_t maxFreq = 100000;
volatile uint32_t prevFreq1 = 0;
volatile uint32_t prevFreq2 = 0;
public:
static uint32_t sync0CycleTime;
volatile uint32_t pwmCycleTime;
StepGen(TIM_TypeDef *Timer, uint32_t timerChannel, PinName stepPin, uint8_t dirPin, void irq(void));
void reqPos(double_t pos);
double reqPos();
void actPos(double_t pos);
double actPos();
void handleStepper(void);
void timerCB();
void setScale(int16_t spm);
void enable(uint8_t yes);
};
#endif

View File

@@ -1,38 +0,0 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
void StepperSetup(void);
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx_hal.h"
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
void makePulses(uint32_t totalLength /* µsec */, uint32_t nPulses);
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */

File diff suppressed because it is too large Load Diff

View File

@@ -148,7 +148,75 @@
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>CommandedVelocity</Name>
<Name>StepsPerMM</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1603</Name>
<BitSize>144</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>CommandedPosition</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>StepsPerMM</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1604</Name>
<BitSize>144</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>Enable1</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>Padding 1</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>80</BitOffs>
@@ -301,6 +369,30 @@
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1A06</Name>
<BitSize>80</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>ActualPosition</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1C00ARR</Name>
<BaseType>USINT</BaseType>
@@ -336,15 +428,15 @@
<DataType>
<Name>DT1C12ARR</Name>
<BaseType>UINT</BaseType>
<BitSize>48</BitSize>
<BitSize>80</BitSize>
<ArrayInfo>
<LBound>1</LBound>
<Elements>3</Elements>
<Elements>5</Elements>
</ArrayInfo>
</DataType>
<DataType>
<Name>DT1C12</Name>
<BitSize>64</BitSize>
<BitSize>96</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -358,7 +450,7 @@
<SubItem>
<Name>Elements</Name>
<Type>DT1C12ARR</Type>
<BitSize>48</BitSize>
<BitSize>80</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
@@ -368,15 +460,15 @@
<DataType>
<Name>DT1C13ARR</Name>
<BaseType>UINT</BaseType>
<BitSize>96</BitSize>
<BitSize>112</BitSize>
<ArrayInfo>
<LBound>1</LBound>
<Elements>6</Elements>
<Elements>7</Elements>
</ArrayInfo>
</DataType>
<DataType>
<Name>DT1C13</Name>
<BitSize>112</BitSize>
<BitSize>128</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -390,7 +482,7 @@
<SubItem>
<Name>Elements</Name>
<Type>DT1C13ARR</Type>
<BitSize>96</BitSize>
<BitSize>112</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access>ro</Access>
@@ -422,9 +514,34 @@
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT6006</Name>
<BitSize>80</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>ActualPosition</Name>
<Type>LREAL</Type>
<BitSize>64</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access WriteRestrictions="PreOP">ro</Access>
<PdoMapping>T</PdoMapping>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT7002</Name>
<BitSize>144</BitSize>
<BitSize>96</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -448,9 +565,45 @@
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>CommandedVelocity</Name>
<Name>StepsPerMM</Name>
<Type>INT</Type>
<BitSize>16</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access WriteRestrictions="PreOP">ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT7003</Name>
<BitSize>96</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
<Type>USINT</Type>
<BitSize>8</BitSize>
<BitOffs>0</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>1</SubIdx>
<Name>CommandedPosition</Name>
<Type>LREAL</Type>
<BitSize>64</BitSize>
<BitOffs>16</BitOffs>
<Flags>
<Access WriteRestrictions="PreOP">ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>StepsPerMM</Name>
<Type>INT</Type>
<BitSize>16</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access WriteRestrictions="PreOP">ro</Access>
@@ -490,6 +643,14 @@
<Name>DINT</Name>
<BitSize>32</BitSize>
</DataType>
<DataType>
<Name>INT</Name>
<BitSize>16</BitSize>
</DataType>
<DataType>
<Name>BOOL</Name>
<BitSize>1</BitSize>
</DataType>
</DataTypes>
<Objects>
<Object>
@@ -648,9 +809,67 @@
</Info>
</SubItem>
<SubItem>
<Name>CommandedVelocity</Name>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>#x70020240</DefaultValue>
<DefaultValue>#x70020210</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1603</Index>
<Name>StepGenIn2</Name>
<Type>DT1603</Type>
<BitSize>144</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>CommandedPosition</Name>
<Info>
<DefaultValue>#x70030140</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>#x70030210</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1604</Index>
<Name>Enable1</Name>
<Type>DT1604</Type>
<BitSize>144</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Enable1</Name>
<Info>
<DefaultValue>#x70040001</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>Padding 1</Name>
<Info>
<DefaultValue>#x00000007</DefaultValue>
</Info>
</SubItem>
</Info>
@@ -796,6 +1015,29 @@
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1A06</Index>
<Name>StepGenOut2</Name>
<Type>DT1A06</Type>
<BitSize>80</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>ActualPosition</Name>
<Info>
<DefaultValue>#x60060140</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x1C00</Index>
<Name>Sync Manager Communication Type</Name>
@@ -841,12 +1083,12 @@
<Index>#x1C12</Index>
<Name>Sync Manager 2 PDO Assignment</Name>
<Type>DT1C12</Type>
<BitSize>64</BitSize>
<BitSize>96</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>3</DefaultValue>
<DefaultValue>5</DefaultValue>
</Info>
</SubItem>
<SubItem>
@@ -867,6 +1109,18 @@
<DefaultValue>#x1602</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1603</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1604</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
@@ -876,12 +1130,12 @@
<Index>#x1C13</Index>
<Name>Sync Manager 3 PDO Assignment</Name>
<Type>DT1C13</Type>
<BitSize>112</BitSize>
<BitSize>128</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>6</DefaultValue>
<DefaultValue>7</DefaultValue>
</Info>
</SubItem>
<SubItem>
@@ -920,6 +1174,12 @@
<DefaultValue>#x1A05</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Info>
<DefaultValue>#x1A06</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
@@ -1013,6 +1273,29 @@
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x6006</Index>
<Name>StepGenOut2</Name>
<Type>DT6006</Type>
<BitSize>80</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>ActualPosition</Name>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x7000</Index>
<Name>EncPosScale</Name>
@@ -1043,7 +1326,7 @@
<Index>#x7002</Index>
<Name>StepGenIn1</Name>
<Type>DT7002</Type>
<BitSize>144</BitSize>
<BitSize>96</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
@@ -1058,7 +1341,7 @@
</Info>
</SubItem>
<SubItem>
<Name>CommandedVelocity</Name>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
@@ -1068,6 +1351,48 @@
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x7003</Index>
<Name>StepGenIn2</Name>
<Type>DT7003</Type>
<BitSize>96</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>CommandedPosition</Name>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
</Flags>
</Object>
<Object>
<Index>#x7004</Index>
<Name>Enable1</Name>
<Type>BOOL</Type>
<BitSize>1</BitSize>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
<Flags>
<Access>ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</Object>
</Objects>
</Dictionary>
</Profile>
@@ -1113,10 +1438,44 @@
<Entry>
<Index>#x7002</Index>
<SubIndex>#x2</SubIndex>
<BitLen>16</BitLen>
<Name>StepsPerMM</Name>
<DataType>INT</DataType>
</Entry>
</RxPdo>
<RxPdo Fixed="true" Mandatory="true" Sm="2">
<Index>#x1603</Index>
<Name>StepGenIn2</Name>
<Entry>
<Index>#x7003</Index>
<SubIndex>#x1</SubIndex>
<BitLen>64</BitLen>
<Name>CommandedVelocity</Name>
<Name>CommandedPosition</Name>
<DataType>LREAL</DataType>
</Entry>
<Entry>
<Index>#x7003</Index>
<SubIndex>#x2</SubIndex>
<BitLen>16</BitLen>
<Name>StepsPerMM</Name>
<DataType>INT</DataType>
</Entry>
</RxPdo>
<RxPdo Fixed="true" Mandatory="true" Sm="2">
<Index>#x1604</Index>
<Name>Enable1</Name>
<Entry>
<Index>#x7004</Index>
<SubIndex>#x0</SubIndex>
<BitLen>1</BitLen>
<Name>Enable1</Name>
<DataType>BOOL</DataType>
</Entry>
<Entry>
<Index>0</Index>
<SubIndex>0</SubIndex>
<BitLen>7</BitLen>
</Entry>
</RxPdo>
<TxPdo Fixed="true" Mandatory="true" Sm="3">
<Index>#x1A00</Index>
@@ -1184,6 +1543,17 @@
<DataType>LREAL</DataType>
</Entry>
</TxPdo>
<TxPdo Fixed="true" Mandatory="true" Sm="3">
<Index>#x1A06</Index>
<Name>StepGenOut2</Name>
<Entry>
<Index>#x6006</Index>
<SubIndex>#x1</SubIndex>
<BitLen>64</BitLen>
<Name>ActualPosition</Name>
<DataType>LREAL</DataType>
</Entry>
</TxPdo>
<Mailbox DataLinkLayer="true">
<CoE SdoInfo="true" PdoAssign="false" PdoConfig="false" PdoUpload="true" CompleteAccess="false" />
</Mailbox>

View File

@@ -33,8 +33,8 @@
#define SM3_smc 0x20
#define SM3_act 1
#define MAX_MAPPINGS_SM2 4
#define MAX_MAPPINGS_SM3 6
#define MAX_MAPPINGS_SM2 8
#define MAX_MAPPINGS_SM3 7
#define MAX_RXPDO_SIZE 512
#define MAX_TXPDO_SIZE 512

View File

@@ -124,6 +124,26 @@
"pdo_mappings": [
"txpdo"
]
},
"6006": {
"otype": "RECORD",
"name": "StepGenOut2",
"access": "RO",
"items": [
{
"name": "Max SubIndex"
},
{
"name": "ActualPosition",
"dtype": "REAL64",
"data": "&Obj.StepGenOut2.ActualPosition",
"value": "0",
"access": "RO"
}
],
"pdo_mappings": [
"txpdo"
]
}
},
"rxpdo": {
@@ -165,17 +185,55 @@
"access": "RO"
},
{
"name": "CommandedVelocity",
"dtype": "REAL64",
"name": "StepsPerMM",
"dtype": "INTEGER16",
"value": "0",
"access": "RO",
"data": "&Obj.StepGenIn1.CommandedVelocity"
"data": "&Obj.StepGenIn1.StepsPerMM"
}
],
"pdo_mappings": [
"rxpdo"
]
},
"7003": {
"otype": "RECORD",
"name": "StepGenIn2",
"access": "RO",
"items": [
{
"name": "Max SubIndex"
},
{
"name": "CommandedPosition",
"dtype": "REAL64",
"data": "&Obj.StepGenIn2.CommandedPosition",
"value": "0",
"access": "RO"
},
{
"name": "StepsPerMM",
"dtype": "INTEGER16",
"value": "0",
"access": "RO",
"data": "&Obj.StepGenIn2.StepsPerMM"
}
],
"pdo_mappings": [
"rxpdo"
]
},
"7004": {
"otype": "VAR",
"name": "Enable1",
"access": "RO",
"pdo_mappings": [
"rxpdo"
],
"dtype": "BOOLEAN",
"value": "0",
"data": "&Obj.Enable1"
},
"60664": {
"otype": "VAR",
"name": "ActualPosition",

View File

@@ -22,7 +22,15 @@ static const char acName1601_01[] = "IndexLatchEnable";
static const char acName1602[] = "StepGenIn1";
static const char acName1602_00[] = "Max SubIndex";
static const char acName1602_01[] = "CommandedPosition";
static const char acName1602_02[] = "CommandedVelocity";
static const char acName1602_02[] = "StepsPerMM";
static const char acName1603[] = "StepGenIn2";
static const char acName1603_00[] = "Max SubIndex";
static const char acName1603_01[] = "CommandedPosition";
static const char acName1603_02[] = "StepsPerMM";
static const char acName1604[] = "Enable1";
static const char acName1604_00[] = "Max SubIndex";
static const char acName1604_01[] = "Enable1";
static const char acName1604_02[] = "Padding 1";
static const char acName1A00[] = "EncPos";
static const char acName1A00_00[] = "Max SubIndex";
static const char acName1A00_01[] = "EncPos";
@@ -41,6 +49,9 @@ static const char acName1A04_01[] = "IndexStatus";
static const char acName1A05[] = "StepGenOut1";
static const char acName1A05_00[] = "Max SubIndex";
static const char acName1A05_01[] = "ActualPosition";
static const char acName1A06[] = "StepGenOut2";
static const char acName1A06_00[] = "Max SubIndex";
static const char acName1A06_01[] = "ActualPosition";
static const char acName1C00[] = "Sync Manager Communication Type";
static const char acName1C00_00[] = "Max SubIndex";
static const char acName1C00_01[] = "Communications Type SM0";
@@ -52,6 +63,8 @@ static const char acName1C12_00[] = "Max SubIndex";
static const char acName1C12_01[] = "PDO Mapping";
static const char acName1C12_02[] = "PDO Mapping";
static const char acName1C12_03[] = "PDO Mapping";
static const char acName1C12_04[] = "PDO Mapping";
static const char acName1C12_05[] = "PDO Mapping";
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
static const char acName1C13_00[] = "Max SubIndex";
static const char acName1C13_01[] = "PDO Mapping";
@@ -60,6 +73,7 @@ static const char acName1C13_03[] = "PDO Mapping";
static const char acName1C13_04[] = "PDO Mapping";
static const char acName1C13_05[] = "PDO Mapping";
static const char acName1C13_06[] = "PDO Mapping";
static const char acName1C13_07[] = "PDO Mapping";
static const char acName6000[] = "EncPos";
static const char acName6001[] = "EncFrequency";
static const char acName6002[] = "DiffT";
@@ -68,12 +82,20 @@ static const char acName6004[] = "IndexStatus";
static const char acName6005[] = "StepGenOut1";
static const char acName6005_00[] = "Max SubIndex";
static const char acName6005_01[] = "ActualPosition";
static const char acName6006[] = "StepGenOut2";
static const char acName6006_00[] = "Max SubIndex";
static const char acName6006_01[] = "ActualPosition";
static const char acName7000[] = "EncPosScale";
static const char acName7001[] = "IndexLatchEnable";
static const char acName7002[] = "StepGenIn1";
static const char acName7002_00[] = "Max SubIndex";
static const char acName7002_01[] = "CommandedPosition";
static const char acName7002_02[] = "CommandedVelocity";
static const char acName7002_02[] = "StepsPerMM";
static const char acName7003[] = "StepGenIn2";
static const char acName7003_00[] = "Max SubIndex";
static const char acName7003_01[] = "CommandedPosition";
static const char acName7003_02[] = "StepsPerMM";
static const char acName7004[] = "Enable1";
const _objd SDO1000[] =
{
@@ -113,7 +135,19 @@ const _objd SDO1602[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_01, 0x70020140, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_02, 0x70020240, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_02, 0x70020210, NULL},
};
const _objd SDO1603[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_01, 0x70030140, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_02, 0x70030210, NULL},
};
const _objd SDO1604[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1604_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1604_01, 0x70040001, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1604_02, 0x00000007, NULL},
};
const _objd SDO1A00[] =
{
@@ -145,6 +179,11 @@ const _objd SDO1A05[] =
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A05_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A05_01, 0x60050140, NULL},
};
const _objd SDO1A06[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A06_00, 1, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1A06_01, 0x60060140, NULL},
};
const _objd SDO1C00[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
@@ -155,20 +194,23 @@ const _objd SDO1C00[] =
};
const _objd SDO1C12[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 3, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 5, NULL},
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_03, 0x1602, NULL},
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_04, 0x1603, NULL},
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_05, 0x1604, NULL},
};
const _objd SDO1C13[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 6, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 7, NULL},
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_02, 0x1A01, NULL},
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_03, 0x1A02, NULL},
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_04, 0x1A03, NULL},
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_05, 0x1A04, NULL},
{0x06, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_06, 0x1A05, NULL},
{0x07, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_07, 0x1A06, NULL},
};
const _objd SDO6000[] =
{
@@ -195,6 +237,11 @@ const _objd SDO6005[] =
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6005_00, 1, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName6005_01, 0, &Obj.StepGenOut1.ActualPosition},
};
const _objd SDO6006[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6006_00, 1, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName6006_01, 0, &Obj.StepGenOut2.ActualPosition},
};
const _objd SDO7000[] =
{
{0x0, DTYPE_INTEGER32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.EncPosScale},
@@ -207,7 +254,17 @@ const _objd SDO7002[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 2, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7002_01, 0, &Obj.StepGenIn1.CommandedPosition},
{0x02, DTYPE_REAL64, 64, ATYPE_RO, acName7002_02, 0, &Obj.StepGenIn1.CommandedVelocity},
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7002_02, 0, &Obj.StepGenIn1.StepsPerMM},
};
const _objd SDO7003[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7003_00, 2, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7003_01, 0, &Obj.StepGenIn2.CommandedPosition},
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7003_02, 0, &Obj.StepGenIn2.StepsPerMM},
};
const _objd SDO7004[] =
{
{0x0, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7004, 0, &Obj.Enable1},
};
const _objectlist SDOobjects[] =
@@ -220,23 +277,29 @@ const _objectlist SDOobjects[] =
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
{0x1602, OTYPE_RECORD, 2, 0, acName1602, SDO1602},
{0x1603, OTYPE_RECORD, 2, 0, acName1603, SDO1603},
{0x1604, OTYPE_RECORD, 2, 0, acName1604, SDO1604},
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
{0x1A03, OTYPE_RECORD, 1, 0, acName1A03, SDO1A03},
{0x1A04, OTYPE_RECORD, 1, 0, acName1A04, SDO1A04},
{0x1A05, OTYPE_RECORD, 1, 0, acName1A05, SDO1A05},
{0x1A06, OTYPE_RECORD, 1, 0, acName1A06, SDO1A06},
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
{0x1C12, OTYPE_ARRAY, 3, 0, acName1C12, SDO1C12},
{0x1C13, OTYPE_ARRAY, 6, 0, acName1C13, SDO1C13},
{0x1C12, OTYPE_ARRAY, 5, 0, acName1C12, SDO1C12},
{0x1C13, OTYPE_ARRAY, 7, 0, acName1C13, SDO1C13},
{0x6000, OTYPE_VAR, 0, 0, acName6000, SDO6000},
{0x6001, OTYPE_VAR, 0, 0, acName6001, SDO6001},
{0x6002, OTYPE_VAR, 0, 0, acName6002, SDO6002},
{0x6003, OTYPE_VAR, 0, 0, acName6003, SDO6003},
{0x6004, OTYPE_VAR, 0, 0, acName6004, SDO6004},
{0x6005, OTYPE_RECORD, 1, 0, acName6005, SDO6005},
{0x6006, OTYPE_RECORD, 1, 0, acName6006, SDO6006},
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
{0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002},
{0x7003, OTYPE_RECORD, 2, 0, acName7003, SDO7003},
{0x7004, OTYPE_VAR, 0, 0, acName7004, SDO7004},
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
};

View File

@@ -22,6 +22,10 @@ typedef struct
{
double ActualPosition;
} StepGenOut1;
struct
{
double ActualPosition;
} StepGenOut2;
/* Outputs */
@@ -30,8 +34,14 @@ typedef struct
struct
{
double CommandedPosition;
double CommandedVelocity;
int16_t StepsPerMM;
} StepGenIn1;
struct
{
double CommandedPosition;
int16_t StepsPerMM;
} StepGenIn2;
uint8_t Enable1;
} _Objects;

94
Firmware/src/MyEncoder.cpp Executable file
View File

@@ -0,0 +1,94 @@
#include "MyENcoder.h"
MyEncoder::MyEncoder(TIM_TypeDef *_tim_base, uint8_t _indexPin, void irq(void))
{
tim_base = _tim_base;
indexPin = _indexPin;
attachInterrupt(digitalPinToInterrupt(indexPin), irq, RISING); // When Index triggered
EncoderInit.SetCount(0);
}
#define ONE_PERIOD 65536
#define HALF_PERIOD 32768
int64_t MyEncoder::unwrapEncoder(uint16_t in)
{
int32_t c32 = (int32_t)in - HALF_PERIOD; // remove half period to determine (+/-) sign of the wrap
int32_t dif = (c32 - previousEncoderCounterValue); // core concept: prev + (current - prev) = current
// wrap difference from -HALF_PERIOD to HALF_PERIOD. modulo prevents differences after the wrap from having an incorrect result
int32_t mod_dif = ((dif + HALF_PERIOD) % ONE_PERIOD) - HALF_PERIOD;
if (dif < -HALF_PERIOD)
mod_dif += ONE_PERIOD; // account for mod of negative number behavior in C
int64_t unwrapped = previousEncoderCounterValue + mod_dif;
previousEncoderCounterValue = unwrapped; // load previous value
return unwrapped + HALF_PERIOD; // remove the shift we applied at the beginning, and return
}
void MyEncoder::indexPulse(void)
{
if (pleaseZeroTheCounter)
{
tim_base->CNT = 0;
indexPulseFired = 1;
Pos.clear();
TDelta.clear();
pleaseZeroTheCounter = 0;
}
}
uint8_t MyEncoder::indexHappened()
{
if (indexPulseFired)
{
indexPulseFired = 0;
previousEncoderCounterValue = 0;
return 1;
}
return 0;
}
double MyEncoder::currentPos()
{
curPos = unwrapEncoder(tim_base->CNT) * PosScaleRes;
return curPos;
}
double MyEncoder::frequency(uint64_t time)
{
double diffT = 0;
double diffPos = 0;
TDelta.push(time); // Running average over the length of the circular buffer
Pos.push(curPos);
if (Pos.size() >= 2)
{
diffT = 1.0e-9 * (TDelta.last() - TDelta.first()); // Time is in nanoseconds
diffPos = fabs(Pos.last() - Pos.first());
}
return diffT != 0 ? diffPos / diffT : 0.0; // Revolutions per second
}
uint8_t MyEncoder::getIndexState()
{
return digitalRead(indexPin);
}
void MyEncoder::setScale(double scale)
{
if (CurPosScale != scale && scale != 0)
{
CurPosScale = scale;
PosScaleRes = 1.0 / double(scale);
}
}
void MyEncoder::setLatch(uint8_t latchEnable)
{
if (latchEnable && !oldLatchCEnable) // Should only happen first time IndexCEnable is set
{
pleaseZeroTheCounter = 1;
}
oldLatchCEnable = latchEnable;
}

148
Firmware/src/StepGen.cpp Executable file
View File

@@ -0,0 +1,148 @@
#include <Arduino.h>
#include <stdio.h>
#include "StepGen.h"
StepGen::StepGen(TIM_TypeDef *Timer, uint32_t _timerChannel, PinName _stepPin, uint8_t _dirPin, void irq(void))
{
timerIsRunning = 0;
timerStepPosition = 0;
timerStepDirection = 0;
timerStepPositionAtEnd = 0;
timerNewEndStepPosition = 0;
actualPosition = 0;
requestedPosition = 0;
stepsPerMM = 0;
enabled = 0;
dirPin = _dirPin;
stepPin = _stepPin;
timerChan = _timerChannel;
MyTim = new HardwareTimer(Timer);
MyTim->attachInterrupt(irq);
pinMode(dirPin, OUTPUT);
}
void StepGen::reqPos(double_t pos)
{
requestedPosition = pos;
}
double StepGen::reqPos()
{
return requestedPosition;
}
void StepGen::actPos(double pos)
{
actualPosition = pos;
}
double StepGen::actPos()
{
return actualPosition;
}
void StepGen::enable(uint8_t yes)
{
enabled = yes;
}
void StepGen::handleStepper(void)
{
if (!enabled)
return;
pwmCycleTime = StepGen::sync0CycleTime;
actPos(timerStepPosition / double(stepsPerMM));
double diffPosition = reqPos() - actPos();
#if 1
// Wild "tone" kludge. map() function
#define SPEED_MIN 0.00005
#define SPEED_MAX 0.0005
#define FACT_LOW 1.0
#define FACT_HIGH 20.0
if (abs(diffPosition) < SPEED_MIN) // 60 mm/min = 0.001 mm/ms
{
pwmCycleTime = FACT_LOW * StepGen::sync0CycleTime;
}
else if (abs(diffPosition) > SPEED_MAX) // 60 mm/min = 0.001 mm/ms
{
pwmCycleTime = FACT_HIGH * StepGen::sync0CycleTime;
}
else
{
pwmCycleTime = (FACT_LOW + (FACT_HIGH - FACT_LOW) * (abs(diffPosition) - SPEED_MIN) / (SPEED_MAX - SPEED_MIN)) * StepGen::sync0CycleTime;
}
#endif
uint64_t fre = (abs(diffPosition) * stepsPerMM * 1000000) / pwmCycleTime; // Frequency needed
if (fre > maxFreq) // Only do maxFre
{
double maxDist = (maxFreq * pwmCycleTime) / (stepsPerMM * 1000000.0) * (diffPosition > 0 ? 1 : -1);
reqPos(actPos() + maxDist);
}
int32_t pulsesAtEndOfCycle = stepsPerMM * reqPos();
// Will be picked up by the timer_CB and the timer is reloaded, if it runs.
timerNewEndStepPosition = pulsesAtEndOfCycle;
if (!timerIsRunning) // Timer isn't running. Start it here
{
int32_t steps = pulsesAtEndOfCycle - timerStepPosition; // Pulses to go + or -
if (steps != 0)
{
if (steps > 0)
{
digitalWrite(dirPin, HIGH);
timerStepDirection = 1;
}
else
{
digitalWrite(dirPin, LOW);
timerStepDirection = -1;
}
timerStepPositionAtEnd = pulsesAtEndOfCycle; // Current Position
float_t freqf = abs(steps) / (pwmCycleTime*1.0e-6);
uint32_t freq = uint32_t(freqf);
MyTim->setMode(timerChan, TIMER_OUTPUT_COMPARE_PWM2, stepPin);
MyTim->setOverflow(freq, HERTZ_FORMAT);
MyTim->setCaptureCompare(timerChan, 50, PERCENT_COMPARE_FORMAT); // 50 %
timerIsRunning = 1;
MyTim->resume();
}
}
}
void StepGen::timerCB()
{
timerStepPosition += timerStepDirection; // The step that was just completed
if (timerNewEndStepPosition != 0) // Are we going to reload?
{
// Input for reload is timerNewEndStepPosition
// The timer has current position and from this
// can set new frequency and new endtarget for steps
MyTim->pause(); // We are not at stop, let's stop it. Note stepPin is floating
int32_t steps = timerNewEndStepPosition - timerStepPosition;
if (steps != 0)
{
uint8_t sgn = steps > 0 ? HIGH : LOW;
digitalWrite(dirPin, sgn);
float_t freqf = abs(steps) / float(pwmCycleTime*1.0e-6);
uint32_t freq = uint32_t(freqf);
timerStepDirection = steps > 0 ? 1 : -1;
timerStepPositionAtEnd = timerNewEndStepPosition;
timerNewEndStepPosition = 0; // Set to zero to not reload next time
MyTim->setMode(timerChan, TIMER_OUTPUT_COMPARE_PWM2, stepPin);
MyTim->setOverflow(freq, HERTZ_FORMAT);
MyTim->setCaptureCompare(timerChan, 50, PERCENT_COMPARE_FORMAT); // 50 %
MyTim->resume();
timerIsRunning = 1;
}
}
if (timerStepPosition == timerStepPositionAtEnd) // Are we finished?
{
timerIsRunning = 0;
MyTim->pause();
}
}
void StepGen::setScale(int16_t spm)
{
stepsPerMM = spm;
}
uint32_t StepGen::sync0CycleTime = 0;

View File

@@ -5,45 +5,21 @@
Created on: Nov 20, 2020
Author: GoktugH.
*/
// TIM2, TIM3, TIM4, TIM8
Encoder::Encoder()
{
int unit;
}
void Encoder::eattach(int enco)
// void Encoder::SetCount(enum EncTimer enc, int64_t Counter)
void Encoder::SetCount(int64_t Counter)
{
tim_base->CNT = Counter;
}
void Encoder::attachh(int encoNumber)
// uint16_t Encoder::GetCount(enum EncTimer enc)
uint16_t Encoder::GetCount()
{
eattach(encoNumber);
}
void Encoder::SetCount(enum EncTimer enc, int64_t Counter)
{
if (enc == Tim2)
TIM2->CNT = Counter;
else if (enc == Tim3)
TIM3->CNT = Counter;
else if (enc == Tim4)
TIM4->CNT = Counter;
else if (enc == Tim8)
TIM8->CNT = Counter;
}
uint16_t Encoder::GetCount(enum EncTimer enc)
{
if (enc == Tim2)
c = (TIM2->CNT);
else if (enc == Tim3)
c = (TIM3->CNT);
else if (enc == Tim4)
c = (TIM4->CNT);
else if (enc == Tim8)
c = (TIM8->CNT);
return c;
return tim_base->CNT;
}
void GpioConfigPortA(GPIO_TypeDef *GPIOx)
@@ -295,27 +271,27 @@ void rcc_config()
RCC->AHB1ENR |= 0x10; // GPIOE
RCC->APB1ENR |= 0x20000000; // ENABLE DAC
RCC->APB2ENR |= 0x00000002; // APB2 TIM8
// RCC->APB2ENR |= 0x00000002; // APB2 TIM8
RCC->APB1ENR |= 0x00000004; // APB1 TIM4
RCC->APB1ENR |= 0x00000001; // APB1 TIM2
RCC->APB1ENR |= 0x00000002; // APB1 TIM3
// RCC->APB1ENR |= 0x00000002; // APB1 TIM3
GpioConfigPortA(GPIOA);
GpioConfigPortC(GPIOC);
// GpioConfigPortC(GPIOC);
GpioConfigPortD(GPIOD);
#if 0 // Skipping since TIM8 is step generator and TIM3, chan4 is smae as TIM8, chan4
GPIO_PinAF(GPIOA, GPIO_PinSource6, GPIO_AF_TIM3);
GPIO_PinAF(GPIOA, GPIO_PinSource7, GPIO_AF_TIM3);
GPIO_PinAF(GPIOC, GPIO_PinSource6, GPIO_AF_TIM8);
GPIO_PinAF(GPIOC, GPIO_PinSource7, GPIO_AF_TIM8);
#endif
GPIO_PinAF(GPIOD, GPIO_PinSource12, GPIO_AF_TIM4);
GPIO_PinAF(GPIOD, GPIO_PinSource13, GPIO_AF_TIM4);
GPIO_PinAF(GPIOA, GPIO_PinSource0, GPIO_AF_TIM2);
GPIO_PinAF(GPIOA, GPIO_PinSource1, GPIO_AF_TIM2);
#if 0 // Skipping since I use TIM8 as stepper generator
TIM_EncoderInterConfig(TIM8, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Falling);
TIMER_InitStructure.TIM_Period = 65535;
TIMER_InitStructure.TIM_CounterMode = TIM_CounterMode_Up | TIM_CounterMode_Down;
@@ -323,7 +299,7 @@ void rcc_config()
TIM_TimeBaseStructInit(&TIMER_InitStructure);
TIM_Cmd(TIM8, ENABLE);
TIM8->CNT = 0;
#endif
TIM_EncoderInterConfig(TIM4, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Falling);
TIMER_InitStructureE.TIM_Period = 65535;
TIMER_InitStructureE.TIM_CounterMode = TIM_CounterMode_Up | TIM_CounterMode_Down;
@@ -340,7 +316,7 @@ void rcc_config()
TIM_Cmd(TIM2, ENABLE);
TIM2->CNT = 0;
#if 0
TIM_EncoderInterConfig(TIM3, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Falling);
TIMER_InitStructureEEG.TIM_Period = 65535;
TIMER_InitStructureEEG.TIM_CounterMode = TIM_CounterMode_Up | TIM_CounterMode_Down;
@@ -349,4 +325,5 @@ void rcc_config()
TIM_Cmd(TIM3, ENABLE);
TIM3->CNT = 0;
#endif
}

View File

@@ -1,102 +1,90 @@
#include <Arduino.h>
#include <HardwareTimer.h>
#include <stdio.h>
extern "C"
{
#include "ecat_slv.h"
#include "utypes.h"
};
#include <CircularBuffer.h>
#define RINGBUFFERLEN 101
CircularBuffer<double_t, RINGBUFFERLEN> Pos;
CircularBuffer<uint32_t, RINGBUFFERLEN> TDelta;
#include <Stm32F4_Encoder.h>
int64_t PreviousEncoderCounterValue = 0;
int64_t unwrap_encoder(uint16_t in, int64_t *prev);
Encoder EncoderInit;
Encoder *encP = &EncoderInit;
#define INDEX_PIN PA2
HardwareSerial Serial1(PA10, PA9);
_Objects Obj;
void indexPulse(void);
double PosScaleRes = 1.0;
uint32_t CurPosScale = 1;
uint8_t OldLatchCEnable = 0;
volatile uint8_t indexPulseFired = 0;
uint32_t nFires = 0;
volatile uint8_t pleaseZeroTheCounter = 0;
HardwareSerial Serial1(PA10, PA9);
#define STEPPER_DIR_PIN PA12
#define STEPPER_STEP_PIN PA11
HardwareTimer *MyTim;
volatile uint32_t stepCount = 0, stepPulses = 0;
volatile double_t actualPosition = 0;
volatile double_t requestedPosition, requestedVelocity;
#define DEBUG_TIM8 1
#include "MyEncoder.h"
void indexPulseEncoderCB1(void);
MyEncoder Encoder1(TIM2, PA2, indexPulseEncoderCB1);
void indexPulseEncoderCB1(void)
{
Encoder1.indexPulse();
}
uint32_t sync0CycleTime = 0;
#include "StepGen.h"
void handleStepper(void);
void makePulses(uint32_t period /* in usecs */, int32_t pulses /* nr of pulses to do*/);
void timerCallbackStep1(void);
StepGen Step1(TIM1, 4, PA_11, PA12, timerCallbackStep1);
void timerCallbackStep1(void)
{
Step1.timerCB();
}
void timerCallbackStep2(void);
StepGen Step2(TIM3, 4, PC_9, PC10, timerCallbackStep2);
void timerCallbackStep2(void)
{
Step2.timerCB();
}
CircularBuffer<uint32_t, 200> Tim;
volatile uint64_t nowTime = 0, thenTime = 0;
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
{
if (Obj.IndexLatchEnable && !OldLatchCEnable) // Should only happen first time IndexCEnable is set
{
pleaseZeroTheCounter = 1;
}
OldLatchCEnable = Obj.IndexLatchEnable;
Encoder1.setLatch(Obj.IndexLatchEnable);
Encoder1.setScale(Obj.EncPosScale);
if (CurPosScale != Obj.EncPosScale && Obj.EncPosScale != 0)
{
CurPosScale = Obj.EncPosScale;
PosScaleRes = 1.0 / double(CurPosScale);
}
requestedPosition = Obj.StepGenIn1.CommandedPosition;
requestedVelocity = Obj.StepGenIn1.CommandedVelocity;
Step1.reqPos(Obj.StepGenIn1.CommandedPosition);
Step1.setScale(Obj.StepGenIn1.StepsPerMM);
Step1.enable(Obj.Enable1);
Step2.reqPos(Obj.StepGenIn2.CommandedPosition);
Step2.setScale(Obj.StepGenIn2.StepsPerMM);
Step2.enable(Obj.Enable1);
}
void handleStepper(void)
{
Step1.handleStepper();
Step2.handleStepper();
}
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
{
Obj.IndexStatus = 0;
if (indexPulseFired)
Obj.IndexStatus = Encoder1.indexHappened();
Obj.EncPos = Encoder1.currentPos();
Obj.EncFrequency = Encoder1.frequency(ESCvar.Time);
Obj.IndexByte = Encoder1.getIndexState();
Obj.StepGenOut1.ActualPosition = Step1.actPos();
Obj.StepGenOut2.ActualPosition = Step2.actPos();
uint32_t dTim = nowTime - thenTime; // Debug. Getting jitter over the last 200 milliseconds
Tim.push(dTim);
uint32_t max_Tim = 0, min_Tim = UINT32_MAX;
for (decltype(Tim)::index_t i = 0; i < Tim.size(); i++)
{
Obj.IndexStatus = 1;
indexPulseFired = 0;
nFires++;
PreviousEncoderCounterValue = 0;
uint32_t aTim = Tim[i];
if (aTim > max_Tim)
max_Tim = aTim;
if (aTim < min_Tim)
min_Tim = aTim;
}
// Obj.DiffT = sync0CycleTime;
int64_t pos = unwrap_encoder(TIM2->CNT, &PreviousEncoderCounterValue);
double CurPos = pos * PosScaleRes;
Obj.EncPos = CurPos;
double diffT = 0;
double diffPos = 0;
TDelta.push(ESCvar.Time); // Running average over the length of the circular buffer
Pos.push(CurPos);
if (Pos.size() >= 2)
{
diffT = 1.0e-9 * (TDelta.last() - TDelta.first()); // Time is in nanoseconds
diffPos = fabs(Pos.last() - Pos.first());
}
Obj.EncFrequency = diffT != 0 ? diffPos / diffT : 0.0; // Revolutions per second
Obj.IndexByte = digitalRead(INDEX_PIN);
if (Obj.IndexByte)
Serial1.printf("IS 1\n");
Obj.StepGenOut1.ActualPosition = actualPosition;
Obj.DiffT = 10000 * requestedPosition; // deltaT;
thenTime = nowTime;
Obj.DiffT = max_Tim - min_Tim; // Debug
}
void ESC_interrupt_enable(uint32_t mask);
void ESC_interrupt_disable(uint32_t mask);
uint16_t dc_checker(void);
void sync0Handler(void);
static esc_cfg_t config =
{
@@ -106,7 +94,7 @@ static esc_cfg_t config =
.set_defaults_hook = NULL,
.pre_state_change_hook = NULL,
.post_state_change_hook = NULL,
.application_hook = handleStepper, // StepGen,
.application_hook = handleStepper,
.safeoutput_override = NULL,
.pre_object_download_hook = NULL,
.post_object_download_hook = NULL,
@@ -118,90 +106,28 @@ static esc_cfg_t config =
.esc_check_dc_handler = dc_checker,
};
void TimerStep_CB(void)
{
stepCount++;
if (stepCount == stepPulses)
{
MyTim->pause();
}
}
volatile byte serveIRQ = 0;
void makePulses(uint32_t period /* in usecs */, int32_t pulses /* nr of pulses to do*/)
{
byte sgn = pulses > 0 ? HIGH : LOW;
digitalWrite(STEPPER_DIR_PIN, sgn); // I think one should really wait a bit when changed
uint32_t puls = abs(pulses);
MyTim->setOverflow(abs(pulses) * 1000000 / period, HERTZ_FORMAT);
MyTim->setCaptureCompare(4, 50, PERCENT_COMPARE_FORMAT); // 50 %
stepCount = 0;
stepPulses = abs(pulses);
MyTim->resume();
}
void sync0Handler(void);
void setup(void)
{
Serial1.begin(115200);
rcc_config();
TIM_TypeDef *Instance = TIM1;
MyTim = new HardwareTimer(Instance);
MyTim->setMode(4, TIMER_OUTPUT_COMPARE_PWM2, STEPPER_STEP_PIN);
MyTim->attachInterrupt(TimerStep_CB);
pinMode(STEPPER_DIR_PIN, OUTPUT);
// Set starting count value
EncoderInit.SetCount(Tim2, 0);
attachInterrupt(digitalPinToInterrupt(INDEX_PIN), indexPulse, RISING); // Always when Index triggered
// EncoderInit.SetCount(Tim3, 0);
// EncoderInit.SetCount(Tim4, 0);
// EncoderInit.SetCount(Tim8, 0);
rcc_config(); // probably breaks some timers.
ecat_slv_init(&config);
}
volatile byte serveIRQ = 0;
void loop(void)
{
ESCvar.PrevTime = ESCvar.Time;
if (serveIRQ)
{
nowTime = micros();
DIG_process(DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
serveIRQ = 0;
ESCvar.PrevTime = ESCvar.Time;
}
ecat_slv_poll();
}
#define ONE_PERIOD 65536
#define HALF_PERIOD 32768
int64_t unwrap_encoder(uint16_t in, int64_t *prev)
{
int64_t c64 = (int32_t)in - HALF_PERIOD; // remove half period to determine (+/-) sign of the wrap
int64_t dif = (c64 - *prev); // core concept: prev + (current - prev) = current
// wrap difference from -HALF_PERIOD to HALF_PERIOD. modulo prevents differences after the wrap from having an incorrect result
int64_t mod_dif = ((dif + HALF_PERIOD) % ONE_PERIOD) - HALF_PERIOD;
if (dif < -HALF_PERIOD)
mod_dif += ONE_PERIOD; // account for mod of negative number behavior in C
int64_t unwrapped = *prev + mod_dif;
*prev = unwrapped; // load previous value
return unwrapped + HALF_PERIOD; // remove the shift we applied at the beginning, and return
}
void indexPulse(void)
{
if (pleaseZeroTheCounter)
{
TIM2->CNT = 0;
indexPulseFired = 1;
Pos.clear();
TDelta.clear();
pleaseZeroTheCounter = 0;
}
uint32_t dTime = micros() - nowTime;
if ((dTime > 200 && dTime < 500) || dTime > 1500) // Don't run ecat_slv_poll when expecting to serve interrupt
ecat_slv_poll();
}
void sync0Handler(void)
@@ -209,21 +135,11 @@ void sync0Handler(void)
serveIRQ = 1;
}
void handleStepper(void)
{
byte forwardDirection = 0; // 1 if going forward
int32_t pulsesToGo = 100 * (requestedPosition - actualPosition);
if (pulsesToGo != 0)
makePulses(900, pulsesToGo); // Make the pulses using hardware timer
actualPosition = requestedPosition;
}
void ESC_interrupt_enable(uint32_t mask)
{
// Enable interrupt for SYNC0 or SM2 or SM3
uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 |
ESCREG_ALEVENT_SM2 |
ESCREG_ALEVENT_SM3;
// uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 | ESCREG_ALEVENT_SM2 | ESCREG_ALEVENT_SM3;
uint32_t user_int_mask = ESCREG_ALEVENT_SM2; // Only SM2
if (mask & user_int_mask)
{
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
@@ -242,9 +158,8 @@ void ESC_interrupt_enable(uint32_t mask)
void ESC_interrupt_disable(uint32_t mask)
{
// Enable interrupt for SYNC0 or SM2 or SM3
uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 |
ESCREG_ALEVENT_SM2 |
ESCREG_ALEVENT_SM3;
// uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 | ESCREG_ALEVENT_SM2 | ESCREG_ALEVENT_SM3;
uint32_t user_int_mask = ESCREG_ALEVENT_SM2;
if (mask & user_int_mask)
{
@@ -258,11 +173,12 @@ void ESC_interrupt_disable(uint32_t mask)
}
extern "C" uint32_t ESC_SYNC0cycletime(void);
// Setup of DC
uint16_t dc_checker(void)
{
// Indicate we run DC
ESCvar.dcsync = 0;
sync0CycleTime = ESC_SYNC0cycletime();
ESCvar.dcsync = 1;
StepGen::sync0CycleTime = ESC_SYNC0cycletime() / 1000; // usecs
return 0;
}

View File

@@ -1,3 +1,14 @@
AX58100-stm32-ethercat-backups
.~lock*
fp-info-cache
\#auto_saved_file*
gerbers/
Ax58100-stm32-ethercat-backups/
freerouting.*
*.dsn
*.frb
*.rules
*.ses
Ax58100-stm32-ethercat.csv
Ax58100-stm32-ethercat.ods

View File

@@ -4,6 +4,10 @@
(paper "A4")
(title_block
(title "MetalMusings EaserCAT 3000")
)
(lib_symbols
(symbol "Device:C" (pin_numbers hide) (pin_names (offset 0.254)) (in_bom yes) (on_board yes)
(property "Reference" "C" (at 0.635 2.54 0)
@@ -883,6 +887,9 @@
(junction (at 153.67 76.2) (diameter 0) (color 0 0 0 0)
(uuid 1d94dd01-6dce-414e-82ad-3ac082fe20b1)
)
(junction (at 37.465 106.68) (diameter 0) (color 0 0 0 0)
(uuid 1f401ea1-91c2-4b1c-8946-0cebb61cc079)
)
(junction (at 241.3 125.73) (diameter 0) (color 0 0 0 0)
(uuid 24742ea1-03d5-4527-95f5-a7eea04d187b)
)
@@ -1077,10 +1084,6 @@
(stroke (width 0) (type default))
(uuid 329bb402-dfdb-48ca-96e4-cd8113da5fed)
)
(wire (pts (xy 44.45 106.68) (xy 59.69 106.68))
(stroke (width 0) (type default))
(uuid 34f3e2b5-6955-4782-bb5a-a609e45555c8)
)
(wire (pts (xy 44.45 66.04) (xy 59.69 66.04))
(stroke (width 0) (type default))
(uuid 3ec5c533-9953-4224-b74b-0735dd26a008)
@@ -1105,7 +1108,7 @@
(stroke (width 0) (type default))
(uuid 47db0b49-0009-4a05-8b96-6b8f84d107d5)
)
(wire (pts (xy 44.45 101.6) (xy 59.69 101.6))
(wire (pts (xy 52.07 101.6) (xy 59.69 101.6))
(stroke (width 0) (type default))
(uuid 4d357d9e-d279-48fb-988a-f7a606aaaceb)
)
@@ -1269,7 +1272,7 @@
(stroke (width 0) (type default))
(uuid 9585e42b-254e-4035-872d-73149242942a)
)
(wire (pts (xy 44.45 104.14) (xy 59.69 104.14))
(wire (pts (xy 52.07 104.14) (xy 59.69 104.14))
(stroke (width 0) (type default))
(uuid 980d2c40-5368-442a-bca9-5b05633779dc)
)
@@ -1297,6 +1300,10 @@
(stroke (width 0) (type default))
(uuid a8f7bd69-6ca5-40d2-94f6-95e3f5e577ec)
)
(wire (pts (xy 33.02 106.68) (xy 37.465 106.68))
(stroke (width 0) (type default))
(uuid ab06e9f6-751e-4e57-8ad8-4e32f30960c6)
)
(wire (pts (xy 128.27 81.28) (xy 121.92 81.28))
(stroke (width 0) (type default))
(uuid ac3cbfb3-166c-465f-abf3-8aa52050d758)
@@ -1329,6 +1336,10 @@
(stroke (width 0) (type default))
(uuid bc9e0b10-af0b-4c3d-ac1d-d925f4391c1b)
)
(wire (pts (xy 37.465 106.68) (xy 59.69 106.68))
(stroke (width 0) (type default))
(uuid bcc30d1c-f679-4fb9-93ef-8f4572d2ba2f)
)
(wire (pts (xy 53.34 86.36) (xy 59.69 86.36))
(stroke (width 0) (type default))
(uuid be5e8aa3-0c6a-4679-a6c3-2d7b538935e0)
@@ -1541,10 +1552,10 @@
(effects (font (size 1.27 1.27)) (justify left) hide)
)
)
(global_label "SPI_MOSI" (shape input) (at 44.45 101.6 180) (fields_autoplaced)
(global_label "SPI_MOSI" (shape input) (at 52.07 101.6 180) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify right))
(uuid 5584513c-826f-4b8d-805f-97d18e92e5c9)
(property "Intersheetrefs" "${INTERSHEET_REFS}" (at 32.8167 101.6 0)
(property "Intersheetrefs" "${INTERSHEET_REFS}" (at 40.4367 101.6 0)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
)
@@ -1569,10 +1580,10 @@
(effects (font (size 1.27 1.27)) (justify left) hide)
)
)
(global_label "SCS_FUNC" (shape input) (at 44.45 106.68 180) (fields_autoplaced)
(global_label "SCS_FUNC" (shape input) (at 33.02 106.68 180) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify right))
(uuid 7e0714f5-2bf0-4368-8a15-1f7b363302fe)
(property "Intersheetrefs" "${INTERSHEET_REFS}" (at 31.7886 106.68 0)
(property "Intersheetrefs" "${INTERSHEET_REFS}" (at 20.3586 106.68 0)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
)
@@ -1583,10 +1594,10 @@
(effects (font (size 1.27 1.27)) (justify right) hide)
)
)
(global_label "SPI_CS" (shape input) (at 44.45 104.14 180) (fields_autoplaced)
(global_label "SPI_CS" (shape input) (at 52.07 104.14 180) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify right))
(uuid 88863808-4577-46ee-a6dc-85331fa7a41f)
(property "Intersheetrefs" "${INTERSHEET_REFS}" (at 34.9334 104.14 0)
(property "Intersheetrefs" "${INTERSHEET_REFS}" (at 42.5534 104.14 0)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
)
@@ -1777,7 +1788,7 @@
(symbol (lib_id "Device:C") (at 87.63 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 103155a9-e700-4183-b756-a6fc8ca57bcd)
(property "Reference" "C17" (at 87.63 162.56 0)
(property "Reference" "C47" (at 87.63 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 87.63 167.64 0)
@@ -1794,7 +1805,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C17") (unit 1)
(reference "C47") (unit 1)
)
)
)
@@ -1803,7 +1814,7 @@
(symbol (lib_id "Device:Crystal_GND24") (at 227.33 34.29 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 115ef340-5699-4045-a27b-e4216819b835)
(property "Reference" "Y1" (at 227.33 34.29 0)
(property "Reference" "Y2" (at 227.33 34.29 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "NXK25.000AE12F-KAB6-12" (at 228.6 27.94 0)
@@ -1822,7 +1833,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "Y1") (unit 1)
(reference "Y2") (unit 1)
)
)
)
@@ -1831,7 +1842,7 @@
(symbol (lib_id "Device:C") (at 237.49 39.37 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 11d5ea8f-3a28-42fa-b01d-beb1a86a57de)
(property "Reference" "C12" (at 240.411 38.1579 0)
(property "Reference" "C51" (at 240.411 38.1579 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "18pF" (at 240.411 40.5821 0)
@@ -1848,7 +1859,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C12") (unit 1)
(reference "C51") (unit 1)
)
)
)
@@ -1885,7 +1896,7 @@
(symbol (lib_id "HakansLibrary:AX58100") (at 139.7 134.62 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 151decbc-1b66-4082-88a8-6da1bb3d9015)
(property "Reference" "U2" (at 91.44 83.82 0)
(property "Reference" "U10" (at 91.44 83.82 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "AX58100" (at 139.7 134.62 0)
@@ -1981,7 +1992,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "U2") (unit 1)
(reference "U10") (unit 1)
)
)
)
@@ -2015,6 +2026,38 @@
)
)
(symbol (lib_id "Device:R") (at 37.465 102.87 0) (mirror x) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 19d42dc4-fd87-4164-bac8-0603985804da)
(property "Reference" "R46" (at 37.465 102.87 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4k7" (at 34.925 102.87 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0603_1608Metric" (at 35.687 102.87 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (at 37.465 102.87 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid 421d68b0-205a-407e-a601-90c4e8fac9f1))
(pin "2" (uuid 3fb62006-6df3-4595-8d3f-4992742be454))
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/d564400f-40ba-4aca-9c2a-14ec52a8353b"
(reference "R46") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/0a376a6c-0f15-42f8-81f6-3a55619be267"
(reference "R2") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R42") (unit 1)
)
)
)
)
(symbol (lib_id "power:GND") (at 147.32 168.91 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 21e7ff22-3038-45da-a38c-8a0064bd7007)
@@ -2121,7 +2164,7 @@
(symbol (lib_id "Device:C") (at 132.08 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 28999b48-7a3f-4a2d-8295-808981bd0f46)
(property "Reference" "C30" (at 132.08 162.56 0)
(property "Reference" "C24" (at 132.08 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 132.08 167.64 0)
@@ -2138,7 +2181,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C30") (unit 1)
(reference "C24") (unit 1)
)
)
)
@@ -2175,7 +2218,7 @@
(symbol (lib_id "Device:R") (at 80.01 127 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 32075a8b-69da-4a9b-bc51-4abd88b43499)
(property "Reference" "R30" (at 80.01 127 90)
(property "Reference" "R43" (at 80.01 127 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "22" (at 78.74 124.46 90)
@@ -2192,7 +2235,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R30") (unit 1)
(reference "R43") (unit 1)
)
)
)
@@ -2332,7 +2375,7 @@
(symbol (lib_id "Device:R") (at 52.07 60.96 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 45a449d5-9134-41f8-aaba-983731aca91e)
(property "Reference" "R40" (at 52.07 60.96 90)
(property "Reference" "R47" (at 52.07 60.96 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "22" (at 54.61 59.69 90)
@@ -2349,7 +2392,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R40") (unit 1)
(reference "R47") (unit 1)
)
)
)
@@ -2358,7 +2401,7 @@
(symbol (lib_id "Device:C") (at 154.94 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 4693cf1a-5c81-4dfd-8a56-8dd30b07179a)
(property "Reference" "C16" (at 154.94 162.56 0)
(property "Reference" "C48" (at 154.94 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 154.94 167.64 0)
@@ -2375,7 +2418,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C16") (unit 1)
(reference "C48") (unit 1)
)
)
)
@@ -2465,10 +2508,10 @@
(symbol (lib_id "Device:R") (at 236.22 78.74 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 57d23afb-3e89-43f3-b8ac-d446fddb5c78)
(property "Reference" "R24" (at 236.22 78.74 90)
(property "Reference" "R67" (at 236.22 78.74 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 234.95 76.2 90)
(property "Value" "4k7" (at 234.95 76.2 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 237.998 78.74 90)
@@ -2482,7 +2525,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R24") (unit 1)
(reference "R67") (unit 1)
)
)
)
@@ -2513,6 +2556,31 @@
)
)
(symbol (lib_id "power:+3.3V") (at 37.465 99.06 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 5e12ee82-fcda-4974-89c8-6d39855dd9a7)
(property "Reference" "#PWR0122" (at 37.465 102.87 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "+3.3V" (at 37.465 92.71 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (at 37.465 99.06 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (at 37.465 99.06 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid fd5e815d-25e7-463e-abf0-345676136502))
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "#PWR0122") (unit 1)
)
)
)
)
(symbol (lib_id "power:GND") (at 80.01 168.91 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 5eab1301-c652-4034-b7ac-a7c7e2e2d177)
@@ -2572,10 +2640,10 @@
(symbol (lib_id "Device:R") (at 142.24 73.66 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 64094713-7d76-4b8b-9bf9-b7f64f75c920)
(property "Reference" "R21" (at 142.24 73.66 90)
(property "Reference" "R69" (at 142.24 73.66 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 144.78 72.39 90)
(property "Value" "4k7" (at 144.78 72.39 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 142.24 75.438 90)
@@ -2589,7 +2657,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R21") (unit 1)
(reference "R69") (unit 1)
)
)
)
@@ -2598,10 +2666,10 @@
(symbol (lib_id "Device:R") (at 142.24 91.44 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 6624d943-f8e6-4441-982c-3de575b1dc6e)
(property "Reference" "R26" (at 142.24 91.44 90)
(property "Reference" "R65" (at 142.24 91.44 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 144.78 90.17 90)
(property "Value" "4k7" (at 144.78 90.17 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 142.24 93.218 90)
@@ -2615,7 +2683,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R26") (unit 1)
(reference "R65") (unit 1)
)
)
)
@@ -2624,7 +2692,7 @@
(symbol (lib_id "Device:C") (at 35.56 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 67ac6176-2471-48a9-ab9f-52beec89a1b4)
(property "Reference" "C31" (at 35.56 162.56 0)
(property "Reference" "C23" (at 35.56 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 35.56 167.64 0)
@@ -2641,7 +2709,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C31") (unit 1)
(reference "C23") (unit 1)
)
)
)
@@ -2650,10 +2718,10 @@
(symbol (lib_id "Device:R") (at 236.22 133.35 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 687437c4-7aa9-4046-9f4a-5ed469d0a577)
(property "Reference" "R39" (at 236.22 133.35 90)
(property "Reference" "R45" (at 236.22 133.35 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 234.95 128.27 90)
(property "Value" "4k7" (at 234.95 128.27 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 234.442 133.35 90)
@@ -2667,7 +2735,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R39") (unit 1)
(reference "R45") (unit 1)
)
)
)
@@ -2676,10 +2744,10 @@
(symbol (lib_id "Device:R") (at 236.22 154.94 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 69038310-08d8-4fd8-baf2-714dff3fe0fa)
(property "Reference" "R37" (at 236.22 154.94 90)
(property "Reference" "R41" (at 236.22 154.94 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 234.95 149.86 90)
(property "Value" "4k7" (at 234.95 149.86 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 234.442 154.94 90)
@@ -2693,7 +2761,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R37") (unit 1)
(reference "R41") (unit 1)
)
)
)
@@ -2918,7 +2986,7 @@
(symbol (lib_id "Device:C") (at 147.32 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 7c830bcb-695d-41b3-8002-7f2c5e88ee96)
(property "Reference" "C24" (at 147.32 162.56 0)
(property "Reference" "C21" (at 147.32 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 147.32 167.64 0)
@@ -2935,7 +3003,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C24") (unit 1)
(reference "C21") (unit 1)
)
)
)
@@ -2944,7 +3012,7 @@
(symbol (lib_id "Device:C") (at 80.01 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 80b396e6-1879-4eac-b0a4-6cc056dcdbd4)
(property "Reference" "C15" (at 80.01 162.56 0)
(property "Reference" "C49" (at 80.01 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 80.01 167.64 0)
@@ -2961,7 +3029,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C15") (unit 1)
(reference "C49") (unit 1)
)
)
)
@@ -2998,7 +3066,7 @@
(symbol (lib_id "Memory_EEPROM:AT24CS32-SSHM") (at 223.52 143.51 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 8408a666-ef40-4b48-8c8c-2ec840ed8567)
(property "Reference" "U3" (at 215.9 137.16 0)
(property "Reference" "U8" (at 215.9 137.16 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "24LC32A" (at 215.9 152.4 0)
@@ -3021,7 +3089,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "U3") (unit 1)
(reference "U8") (unit 1)
)
)
)
@@ -3080,7 +3148,7 @@
(symbol (lib_id "Device:C") (at 217.17 39.37 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 8c1a0b38-bcc5-4658-8a69-f4a9c64b4a45)
(property "Reference" "C11" (at 220.091 38.1579 0)
(property "Reference" "C52" (at 220.091 38.1579 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "18pF" (at 220.091 40.5821 0)
@@ -3097,7 +3165,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C11") (unit 1)
(reference "C52") (unit 1)
)
)
)
@@ -3156,7 +3224,7 @@
(symbol (lib_id "Device:R") (at 142.24 76.2 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 95dffa01-7efa-4524-83d7-dd663891f3a6)
(property "Reference" "R25" (at 142.24 76.2 90)
(property "Reference" "R66" (at 142.24 76.2 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "12k 1%" (at 144.78 74.93 90)
@@ -3173,7 +3241,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R25") (unit 1)
(reference "R66") (unit 1)
)
)
)
@@ -3207,7 +3275,7 @@
(symbol (lib_id "Device:C") (at 251.46 125.73 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid a3b06323-b5c8-4051-b0b4-69c7a4fc48db)
(property "Reference" "C33" (at 255.27 127 90)
(property "Reference" "C22" (at 255.27 127 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "0.1uF" (at 255.27 124.46 90)
@@ -3224,7 +3292,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C33") (unit 1)
(reference "C22") (unit 1)
)
)
)
@@ -3233,7 +3301,7 @@
(symbol (lib_id "Device:C") (at 139.7 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid ad6de67e-4fd5-4374-8c26-533464ecb640)
(property "Reference" "C28" (at 139.7 162.56 0)
(property "Reference" "C16" (at 139.7 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 139.7 167.64 0)
@@ -3250,7 +3318,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C28") (unit 1)
(reference "C16") (unit 1)
)
)
)
@@ -3259,7 +3327,7 @@
(symbol (lib_id "Device:C") (at 72.39 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid afc04acb-541e-4783-aa5d-3ce559901854)
(property "Reference" "C14" (at 72.39 162.56 0)
(property "Reference" "C50" (at 72.39 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 72.39 167.64 0)
@@ -3276,7 +3344,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C14") (unit 1)
(reference "C50") (unit 1)
)
)
)
@@ -3310,7 +3378,7 @@
(symbol (lib_id "Device:R") (at 69.85 36.83 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid b162f748-c4c9-4222-9aec-552919872ce9)
(property "Reference" "R31" (at 69.85 36.83 90)
(property "Reference" "R58" (at 69.85 36.83 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "22" (at 68.58 34.29 90)
@@ -3327,7 +3395,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R31") (unit 1)
(reference "R58") (unit 1)
)
)
)
@@ -3392,7 +3460,7 @@
(symbol (lib_id "Device:C") (at 236.22 96.52 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid c01f9f04-3e14-4fe2-bfff-c83b3128fbfe)
(property "Reference" "C13" (at 239.141 95.3079 0)
(property "Reference" "C45" (at 239.141 95.3079 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "1uF" (at 239.141 97.7321 0)
@@ -3409,7 +3477,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C13") (unit 1)
(reference "C45") (unit 1)
)
)
)
@@ -3418,7 +3486,7 @@
(symbol (lib_id "Device:C") (at 27.94 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid c46518db-79b6-4045-8dfc-08fea70463ae)
(property "Reference" "C23" (at 27.94 162.56 0)
(property "Reference" "C40" (at 27.94 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 27.94 167.64 0)
@@ -3435,7 +3503,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C23") (unit 1)
(reference "C40") (unit 1)
)
)
)
@@ -3519,7 +3587,7 @@
(symbol (lib_id "Device:C") (at 95.25 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid ca3b83df-34a4-4261-8b7d-4450fdcf7ea0)
(property "Reference" "C18" (at 95.25 162.56 0)
(property "Reference" "C46" (at 95.25 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 95.25 167.64 0)
@@ -3536,7 +3604,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C18") (unit 1)
(reference "C46") (unit 1)
)
)
)
@@ -3573,7 +3641,7 @@
(symbol (lib_id "Device:C") (at 43.18 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid cd4007e2-5a66-41a7-ba64-1fe909a22a11)
(property "Reference" "C29" (at 43.18 162.56 0)
(property "Reference" "C25" (at 43.18 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 43.18 167.64 0)
@@ -3590,7 +3658,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C29") (unit 1)
(reference "C25") (unit 1)
)
)
)
@@ -3624,10 +3692,10 @@
(symbol (lib_id "Device:R") (at 241.3 133.35 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid dbb53c1f-a3e9-40f7-9c26-4cfbc7e7faea)
(property "Reference" "R38" (at 241.3 133.35 90)
(property "Reference" "R44" (at 241.3 133.35 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 240.03 128.27 90)
(property "Value" "4k7" (at 240.03 128.27 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 239.522 133.35 90)
@@ -3641,7 +3709,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R38") (unit 1)
(reference "R44") (unit 1)
)
)
)
@@ -3731,10 +3799,10 @@
(symbol (lib_id "Device:R") (at 223.52 99.06 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid e42bfe7f-7ca3-4fd5-a029-2fee492bb34b)
(property "Reference" "R23" (at 223.52 99.06 90)
(property "Reference" "R68" (at 223.52 99.06 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 222.25 96.52 90)
(property "Value" "4k7" (at 222.25 96.52 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 225.298 99.06 90)
@@ -3748,7 +3816,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "R23") (unit 1)
(reference "R68") (unit 1)
)
)
)
@@ -3808,7 +3876,7 @@
(symbol (lib_id "Device:C") (at 50.8 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid f2ad262e-6efc-4ec5-abc3-f362fad8d615)
(property "Reference" "C26" (at 50.8 162.56 0)
(property "Reference" "C20" (at 50.8 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 50.8 167.64 0)
@@ -3825,7 +3893,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C26") (unit 1)
(reference "C20") (unit 1)
)
)
)
@@ -3890,7 +3958,7 @@
(symbol (lib_id "Device:C") (at 124.46 165.1 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid feb0a5ed-4720-49ab-b7b2-db871d6fd2ee)
(property "Reference" "C25" (at 124.46 162.56 0)
(property "Reference" "C39" (at 124.46 162.56 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "0.1uF" (at 124.46 167.64 0)
@@ -3907,7 +3975,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/9f485422-734f-43d3-94ea-443cbc453d2e"
(reference "C25") (unit 1)
(reference "C39") (unit 1)
)
)
)

View File

@@ -4,6 +4,10 @@
(paper "A4")
(title_block
(title "MetalMusings EaserCAT 3000")
)
(lib_symbols
(symbol "Device:C" (pin_numbers hide) (pin_names (offset 0.254)) (in_bom yes) (on_board yes)
(property "Reference" "C" (at 0.635 2.54 0)
@@ -2937,7 +2941,7 @@
(symbol (lib_id "Device:R") (at 245.11 88.9 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 0156fcd2-2fd8-4277-bfea-a43d1b5d2609)
(property "Reference" "R43" (at 245.11 88.9 90)
(property "Reference" "R63" (at 245.11 88.9 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 250.19 87.63 90)
@@ -2954,7 +2958,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R43") (unit 1)
(reference "R63") (unit 1)
)
)
)
@@ -2963,7 +2967,7 @@
(symbol (lib_id "Device:FerriteBead_Small") (at 137.16 162.56 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 044bfca2-fe85-424e-89e6-85976fdf3676)
(property "Reference" "B4" (at 137.16 160.02 90)
(property "Reference" "B6" (at 137.16 160.02 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "BLM18EG221SN1D" (at 137.16 165.1 90)
@@ -2980,7 +2984,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "B4") (unit 1)
(reference "B6") (unit 1)
)
)
)
@@ -3017,10 +3021,10 @@
(symbol (lib_id "Device:R") (at 222.25 127 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 137b958d-6c66-4243-b922-13e0d4e0ff22)
(property "Reference" "R19" (at 222.25 127 90)
(property "Reference" "R71" (at 222.25 127 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 227.33 125.73 90)
(property "Value" "4k7" (at 227.33 125.73 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 222.25 125.222 90)
@@ -3034,7 +3038,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R19") (unit 1)
(reference "R71") (unit 1)
)
)
)
@@ -3068,7 +3072,7 @@
(symbol (lib_id "Device:FerriteBead_Small") (at 99.06 154.94 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 18c39117-9175-49a5-804f-919c3f463e74)
(property "Reference" "B7" (at 99.06 152.4 90)
(property "Reference" "B1" (at 99.06 152.4 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "BLM18EG221SN1D" (at 99.06 157.48 90)
@@ -3085,7 +3089,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "B7") (unit 1)
(reference "B1") (unit 1)
)
)
)
@@ -3094,7 +3098,7 @@
(symbol (lib_id "Device:R") (at 46.99 36.83 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 1c4db209-5e6a-4cbe-b133-c6f6909b09dd)
(property "Reference" "R11" (at 46.99 36.83 90)
(property "Reference" "R55" (at 46.99 36.83 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 45.72 31.75 90)
@@ -3111,7 +3115,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R11") (unit 1)
(reference "R55") (unit 1)
)
)
)
@@ -3126,7 +3130,7 @@
(property "Value" "Green led" (at 209.55 119.38 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "LED_SMD:LED_0805_2012Metric" (at 209.55 123.19 0)
(property "Footprint" "LED_SMD:LED_0603_1608Metric" (at 209.55 123.19 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (at 209.55 123.19 0)
@@ -3140,7 +3144,7 @@
(reference "D?") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "D1") (unit 1)
(reference "D21") (unit 1)
)
)
)
@@ -3174,7 +3178,7 @@
(symbol (lib_id "Device:C") (at 58.42 128.27 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 252ccc0b-afe2-4cfa-9240-bbd4119b8767)
(property "Reference" "C9" (at 59.69 132.08 90)
(property "Reference" "C29" (at 59.69 132.08 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 59.69 124.46 90)
@@ -3191,7 +3195,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C9") (unit 1)
(reference "C29") (unit 1)
)
)
)
@@ -3228,7 +3232,7 @@
(symbol (lib_id "Device:C") (at 63.5 128.27 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 33b95d1b-4180-477e-93fe-daa04b8a21ee)
(property "Reference" "C10" (at 64.77 132.08 90)
(property "Reference" "C28" (at 64.77 132.08 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "0.1uF" (at 64.77 124.46 90)
@@ -3245,7 +3249,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C10") (unit 1)
(reference "C28") (unit 1)
)
)
)
@@ -3282,7 +3286,7 @@
(symbol (lib_id "Device:R") (at 52.07 36.83 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 395e4cb0-42d4-43ec-b523-c62753046557)
(property "Reference" "R12" (at 52.07 36.83 90)
(property "Reference" "R54" (at 52.07 36.83 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 50.8 31.75 90)
@@ -3299,7 +3303,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R12") (unit 1)
(reference "R54") (unit 1)
)
)
)
@@ -3364,7 +3368,7 @@
(symbol (lib_id "Device:R") (at 135.89 59.69 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 43243964-0602-4452-b782-e18672992d26)
(property "Reference" "R4" (at 135.89 59.69 90)
(property "Reference" "R62" (at 135.89 59.69 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 134.62 54.61 90)
@@ -3381,7 +3385,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R4") (unit 1)
(reference "R62") (unit 1)
)
)
)
@@ -3456,7 +3460,7 @@
(symbol (lib_id "Device:R") (at 245.11 49.53 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 52f49fd2-f073-4f65-b85d-4076ede1e08b)
(property "Reference" "R35" (at 245.11 49.53 90)
(property "Reference" "R57" (at 245.11 49.53 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 251.46 48.26 90)
@@ -3473,7 +3477,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R35") (unit 1)
(reference "R57") (unit 1)
)
)
)
@@ -3482,7 +3486,7 @@
(symbol (lib_id "Device:FerriteBead_Small") (at 99.06 162.56 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 5a256e67-effb-487d-986d-5a4e91cc6e7b)
(property "Reference" "B6" (at 99.06 160.02 90)
(property "Reference" "B4" (at 99.06 160.02 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "BLM18EG221SN1D" (at 99.06 165.1 90)
@@ -3499,7 +3503,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "B6") (unit 1)
(reference "B4") (unit 1)
)
)
)
@@ -3508,7 +3512,7 @@
(symbol (lib_id "Device:R") (at 48.26 96.52 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 5b51c0db-89fb-4b33-acf6-55877b663ddb)
(property "Reference" "R15" (at 48.26 96.52 90)
(property "Reference" "R51" (at 48.26 96.52 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 46.99 91.44 90)
@@ -3525,7 +3529,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R15") (unit 1)
(reference "R51") (unit 1)
)
)
)
@@ -3560,10 +3564,10 @@
(symbol (lib_id "Device:R") (at 212.09 95.25 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 5d2a3bd4-36a3-4cd5-b2ec-31d44b293cc0)
(property "Reference" "R28" (at 212.09 95.25 90)
(property "Reference" "R64" (at 212.09 95.25 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 217.17 93.98 90)
(property "Value" "4k7" (at 217.17 93.98 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 212.09 93.472 90)
@@ -3577,7 +3581,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R28") (unit 1)
(reference "R64") (unit 1)
)
)
)
@@ -3614,7 +3618,7 @@
(symbol (lib_id "Device:FerriteBead_Small") (at 62.23 36.83 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no) (fields_autoplaced)
(uuid 5f64f649-130a-4994-879c-e0ac6e94924e)
(property "Reference" "B1" (at 64.6938 35.5798 0)
(property "Reference" "B3" (at 64.6938 35.5798 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "BLM18EG221S" (at 64.6938 38.004 0)
@@ -3631,7 +3635,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "B1") (unit 1)
(reference "B3") (unit 1)
)
)
)
@@ -3640,10 +3644,10 @@
(symbol (lib_id "Device:R") (at 209.55 27.94 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 5ff7eb3b-4022-400e-8b2d-e57549faafb6)
(property "Reference" "R34" (at 209.55 27.94 90)
(property "Reference" "R46" (at 209.55 27.94 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 214.63 26.67 90)
(property "Value" "4k7" (at 214.63 26.67 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 209.55 26.162 90)
@@ -3657,7 +3661,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R34") (unit 1)
(reference "R46") (unit 1)
)
)
)
@@ -3686,7 +3690,7 @@
(reference "C39") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C19") (unit 1)
(reference "C44") (unit 1)
)
)
)
@@ -3695,7 +3699,7 @@
(symbol (lib_id "Device:C") (at 46.99 68.58 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 703a5ad5-261f-462a-927b-2f5091816ac1)
(property "Reference" "C2" (at 48.26 72.39 90)
(property "Reference" "C36" (at 48.26 72.39 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 48.26 64.77 90)
@@ -3712,7 +3716,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C2") (unit 1)
(reference "C36") (unit 1)
)
)
)
@@ -3724,10 +3728,10 @@
(property "Reference" "D?" (at 228.6 46.99 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "Green led" (at 228.6 53.34 0)
(property "Value" "Green led" (at 231.775 51.435 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "LED_SMD:LED_0805_2012Metric" (at 228.6 49.53 0)
(property "Footprint" "LED_SMD:LED_0603_1608Metric" (at 228.6 49.53 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (at 228.6 49.53 0)
@@ -3741,7 +3745,7 @@
(reference "D?") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "D2") (unit 1)
(reference "D19") (unit 1)
)
)
)
@@ -3750,7 +3754,7 @@
(symbol (lib_id "Device:R") (at 41.91 36.83 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 7e520c4e-ee0b-4ea7-8b18-2be4397e790f)
(property "Reference" "R10" (at 41.91 36.83 90)
(property "Reference" "R56" (at 41.91 36.83 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 40.64 31.75 90)
@@ -3767,7 +3771,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R10") (unit 1)
(reference "R56") (unit 1)
)
)
)
@@ -3776,7 +3780,7 @@
(symbol (lib_id "Device:C") (at 53.34 128.27 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 817571cd-b71b-4f1f-b21a-2340accaf437)
(property "Reference" "C8" (at 54.61 132.08 90)
(property "Reference" "C30" (at 54.61 132.08 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 54.61 124.46 90)
@@ -3793,7 +3797,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C8") (unit 1)
(reference "C30") (unit 1)
)
)
)
@@ -3909,7 +3913,7 @@
(symbol (lib_id "Device:R") (at 57.15 36.83 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid 94e7971f-a4d4-466b-8bd1-b0a1da13dc73)
(property "Reference" "R13" (at 57.15 36.83 90)
(property "Reference" "R53" (at 57.15 36.83 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 55.88 31.75 90)
@@ -3926,7 +3930,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R13") (unit 1)
(reference "R53") (unit 1)
)
)
)
@@ -3955,7 +3959,7 @@
(reference "C30") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C20") (unit 1)
(reference "C43") (unit 1)
)
)
)
@@ -4020,7 +4024,7 @@
(symbol (lib_id "Device:R") (at 222.25 123.19 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid a8f795da-4f57-4266-9dbc-d4b1ec49a21b)
(property "Reference" "R20" (at 222.25 123.19 90)
(property "Reference" "R70" (at 222.25 123.19 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 228.6 121.92 90)
@@ -4037,7 +4041,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R20") (unit 1)
(reference "R70") (unit 1)
)
)
)
@@ -4102,7 +4106,7 @@
(symbol (lib_id "Device:R") (at 53.34 96.52 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid aaa3a6f9-473c-405e-9246-c50f1418c80a)
(property "Reference" "R16" (at 53.34 96.52 90)
(property "Reference" "R50" (at 53.34 96.52 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 52.07 91.44 90)
@@ -4119,7 +4123,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R16") (unit 1)
(reference "R50") (unit 1)
)
)
)
@@ -4128,7 +4132,7 @@
(symbol (lib_id "Device:C") (at 48.26 128.27 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid acd922bf-b439-49a5-93b9-08d057963a14)
(property "Reference" "C7" (at 49.53 132.08 90)
(property "Reference" "C31" (at 49.53 132.08 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 49.53 124.46 90)
@@ -4145,7 +4149,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C7") (unit 1)
(reference "C31") (unit 1)
)
)
)
@@ -4182,7 +4186,7 @@
(symbol (lib_id "Device:C") (at 43.18 128.27 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid b297d9a7-f493-4b05-81ae-f0b3d7b2667f)
(property "Reference" "C6" (at 44.45 132.08 90)
(property "Reference" "C32" (at 44.45 132.08 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 44.45 124.46 90)
@@ -4199,7 +4203,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C6") (unit 1)
(reference "C32") (unit 1)
)
)
)
@@ -4208,10 +4212,10 @@
(symbol (lib_id "Device:R") (at 209.55 55.88 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid b5c12ec7-2ca4-4236-a5f3-044e9cc59673)
(property "Reference" "R33" (at 209.55 55.88 90)
(property "Reference" "R48" (at 209.55 55.88 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "4.7k" (at 215.9 54.61 90)
(property "Value" "4k7" (at 215.9 54.61 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Resistor_SMD:R_0805_2012Metric" (at 209.55 54.102 90)
@@ -4225,7 +4229,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R33") (unit 1)
(reference "R48") (unit 1)
)
)
)
@@ -4234,7 +4238,7 @@
(symbol (lib_id "Device:R") (at 43.18 96.52 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid b79bae43-c327-493d-a038-855680f06fe3)
(property "Reference" "R14" (at 43.18 96.52 90)
(property "Reference" "R52" (at 43.18 96.52 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 41.91 91.44 90)
@@ -4251,7 +4255,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R14") (unit 1)
(reference "R52") (unit 1)
)
)
)
@@ -4309,7 +4313,7 @@
(reference "U3") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "U1") (unit 1)
(reference "U9") (unit 1)
)
)
)
@@ -4324,7 +4328,7 @@
(property "Value" "Red led" (at 228.6 92.71 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "LED_SMD:LED_0805_2012Metric" (at 228.6 88.9 0)
(property "Footprint" "LED_SMD:LED_0603_1608Metric" (at 228.6 88.9 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (at 228.6 88.9 0)
@@ -4338,7 +4342,7 @@
(reference "D?") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "D4") (unit 1)
(reference "D20") (unit 1)
)
)
)
@@ -4385,7 +4389,7 @@
(symbol (lib_id "Device:R") (at 130.81 48.26 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid d135b0c1-00a9-4a15-bf69-2c050be870d3)
(property "Reference" "R5" (at 130.81 48.26 90)
(property "Reference" "R61" (at 130.81 48.26 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 135.89 46.99 90)
@@ -4402,7 +4406,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R5") (unit 1)
(reference "R61") (unit 1)
)
)
)
@@ -4411,7 +4415,7 @@
(symbol (lib_id "Device:C") (at 52.07 68.58 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid d97aea31-efd3-4805-a26e-93bfe540f39c)
(property "Reference" "C3" (at 53.34 72.39 90)
(property "Reference" "C35" (at 53.34 72.39 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 53.34 64.77 90)
@@ -4428,7 +4432,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C3") (unit 1)
(reference "C35") (unit 1)
)
)
)
@@ -4437,7 +4441,7 @@
(symbol (lib_id "Device:R") (at 58.42 96.52 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid dcb1369b-bcf1-4c3e-bd29-50410ac94349)
(property "Reference" "R17" (at 58.42 96.52 90)
(property "Reference" "R49" (at 58.42 96.52 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "49.9" (at 57.15 91.44 90)
@@ -4454,7 +4458,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R17") (unit 1)
(reference "R49") (unit 1)
)
)
)
@@ -4463,7 +4467,7 @@
(symbol (lib_id "Device:C") (at 57.15 68.58 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid e0f26f8b-8985-49e6-8c97-f11bdae1e3a3)
(property "Reference" "C4" (at 58.42 72.39 90)
(property "Reference" "C34" (at 58.42 72.39 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 58.42 64.77 90)
@@ -4480,7 +4484,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C4") (unit 1)
(reference "C34") (unit 1)
)
)
)
@@ -4517,7 +4521,7 @@
(symbol (lib_id "Device:C") (at 62.23 68.58 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid e534b46c-80d1-4c34-8578-50b240333e0c)
(property "Reference" "C5" (at 63.5 72.39 90)
(property "Reference" "C33" (at 63.5 72.39 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "0.1uF" (at 63.5 64.77 90)
@@ -4534,7 +4538,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C5") (unit 1)
(reference "C33") (unit 1)
)
)
)
@@ -4543,7 +4547,7 @@
(symbol (lib_id "Device:R") (at 133.35 107.95 270) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid e59e1dd2-d274-40ca-a8b1-cb4b3dd2162e)
(property "Reference" "R7" (at 133.35 107.95 90)
(property "Reference" "R59" (at 133.35 107.95 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 138.43 106.68 90)
@@ -4560,7 +4564,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R7") (unit 1)
(reference "R59") (unit 1)
)
)
)
@@ -4617,7 +4621,7 @@
(reference "C33") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C22") (unit 1)
(reference "C41") (unit 1)
)
)
)
@@ -4682,7 +4686,7 @@
(symbol (lib_id "Device:C") (at 41.91 68.58 180) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid f493fbdd-16cf-47a4-8571-5bdeffa77b8e)
(property "Reference" "C1" (at 43.18 72.39 90)
(property "Reference" "C37" (at 43.18 72.39 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "10pF" (at 43.18 64.77 90)
@@ -4699,7 +4703,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C1") (unit 1)
(reference "C37") (unit 1)
)
)
)
@@ -4728,7 +4732,7 @@
(reference "C41") (unit 1)
)
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "C21") (unit 1)
(reference "C42") (unit 1)
)
)
)
@@ -4737,7 +4741,7 @@
(symbol (lib_id "Device:FerriteBead_Small") (at 137.16 154.94 90) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid f76a00b9-0511-4931-90f1-d259b14389f9)
(property "Reference" "B3" (at 137.16 152.4 90)
(property "Reference" "B7" (at 137.16 152.4 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "BLM18EG221SN1D" (at 137.16 157.48 90)
@@ -4754,7 +4758,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "B3") (unit 1)
(reference "B7") (unit 1)
)
)
)
@@ -4763,7 +4767,7 @@
(symbol (lib_id "Device:R") (at 138.43 119.38 0) (unit 1)
(in_bom yes) (on_board yes) (dnp no)
(uuid f8848c60-f91f-414b-a5b0-c8e97aca000a)
(property "Reference" "R6" (at 138.43 119.38 90)
(property "Reference" "R60" (at 138.43 119.38 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "510" (at 137.16 114.3 90)
@@ -4780,7 +4784,7 @@
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1/5bf93325-f5d9-4344-9bf3-f5fc91bc1622"
(reference "R6") (unit 1)
(reference "R60") (unit 1)
)
)
)

View File

@@ -1,40 +0,0 @@
"Id";"Designator";"Footprint";"Quantity";"Designation";"Supplier and ref";
1;"J8";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"Stepper 2";;;
2;"U1";"LQFP-80-1EP_10x10mm_P0.4mm_EP5.3x4.5mm_ThermalVias";1;"AX58100";;;
3;"B3,B7,B4,B6,B5";"C_0805_2012Metric";5;"BLM18EG221SN1D";;;
4;"R59,R61,R51,R45,R60,R58,R50,R57,R53,R52,R56,R55,R46,R54";"R_0805_2012Metric";14;"1k";;;
5;"U5";"LQFP-100_14x14mm_P0.5mm";1;"STM32F407VGT6";;;
6;"U2";"SOIC-8_3.9x4.9mm_P1.27mm";1;"24LC32A";;;
7;"R3,R49,R2,R48,R1";"R_0805_2012Metric";5;"22";;;
8;"C23,C21,C24,C22,C19,C25,C26,C20";"C_0805_2012Metric";8;"10pF";;;
9;"J3,J4,J5";"JST_XH_B6B-XH-A_1x06_P2.50mm_Vertical";3;"Conn_01x06_Pin";;;
10;"J9";"PinHeader_1x04_P2.54mm_Vertical";1;"I2C bus2";;;
11;"C45,C36,C34,C37,C38,C9,C39,C27,C13,C12,C40,C10,C8,C6,C29,C11,C46,C28,C3,C33,C41,C5,C2,C31,C18,C43,C14,C4,C7,C1";"C_0805_2012Metric";30;"0.1uF";;;
12;"Y2";"Crystal_HC49-U_Vertical";1;"8 MHz";;;
13;"R11,R7,R30,R12,R5,R10,R38,R13,R40,R33,R8";"R_0805_2012Metric";11;"4.7k";;;
14;"D1,D2";"LED_0805_2012Metric";2;"Green led";;;
15;"R28,R39,R25,R41,R26,R44,R27";"R_0805_2012Metric";7;"510";;;
16;"J14";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 4";;;
17;"C35,C32,C44,C30";"C_0805_2012Metric";4;"10uF";;;
18;"C49,C53";"C_0805_2012Metric";2;"2.2uF";;;
19;"D4,D5";"LED_0805_2012Metric";2;"Blue led";;;
20;"R22,R18,R19,R20,R17,R23,R21,R24";"R_0805_2012Metric";8;"49.9";;;
21;"C17,C15";"C_0805_2012Metric";2;"18pF";;;
22;"Y1";"Crystal_SMD_SeikoEpson_TSX3225-4Pin_3.2x2.5mm";1;"NXK25.000AE12F-KAB6-12";;;
23;"J12";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 2";;;
24;"J1";"JST_XH_B2B-XH-A_1x02_P2.50mm_Vertical";1;"Conn_01x02_Pin";;;
25;"IN1,OUT1";"PulseJack JB0011D01BNL";2;"J0011D01BNL";;;
26;"J2";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"STLINK";;;
27;"C52,C51";"C_0805_2012Metric";2;"22pF";;;
28;"B2,B1";"C_0805_2012Metric";2;"BLM18EG221S";;;
29;"J10";"JST_XH_B3B-XH-A_1x03_P2.50mm_Vertical";1;"DAC1";;;
30;"U4";"SOT-223-3_TabPin2";1;"AMS1117-3.3";;;
31;"J7";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"Stepper 1";;;
32;"J6";"JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical";1;"Serial usart1";;;
33;"SW1";"SW_Push_1P1T_XKB_TS-1187A";1;"SW PB";;;
34;"C16";"C_0805_2012Metric";1;"1uF";;;
35;"D3";"LED_0805_2012Metric";1;"Red led";;;
36;"J13";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 3";;;
37;"J11";"JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical";1;"Encoder 1";;;
38;"U3";"SOT-223-3_TabPin2";1;"AMS1117-1.2";;;
39;"R6";"R_0805_2012Metric";1;"12k 1%";;;
1 Id Designator Footprint Quantity Designation Supplier and ref
2 1 J8 JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical 1 Stepper 2
3 2 U1 LQFP-80-1EP_10x10mm_P0.4mm_EP5.3x4.5mm_ThermalVias 1 AX58100
4 3 B3,B7,B4,B6,B5 C_0805_2012Metric 5 BLM18EG221SN1D
5 4 R59,R61,R51,R45,R60,R58,R50,R57,R53,R52,R56,R55,R46,R54 R_0805_2012Metric 14 1k
6 5 U5 LQFP-100_14x14mm_P0.5mm 1 STM32F407VGT6
7 6 U2 SOIC-8_3.9x4.9mm_P1.27mm 1 24LC32A
8 7 R3,R49,R2,R48,R1 R_0805_2012Metric 5 22
9 8 C23,C21,C24,C22,C19,C25,C26,C20 C_0805_2012Metric 8 10pF
10 9 J3,J4,J5 JST_XH_B6B-XH-A_1x06_P2.50mm_Vertical 3 Conn_01x06_Pin
11 10 J9 PinHeader_1x04_P2.54mm_Vertical 1 I2C bus2
12 11 C45,C36,C34,C37,C38,C9,C39,C27,C13,C12,C40,C10,C8,C6,C29,C11,C46,C28,C3,C33,C41,C5,C2,C31,C18,C43,C14,C4,C7,C1 C_0805_2012Metric 30 0.1uF
13 12 Y2 Crystal_HC49-U_Vertical 1 8 MHz
14 13 R11,R7,R30,R12,R5,R10,R38,R13,R40,R33,R8 R_0805_2012Metric 11 4.7k
15 14 D1,D2 LED_0805_2012Metric 2 Green led
16 15 R28,R39,R25,R41,R26,R44,R27 R_0805_2012Metric 7 510
17 16 J14 JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical 1 Encoder 4
18 17 C35,C32,C44,C30 C_0805_2012Metric 4 10uF
19 18 C49,C53 C_0805_2012Metric 2 2.2uF
20 19 D4,D5 LED_0805_2012Metric 2 Blue led
21 20 R22,R18,R19,R20,R17,R23,R21,R24 R_0805_2012Metric 8 49.9
22 21 C17,C15 C_0805_2012Metric 2 18pF
23 22 Y1 Crystal_SMD_SeikoEpson_TSX3225-4Pin_3.2x2.5mm 1 NXK25.000AE12F-KAB6-12
24 23 J12 JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical 1 Encoder 2
25 24 J1 JST_XH_B2B-XH-A_1x02_P2.50mm_Vertical 1 Conn_01x02_Pin
26 25 IN1,OUT1 PulseJack JB0011D01BNL 2 J0011D01BNL
27 26 J2 JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical 1 STLINK
28 27 C52,C51 C_0805_2012Metric 2 22pF
29 28 B2,B1 C_0805_2012Metric 2 BLM18EG221S
30 29 J10 JST_XH_B3B-XH-A_1x03_P2.50mm_Vertical 1 DAC1
31 30 U4 SOT-223-3_TabPin2 1 AMS1117-3.3
32 31 J7 JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical 1 Stepper 1
33 32 J6 JST_XH_B4B-XH-A_1x04_P2.50mm_Vertical 1 Serial usart1
34 33 SW1 SW_Push_1P1T_XKB_TS-1187A 1 SW PB
35 34 C16 C_0805_2012Metric 1 1uF
36 35 D3 LED_0805_2012Metric 1 Red led
37 36 J13 JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical 1 Encoder 3
38 37 J11 JST_XH_B5B-XH-A_1x05_P2.50mm_Vertical 1 Encoder 1
39 38 U3 SOT-223-3_TabPin2 1 AMS1117-1.2
40 39 R6 R_0805_2012Metric 1 12k 1%

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -1,6 +1,6 @@
{
"board": {
"active_layer": 0,
"active_layer": 36,
"active_layer_preset": "",
"auto_track_width": true,
"hidden_netclasses": [],
@@ -14,6 +14,7 @@
"vias": 1.0,
"zones": 0.6
},
"ratsnest_display_mode": 0,
"selection_filter": {
"dimensions": true,
"footprints": true,
@@ -64,7 +65,7 @@
39,
40
],
"visible_layers": "7ffffff_80000001",
"visible_layers": "ffc0000_ffffffff",
"zone_display_mode": 0
},
"meta": {

View File

@@ -23,13 +23,13 @@
},
"fab_line_width": 0.09999999999999999,
"fab_text_italic": false,
"fab_text_size_h": 1.0,
"fab_text_size_h": 0.6,
"fab_text_size_v": 1.0,
"fab_text_thickness": 0.15,
"fab_text_upright": false,
"other_line_width": 0.15,
"other_text_italic": false,
"other_text_size_h": 1.0,
"other_text_size_h": 0.6,
"other_text_size_v": 1.0,
"other_text_thickness": 0.15,
"other_text_upright": false,
@@ -40,12 +40,13 @@
},
"silk_line_width": 0.15,
"silk_text_italic": false,
"silk_text_size_h": 1.0,
"silk_text_size_h": 0.6,
"silk_text_size_v": 1.0,
"silk_text_thickness": 0.15,
"silk_text_upright": false,
"zones": {
"min_clearance": 0.5
"45_degree_only": false,
"min_clearance": 0.0
}
},
"diff_pair_dimensions": [
@@ -72,7 +73,7 @@
"duplicate_footprints": "warning",
"extra_footprint": "warning",
"footprint": "error",
"footprint_type_mismatch": "ignore",
"footprint_type_mismatch": "warning",
"hole_clearance": "error",
"hole_near_hole": "error",
"invalid_outline": "error",
@@ -84,12 +85,12 @@
"lib_footprint_mismatch": "warning",
"malformed_courtyard": "error",
"microvia_drill_out_of_range": "error",
"missing_courtyard": "ignore",
"missing_courtyard": "error",
"missing_footprint": "warning",
"net_conflict": "warning",
"npth_inside_courtyard": "ignore",
"npth_inside_courtyard": "warning",
"padstack": "warning",
"pth_inside_courtyard": "ignore",
"pth_inside_courtyard": "warning",
"shorting_items": "error",
"silk_edge_clearance": "warning",
"silk_over_copper": "warning",
@@ -110,6 +111,8 @@
"zones_intersect": "error"
},
"rules": {
"allow_blind_buried_vias": false,
"allow_microvias": false,
"max_error": 0.005,
"min_clearance": 0.0,
"min_connection": 0.0,
@@ -120,10 +123,10 @@
"min_microvia_drill": 0.09999999999999999,
"min_resolved_spokes": 2,
"min_silk_clearance": 0.0,
"min_text_height": 0.7999999999999999,
"min_text_height": 0.6,
"min_text_thickness": 0.08,
"min_through_hole_diameter": 0.3,
"min_track_width": 0.0,
"min_track_width": 0.19999999999999998,
"min_via_annular_width": 0.09999999999999999,
"min_via_diameter": 0.5,
"solder_mask_clearance": 0.0,
@@ -180,7 +183,8 @@
"drill": 0.0
}
],
"zones_allow_external_fillets": false
"zones_allow_external_fillets": false,
"zones_use_no_outline": true
},
"layer_presets": [],
"viewports": []
@@ -390,7 +394,7 @@
"no_connect_dangling": "warning",
"pin_not_connected": "error",
"pin_not_driven": "error",
"pin_to_pin": "warning",
"pin_to_pin": "error",
"power_pin_not_driven": "error",
"similar_labels": "warning",
"simulation_model_issue": "ignore",
@@ -499,7 +503,11 @@
],
[
"0a376a6c-0f15-42f8-81f6-3a55619be267",
"Peripherals"
"Input-Output"
],
[
"cd91a270-7393-4003-91a3-e42304da540b",
"Stepper+encoder"
]
],
"text_variables": {}

View File

@@ -2,25 +2,24 @@
(uuid 5597aedc-b607-407f-bbfd-31b3b298ecb1)
(paper "A3")
(paper "A4")
(title_block
(title "MetalMusings EaserCAT 3000")
)
(lib_symbols
)
(text "Huvudsida" (at 162.56 85.09 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
(uuid adf2be63-7ec7-44be-837f-901ddbc80717)
)
(sheet (at 144.78 224.79) (size 71.12 16.51) (fields_autoplaced)
(sheet (at 57.15 156.21) (size 93.98 39.37) (fields_autoplaced)
(stroke (width 0.1524) (type solid))
(fill (color 0 0 0 0.0000))
(uuid 0a376a6c-0f15-42f8-81f6-3a55619be267)
(property "Sheetname" "Peripherals" (at 144.78 224.0784 0)
(property "Sheetname" "Input-Output" (at 57.15 155.4984 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
)
(property "Sheetfile" "peripherals.kicad_sch" (at 144.78 241.8846 0)
(property "Sheetfile" "peripherals.kicad_sch" (at 57.15 196.1646 0)
(effects (font (size 1.27 1.27)) (justify left top))
)
(instances
@@ -30,14 +29,14 @@
)
)
(sheet (at 234.95 198.12) (size 102.87 34.29) (fields_autoplaced)
(sheet (at 170.18 31.75) (size 101.6 58.42) (fields_autoplaced)
(stroke (width 0.1524) (type solid))
(fill (color 0 0 0 0.0000))
(uuid 5bf93325-f5d9-4344-9bf3-f5fc91bc1622)
(property "Sheetname" "AX58100 phys etc" (at 234.95 197.4084 0)
(property "Sheetname" "AX58100 phys etc" (at 170.18 31.0384 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
)
(property "Sheetfile" "AX58100_phy_etc.kicad_sch" (at 234.95 232.9946 0)
(property "Sheetfile" "AX58100_phy_etc.kicad_sch" (at 170.18 90.7546 0)
(effects (font (size 1.27 1.27)) (justify left top))
)
(instances
@@ -47,14 +46,14 @@
)
)
(sheet (at 233.68 123.19) (size 93.98 60.96) (fields_autoplaced)
(sheet (at 57.15 31.75) (size 93.98 60.96) (fields_autoplaced)
(stroke (width 0.1524) (type solid))
(fill (color 0 0 0 0.0000))
(uuid 9f485422-734f-43d3-94ea-443cbc453d2e)
(property "Sheetname" "AX58100" (at 233.68 122.4784 0)
(property "Sheetname" "AX58100" (at 57.15 31.0384 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
)
(property "Sheetfile" "AX48100.kicad_sch" (at 233.68 184.7346 0)
(property "Sheetfile" "AX48100.kicad_sch" (at 57.15 93.2946 0)
(effects (font (size 1.27 1.27)) (justify left top))
)
(instances
@@ -64,14 +63,31 @@
)
)
(sheet (at 142.24 200.66) (size 74.93 17.78) (fields_autoplaced)
(sheet (at 171.45 156.21) (size 105.41 39.37) (fields_autoplaced)
(stroke (width 0.1524) (type solid))
(fill (color 0 0 0 0.0000))
(uuid cd91a270-7393-4003-91a3-e42304da540b)
(property "Sheetname" "Stepper+encoder" (at 171.45 155.4984 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
)
(property "Sheetfile" "Steppers.kicad_sch" (at 171.45 196.1646 0)
(effects (font (size 1.27 1.27)) (justify left top))
)
(instances
(project "Ax58100-stm32-ethercat"
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "6"))
)
)
)
(sheet (at 57.15 106.68) (size 93.98 35.56) (fields_autoplaced)
(stroke (width 0.1524) (type solid))
(fill (color 0 0 0 0.0000))
(uuid d564400f-40ba-4aca-9c2a-14ec52a8353b)
(property "Sheetname" "STM32F4" (at 142.24 199.9484 0)
(property "Sheetname" "STM32F4" (at 57.15 105.9684 0)
(effects (font (size 1.27 1.27)) (justify left bottom))
)
(property "Sheetfile" "STM32F4.kicad_sch" (at 142.24 219.0246 0)
(property "Sheetfile" "STM32F4.kicad_sch" (at 57.15 142.8246 0)
(effects (font (size 1.27 1.27)) (justify left top))
)
(instances

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -64,7 +64,7 @@
39,
40
],
"visible_layers": "002202a_00000001",
"visible_layers": "002202b_80000005",
"zone_display_mode": 0
},
"meta": {

View File

@@ -6,6 +6,30 @@ that I used during the creation of my own EtherCAT device.
This job is documented in a series of Youtube videos, from my first attempts to understand
how EtherCAT works, to making my own pcb, program it and testing it in LinuxCNC.
## Make my own EtherCAT device 8. EaserCAT 3000
Introducing the new **EaserCAT 3000** board. It's an evolution of the EaserCAT 2000
and intended to be used in my plasma cutter. It features four stepper driver outputs,
input for a THCAD arc voltage card, an encoder, an analog output (for spindle +- 10V),
eigth digital inputs, four digital outputs, plus some 12 I/O for any possible extension.
The KiCAD files are in the [KiCAD folder](Kicad/Ax58100-stm32-ethercat)
[![Watch the video](https://img.youtube.com/vi/boanv6ihYtI/default.jpg)](https://youtu.be/boanv6ihYtI)
## Make my own EtherCAT device 7. Turning in the lathe
I have now put things together so the EaserCAT 2000 card controls
my small CNC lathe. Two stepper generators, one each for the X and Z axes,
and an encoder counter for the spindle encoder are on this small card.
While it works there are still issues caused by the variation in cycle time. Thankfully
I was able to reduce the variation from 80-100 microseconds down to 2-3 microseconds,
[![Watch the video](https://img.youtube.com/vi/Bqi1KXEVI1Q/default.jpg)](https://youtu.be/Bqi1KXEVI1Q)
## Make my own EtherCAT device 6. Stepper motor driver
The stepper driver generator shows up and makes some stepper motor sounds. The two big things
@@ -92,4 +116,4 @@ Arduino sketch to program the AT24C32 eeprom with a valid eeprom content. Hook u
###License
Don't violate the original licenses. No warranties. Use it any way you like.
Don't violate the original licenses. No warranties. Use it any way you like.