Ny structure. Start of the "main" branch
This commit is contained in:
37
Cards/.gitignore
vendored
Normal file
37
Cards/.gitignore
vendored
Normal file
@@ -0,0 +1,37 @@
|
||||
# For PCBs designed using KiCad: https://www.kicad.org/
|
||||
# Format documentation: https://kicad.org/help/file-formats/
|
||||
|
||||
# Temporary files
|
||||
*.000
|
||||
*.bak
|
||||
*.bck
|
||||
*.kicad_pcb-bak
|
||||
*.kicad_sch-bak
|
||||
*-backups
|
||||
*.kicad_prl
|
||||
*.sch-bak
|
||||
*~
|
||||
_autosave-*
|
||||
*.tmp
|
||||
*-save.pro
|
||||
*-save.kicad_pcb
|
||||
fp-info-cache
|
||||
~*.lck
|
||||
\#auto_saved_files#
|
||||
|
||||
# Netlist files (exported from Eeschema)
|
||||
*.net
|
||||
|
||||
# Autorouter files (exported from Pcbnew)
|
||||
*.dsn
|
||||
*.ses
|
||||
|
||||
# Exported BOM files
|
||||
*.xml
|
||||
*.csv
|
||||
|
||||
# Gerber outputs
|
||||
Gerbers\*
|
||||
*.zip
|
||||
|
||||
T*
|
||||
6
Cards/EaserCAT-2000/Firmware/.gitignore
vendored
Executable file
6
Cards/EaserCAT-2000/Firmware/.gitignore
vendored
Executable file
@@ -0,0 +1,6 @@
|
||||
.pio
|
||||
.vscode/.browse.c_cpp.db*
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
||||
.vscode/settings.json
|
||||
10
Cards/EaserCAT-2000/Firmware/.vscode/extensions.json
vendored
Executable file
10
Cards/EaserCAT-2000/Firmware/.vscode/extensions.json
vendored
Executable file
@@ -0,0 +1,10 @@
|
||||
{
|
||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||
// for the documentation about the extensions.json format
|
||||
"recommendations": [
|
||||
"platformio.platformio-ide"
|
||||
],
|
||||
"unwantedRecommendations": [
|
||||
"ms-vscode.cpptools-extension-pack"
|
||||
]
|
||||
}
|
||||
1
Cards/EaserCAT-2000/Firmware/doc/.gitignore
vendored
Normal file
1
Cards/EaserCAT-2000/Firmware/doc/.gitignore
vendored
Normal file
@@ -0,0 +1 @@
|
||||
.~lock.*
|
||||
BIN
Cards/EaserCAT-2000/Firmware/doc/Stepgen.odp
Executable file
BIN
Cards/EaserCAT-2000/Firmware/doc/Stepgen.odp
Executable file
Binary file not shown.
38
Cards/EaserCAT-2000/Firmware/include/MyEncoder.h
Executable file
38
Cards/EaserCAT-2000/Firmware/include/MyEncoder.h
Executable file
@@ -0,0 +1,38 @@
|
||||
#ifndef MYENCODER
|
||||
#define MYENCODER
|
||||
#include "Stm32F4_Encoder.h"
|
||||
#include <CircularBuffer.hpp>
|
||||
#define RINGBUFFERLEN 11
|
||||
|
||||
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;
|
||||
double oldFrequency;
|
||||
|
||||
TIM_TypeDef *tim_base;
|
||||
};
|
||||
|
||||
#endif
|
||||
39
Cards/EaserCAT-2000/Firmware/include/README
Executable file
39
Cards/EaserCAT-2000/Firmware/include/README
Executable file
@@ -0,0 +1,39 @@
|
||||
|
||||
This directory is intended for project header files.
|
||||
|
||||
A header file is a file containing C declarations and macro definitions
|
||||
to be shared between several project source files. You request the use of a
|
||||
header file in your project source file (C, C++, etc) located in `src` folder
|
||||
by including it, with the C preprocessing directive `#include'.
|
||||
|
||||
```src/main.c
|
||||
|
||||
#include "header.h"
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
```
|
||||
|
||||
Including a header file produces the same results as copying the header file
|
||||
into each source file that needs it. Such copying would be time-consuming
|
||||
and error-prone. With a header file, the related declarations appear
|
||||
in only one place. If they need to be changed, they can be changed in one
|
||||
place, and programs that include the header file will automatically use the
|
||||
new version when next recompiled. The header file eliminates the labor of
|
||||
finding and changing all the copies as well as the risk that a failure to
|
||||
find one copy will result in inconsistencies within a program.
|
||||
|
||||
In C, the usual convention is to give header files names that end with `.h'.
|
||||
It is most portable to use only letters, digits, dashes, and underscores in
|
||||
header file names, and at most one dot.
|
||||
|
||||
Read more about using header files in official GCC documentation:
|
||||
|
||||
* Include Syntax
|
||||
* Include Operation
|
||||
* Once-Only Headers
|
||||
* Computed Includes
|
||||
|
||||
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
||||
43
Cards/EaserCAT-2000/Firmware/include/StepGen.h
Executable file
43
Cards/EaserCAT-2000/Firmware/include/StepGen.h
Executable file
@@ -0,0 +1,43 @@
|
||||
|
||||
#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;
|
||||
HardwareTimer *MyTim2;
|
||||
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
|
||||
53
Cards/EaserCAT-2000/Firmware/include/StepGen2.h
Executable file
53
Cards/EaserCAT-2000/Firmware/include/StepGen2.h
Executable file
@@ -0,0 +1,53 @@
|
||||
|
||||
#ifndef STEPGEN
|
||||
#define STEPGEN
|
||||
#include <HardwareTimer.h>
|
||||
|
||||
class StepGen2
|
||||
{
|
||||
public:
|
||||
volatile double_t actualPosition;
|
||||
volatile int32_t nSteps;
|
||||
volatile uint32_t timerFrequency;
|
||||
volatile int32_t timerPosition = 0;
|
||||
volatile int32_t timerEndPosition = 0;
|
||||
|
||||
public:
|
||||
volatile float Tstartf; // Starting delay in secs
|
||||
volatile uint32_t Tstartu; // Starting delay in usecs
|
||||
volatile float Tpulses; // Time it takes to do pulses. Debug
|
||||
|
||||
HardwareTimer *pulseTimer;
|
||||
uint32_t pulseTimerChan;
|
||||
HardwareTimer *startTimer; // Use timers 10,11,13,14
|
||||
uint8_t dirPin;
|
||||
PinName dirPinName;
|
||||
PinName stepPin;
|
||||
uint32_t Tjitter = 400; // Longest time from IRQ to handling in handleStepper, unit is microseconds
|
||||
uint64_t dbg;
|
||||
const uint16_t t2 = 5; // DIR is ahead of PUL with at least 5 usecs
|
||||
const uint16_t t3 = 5; // Pulse width at least 2.5 usecs
|
||||
const uint16_t t4 = 5; // Low level width not less than 2.5 usecs
|
||||
const float maxAllowedFrequency = 1000000 / float(t3 + t4) * 0.9; // 150 kHz for now
|
||||
|
||||
public:
|
||||
volatile double_t commandedPosition; // End position when this cycle is completed
|
||||
volatile int32_t commandedStepPosition; // End step position when this cycle is completed
|
||||
volatile double_t initialPosition; // From previous cycle
|
||||
volatile int32_t initialStepPosition; // From previous cycle
|
||||
int16_t stepsPerMM; // This many steps per mm
|
||||
volatile uint8_t enabled; // Enabled step generator
|
||||
volatile float frequency;
|
||||
|
||||
static uint32_t sync0CycleTime; // Nominal EtherCAT cycle time nanoseconds
|
||||
volatile float lcncCycleTime; // Linuxcnc nominal cycle time in sec (1 ms often)
|
||||
|
||||
StepGen2(TIM_TypeDef *Timer, uint32_t _timerChannel, PinName _stepPin, uint8_t _dirPin, void irq(void), TIM_TypeDef *Timer2, void irq2(void));
|
||||
|
||||
uint32_t handleStepper(uint64_t irqTime /* time when irq happened nanosecs */, uint16_t nLoops);
|
||||
void startTimerCB();
|
||||
void pulseTimerCB();
|
||||
uint32_t updatePos(uint32_t i);
|
||||
};
|
||||
|
||||
#endif
|
||||
156
Cards/EaserCAT-2000/Firmware/include/StepGen3.h
Executable file
156
Cards/EaserCAT-2000/Firmware/include/StepGen3.h
Executable file
@@ -0,0 +1,156 @@
|
||||
|
||||
#ifndef STEPGEN3
|
||||
#define STEPGEN3
|
||||
#include <HardwareTimer.h>
|
||||
|
||||
#define MAX_CHAN 16
|
||||
#define MAX_CYCLE 18
|
||||
#define USER_STEP_TYPE 13
|
||||
|
||||
typedef struct
|
||||
{
|
||||
/* stuff that is both read and written by makepulses */
|
||||
volatile unsigned int timer1; /* times out when step pulse should end */
|
||||
volatile unsigned int timer2; /* times out when safe to change dir */
|
||||
volatile unsigned int timer3; /* times out when safe to step in new dir */
|
||||
volatile int hold_dds; /* prevents accumulator from updating */
|
||||
volatile long addval; /* actual frequency generator add value */
|
||||
volatile long long accum; /* frequency generator accumulator */
|
||||
volatile int rawcount; /* param: position feedback in counts */
|
||||
volatile int curr_dir; /* current direction */
|
||||
volatile int state; /* current position in state table */
|
||||
/* stuff that is read but not written by makepulses */
|
||||
volatile int enable; /* pin for enable stepgen */
|
||||
volatile int target_addval; /* desired freq generator add value */
|
||||
volatile long deltalim; /* max allowed change per period */
|
||||
volatile int step_len; /* parameter: step pulse length */
|
||||
volatile unsigned int dir_hold_dly; /* param: direction hold time or delay */
|
||||
volatile unsigned int dir_setup; /* param: direction setup time */
|
||||
volatile int step_type; /* stepping type - see list above */
|
||||
volatile int cycle_max; /* cycle length for step types 2 and up */
|
||||
volatile int num_phases; /* number of phases for types 2 and up */
|
||||
volatile int phase[5]; /* pins for output signals */
|
||||
volatile const unsigned char *lut; /* pointer to state lookup table */
|
||||
/* stuff that is not accessed by makepulses */
|
||||
int pos_mode; /* 1 = position mode, 0 = velocity mode */
|
||||
unsigned int step_space; /* parameter: min step pulse spacing */
|
||||
double old_pos_cmd; /* previous position command (counts) */
|
||||
int count; /* pin: captured feedback in counts */
|
||||
#define double float
|
||||
double pos_scale; /* param: steps per position unit */
|
||||
double old_scale; /* stored scale value */
|
||||
double scale_recip; /* reciprocal value used for scaling */
|
||||
double vel_cmd; /* pin: velocity command (pos units/sec) */
|
||||
double pos_cmd; /* pin: position command (position units) */
|
||||
double pos_fb; /* pin: position feedback (position units) */
|
||||
double freq; /* param: frequency command */
|
||||
double maxvel; /* param: max velocity, (pos units/sec) */
|
||||
double maxaccel; /* param: max accel (pos units/sec^2) */
|
||||
unsigned int old_step_len; /* used to detect parameter changes */
|
||||
unsigned int old_step_space;
|
||||
unsigned int old_dir_hold_dly;
|
||||
unsigned int old_dir_setup;
|
||||
int printed_error; /* flag to avoid repeated printing */
|
||||
} stepgen_t;
|
||||
|
||||
#define MAX_STEP_TYPE 15
|
||||
|
||||
#define STEP_PIN 0 /* output phase used for STEP signal */
|
||||
#define DIR_PIN 1 /* output phase used for DIR signal */
|
||||
#define UP_PIN 0 /* output phase used for UP signal */
|
||||
#define DOWN_PIN 1 /* output phase used for DOWN signal */
|
||||
|
||||
#define PICKOFF 28 /* bit location in DDS accum */
|
||||
|
||||
typedef enum CONTROL
|
||||
{
|
||||
POSITION,
|
||||
VELOCITY,
|
||||
INVALID
|
||||
} CONTROL;
|
||||
|
||||
class StepGen3
|
||||
{
|
||||
public:
|
||||
int step_type[MAX_CHAN] = {-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}; // stepping types for up to 16 channels
|
||||
char *ctrl_type[MAX_CHAN] = {0}; // control type ("p"pos or "v"vel) for up to 16 channels
|
||||
int user_step_type[MAX_CYCLE] = {-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}; // lookup table for user-defined step type
|
||||
uint32_t stepPin[MAX_CHAN] = {0};
|
||||
uint32_t dirPin[MAX_CHAN] = {0};
|
||||
|
||||
stepgen_t *stepgen_array = 0;
|
||||
|
||||
int num_chan = 0; // number of step generators configured */
|
||||
long periodns; // makepulses function period in nanosec */
|
||||
long old_periodns; // used to detect changes in periodns */
|
||||
double periodfp; // makepulses function period in seconds */
|
||||
double freqscale; // conv. factor from Hz to addval counts */
|
||||
double accelscale; // conv. Hz/sec to addval cnts/period */
|
||||
long old_dtns; // update_freq funct period in nsec */
|
||||
double dt; // update_freq period in seconds */
|
||||
double recip_dt; // recprocal of period, avoids divides */
|
||||
volatile uint64_t cnt = 0; // Debug counter
|
||||
#undef double
|
||||
StepGen3(void);
|
||||
void updateStepGen(double pos_cmd1, double pos_cmd2, uint32_t servoPeriod);
|
||||
void makeAllPulses(void);
|
||||
int rtapi_app_main();
|
||||
int export_stepgen(int num, stepgen_t *addr, int step_type, int pos_mode);
|
||||
void make_pulses(void *arg, long period);
|
||||
void update_freq(void *arg, long period);
|
||||
void update_pos(void *arg, long period);
|
||||
int setup_user_step_type(void);
|
||||
CONTROL parse_ctrl_type(const char *ctrl);
|
||||
unsigned long ulceil(unsigned long value, unsigned long increment);
|
||||
|
||||
private:
|
||||
/* lookup tables for stepping types 2 and higher - phase A is the LSB */
|
||||
|
||||
unsigned char master_lut[MAX_STEP_TYPE][MAX_CYCLE] = {
|
||||
{1, 3, 2, 0, 0, 0, 0, 0, 0, 0}, /* type 2: Quadrature */
|
||||
{1, 2, 4, 0, 0, 0, 0, 0, 0, 0}, /* type 3: Three Wire */
|
||||
{1, 3, 2, 6, 4, 5, 0, 0, 0, 0}, /* type 4: Three Wire Half Step */
|
||||
{1, 2, 4, 8, 0, 0, 0, 0, 0, 0}, /* 5: Unipolar Full Step 1 */
|
||||
{3, 6, 12, 9, 0, 0, 0, 0, 0, 0}, /* 6: Unipoler Full Step 2 */
|
||||
{1, 7, 14, 8, 0, 0, 0, 0, 0, 0}, /* 7: Bipolar Full Step 1 */
|
||||
{5, 6, 10, 9, 0, 0, 0, 0, 0, 0}, /* 8: Bipoler Full Step 2 */
|
||||
{1, 3, 2, 6, 4, 12, 8, 9, 0, 0}, /* 9: Unipolar Half Step */
|
||||
{1, 5, 7, 6, 14, 10, 8, 9, 0, 0}, /* 10: Bipolar Half Step */
|
||||
{1, 2, 4, 8, 16, 0, 0, 0, 0, 0}, /* 11: Five Wire Unipolar */
|
||||
{3, 6, 12, 24, 17, 0, 0, 0, 0, 0}, /* 12: Five Wire Wave */
|
||||
{1, 3, 2, 6, 4, 12, 8, 24, 16, 17}, /* 13: Five Wire Uni Half */
|
||||
{3, 7, 6, 14, 12, 28, 24, 25, 17, 19}, /* 14: Five Wire Wave Half */
|
||||
{0, 0, 0, 0, 0, 0, 0, 0, 0, 0} /* 15: User-defined */
|
||||
};
|
||||
|
||||
unsigned char cycle_len_lut[14] =
|
||||
{4, 3, 6, 4, 4, 4, 4, 8, 8, 5, 5, 10, 10, 0};
|
||||
|
||||
unsigned char num_phases_lut[14] =
|
||||
{
|
||||
2,
|
||||
3,
|
||||
3,
|
||||
4,
|
||||
4,
|
||||
4,
|
||||
4,
|
||||
4,
|
||||
4,
|
||||
5,
|
||||
5,
|
||||
5,
|
||||
5,
|
||||
0,
|
||||
};
|
||||
};
|
||||
|
||||
// For the example
|
||||
#define BASE_PERIOD 20000
|
||||
//#define SERVO_PERIOD 2000000
|
||||
#define JOINT_X_STEPGEN_MAXACCEL 0.0
|
||||
#define JOINT_Z_STEPGEN_MAXACCEL 0.0
|
||||
#define JOINT_X_SCALE -200
|
||||
#define JOINT_Z_SCALE -80
|
||||
|
||||
#endif
|
||||
652
Cards/EaserCAT-2000/Firmware/include/Stm32F4_Encoder.h
Executable file
652
Cards/EaserCAT-2000/Firmware/include/Stm32F4_Encoder.h
Executable file
@@ -0,0 +1,652 @@
|
||||
|
||||
#ifndef __Stm32F4_Encoder_H__
|
||||
#define __Stm32F4_Encoder_H__
|
||||
#include <Arduino.h>
|
||||
|
||||
#define GPIO_Speed_50MHz 0x02 /*!< Fast speed */
|
||||
|
||||
// #define GPIO_MODER_MODER0 ((uint32_t)0x00000003)
|
||||
#define GPIO_Mode_OUT 0x01
|
||||
// #define GPIO_OSPEEDER_OSPEEDR0 ((uint32_t)0x00000003)
|
||||
// #define GPIO_OTYPER_OT_0 ((uint32_t)0x00000001)
|
||||
// #define GPIO_PUPDR_PUPDR0 ((uint32_t)0x00000003)
|
||||
|
||||
#define GPIO_PuPd_NOPULL 0x00
|
||||
#define GPIO_Mode_AF 0x02
|
||||
#define GPIO_OType_PP 0x00
|
||||
#define GPIO_PuPd_NOPULL 0x00
|
||||
#define GPIO_Pin_0 ((uint16_t)0x0001) /* Pin 0 selected */
|
||||
#define GPIO_Pin_1 ((uint16_t)0x0002) /* Pin 1 selected */
|
||||
#define GPIO_Pin_2 ((uint16_t)0x0004) /* Pin 2 selected */
|
||||
#define GPIO_Pin_3 ((uint16_t)0x0008) /* Pin 3 selected */
|
||||
#define GPIO_Pin_4 ((uint16_t)0x0010) /* Pin 4 selected */
|
||||
#define GPIO_Pin_5 ((uint16_t)0x0020) /* Pin 5 selected */
|
||||
#define GPIO_Pin_6 ((uint16_t)0x0040) /* Pin 6 selected */
|
||||
#define GPIO_Pin_7 ((uint16_t)0x0080) /* Pin 7 selected */
|
||||
#define GPIO_Pin_8 ((uint16_t)0x0100) /* Pin 8 selected */
|
||||
#define GPIO_Pin_9 ((uint16_t)0x0200) /* Pin 9 selected */
|
||||
#define GPIO_Pin_10 ((uint16_t)0x0400) /* Pin 10 selected */
|
||||
#define GPIO_Pin_11 ((uint16_t)0x0800) /* Pin 11 selected */
|
||||
#define GPIO_Pin_12 ((uint16_t)0x1000) /* Pin 12 selected */
|
||||
#define GPIO_Pin_13 ((uint16_t)0x2000) /* Pin 13 selected */
|
||||
#define GPIO_Pin_14 ((uint16_t)0x4000) /* Pin 14 selected */
|
||||
#define GPIO_Pin_15 ((uint16_t)0x8000) /* Pin 15 selected */
|
||||
#define GPIO_Pin_All ((uint16_t)0xFFFF) /* All pins selected */
|
||||
|
||||
typedef struct TIM_TimeBaseInitTypeDef
|
||||
{
|
||||
uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock.
|
||||
This parameter can be a number between 0x0000 and 0xFFFF */
|
||||
|
||||
uint16_t TIM_CounterMode; /*!< Specifies the counter mode.
|
||||
This parameter can be a value of @ref TIM_Counter_Mode */
|
||||
|
||||
uint32_t TIM_Period; /*!< Specifies the period value to be loaded into the active
|
||||
Auto-Reload Register at the next update event.
|
||||
This parameter must be a number between 0x0000 and 0xFFFF. */
|
||||
|
||||
uint16_t TIM_ClockDivision; /*!< Specifies the clock division.
|
||||
This parameter can be a value of @ref TIM_Clock_Division_CKD */
|
||||
|
||||
uint8_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter
|
||||
reaches zero, an update event is generated and counting restarts
|
||||
from the RCR value (N).
|
||||
This means in PWM mode that (N+1) corresponds to:
|
||||
- the number of PWM periods in edge-aligned mode
|
||||
- the number of half PWM period in center-aligned mode
|
||||
This parameter must be a number between 0x00 and 0xFF.
|
||||
@note This parameter is valid only for TIM1 and TIM8. */
|
||||
} TIM_TimeBaseInitTypeDef;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint16_t setcount;
|
||||
|
||||
} encoder;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint16_t TIM_OCMode; /*!< Specifies the TIM mode.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */
|
||||
|
||||
uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_State */
|
||||
|
||||
uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_N_State
|
||||
@note This parameter is valid only for TIM1 and TIM8. */
|
||||
|
||||
uint32_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register.
|
||||
This parameter can be a number between 0x0000 and 0xFFFF */
|
||||
|
||||
uint16_t TIM_OCPolarity; /*!< Specifies the output polarity.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_Polarity */
|
||||
|
||||
uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_N_Polarity
|
||||
@note This parameter is valid only for TIM1 and TIM8. */
|
||||
|
||||
uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_Idle_State
|
||||
@note This parameter is valid only for TIM1 and TIM8. */
|
||||
|
||||
uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state.
|
||||
This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State
|
||||
@note This parameter is valid only for TIM1 and TIM8. */
|
||||
} TIM_OCInitTypeDef;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
|
||||
uint16_t TIM_Channel; /*!< Specifies the TIM channel.
|
||||
This parameter can be a value of @ref TIM_Channel */
|
||||
|
||||
uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal.
|
||||
This parameter can be a value of @ref TIM_Input_Capture_Polarity */
|
||||
|
||||
uint16_t TIM_ICSelection; /*!< Specifies the input.
|
||||
This parameter can be a value of @ref TIM_Input_Capture_Selection */
|
||||
|
||||
uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler.
|
||||
This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
|
||||
|
||||
uint16_t TIM_ICFilter; /*!< Specifies the input capture filter.
|
||||
This parameter can be a number between 0x0 and 0xF */
|
||||
} TIM_ICInitTypeDef;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
|
||||
uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode.
|
||||
This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */
|
||||
|
||||
uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state.
|
||||
This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */
|
||||
|
||||
uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters.
|
||||
This parameter can be a value of @ref TIM_Lock_level */
|
||||
|
||||
uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the
|
||||
switching-on of the outputs.
|
||||
This parameter can be a number between 0x00 and 0xFF */
|
||||
|
||||
uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not.
|
||||
This parameter can be a value of @ref TIM_Break_Input_enable_disable */
|
||||
|
||||
uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity.
|
||||
This parameter can be a value of @ref TIM_Break_Polarity */
|
||||
|
||||
uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not.
|
||||
This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */
|
||||
} TIM_BDTRInitTypeDef;
|
||||
|
||||
#define GPIO_PinSource0 ((uint8_t)0x00)
|
||||
#define GPIO_PinSource1 ((uint8_t)0x01)
|
||||
#define GPIO_PinSource2 ((uint8_t)0x02)
|
||||
#define GPIO_PinSource3 ((uint8_t)0x03)
|
||||
#define GPIO_PinSource4 ((uint8_t)0x04)
|
||||
#define GPIO_PinSource5 ((uint8_t)0x05)
|
||||
#define GPIO_PinSource6 ((uint8_t)0x06)
|
||||
#define GPIO_PinSource7 ((uint8_t)0x07)
|
||||
#define GPIO_PinSource8 ((uint8_t)0x08)
|
||||
#define GPIO_PinSource9 ((uint8_t)0x09)
|
||||
#define GPIO_PinSource10 ((uint8_t)0x0A)
|
||||
#define GPIO_PinSource11 ((uint8_t)0x0B)
|
||||
#define GPIO_PinSource12 ((uint8_t)0x0C)
|
||||
#define GPIO_PinSource13 ((uint8_t)0x0D)
|
||||
#define GPIO_PinSource14 ((uint8_t)0x0E)
|
||||
#define GPIO_PinSource15 ((uint8_t)0x0F)
|
||||
#define GPIO_AF_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */
|
||||
#define GPIO_AF_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */
|
||||
#define GPIO_AF_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */
|
||||
#define GPIO_AF_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */
|
||||
#define GPIO_AF_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */
|
||||
#define GPIO_AF_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */
|
||||
|
||||
// #define TIM4 ((TIM_TypeDef *)TIM4_BASE)
|
||||
// #define TIM8 ((TIM_TypeDef *)TIM8_BASE)
|
||||
#define TIM_EncoderMode_TI12 ((uint16_t)0x0003)
|
||||
#define TIM_ICPolarity_Rising ((uint16_t)0x0000)
|
||||
#define TIM_ICPolarity_Falling ((uint16_t)0x0002)
|
||||
// #define TIM_CR1_CEN ((uint16_t)0x0001) /*!<Counter enable */
|
||||
// #define TIM_CR1_CEN ((uint16_t)0x0001) /*!<Counter enable */
|
||||
|
||||
#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
|
||||
((PERIPH) == TIM2) || \
|
||||
((PERIPH) == TIM3) || \
|
||||
((PERIPH) == TIM4) || \
|
||||
((PERIPH) == TIM5) || \
|
||||
((PERIPH) == TIM6) || \
|
||||
((PERIPH) == TIM7) || \
|
||||
((PERIPH) == TIM8) || \
|
||||
((PERIPH) == TIM9) || \
|
||||
((PERIPH) == TIM10) || \
|
||||
((PERIPH) == TIM11) || \
|
||||
((PERIPH) == TIM12) || \
|
||||
(((PERIPH) == TIM13) || \
|
||||
((PERIPH) == TIM14)))
|
||||
|
||||
#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
|
||||
((PERIPH) == TIM2) || \
|
||||
((PERIPH) == TIM3) || \
|
||||
((PERIPH) == TIM4) || \
|
||||
((PERIPH) == TIM5) || \
|
||||
((PERIPH) == TIM8) || \
|
||||
((PERIPH) == TIM9) || \
|
||||
((PERIPH) == TIM10) || \
|
||||
((PERIPH) == TIM11) || \
|
||||
((PERIPH) == TIM12) || \
|
||||
((PERIPH) == TIM13) || \
|
||||
((PERIPH) == TIM14))
|
||||
|
||||
#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
|
||||
((PERIPH) == TIM2) || \
|
||||
((PERIPH) == TIM3) || \
|
||||
((PERIPH) == TIM4) || \
|
||||
((PERIPH) == TIM5) || \
|
||||
((PERIPH) == TIM8) || \
|
||||
((PERIPH) == TIM9) || \
|
||||
((PERIPH) == TIM12))
|
||||
|
||||
#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
|
||||
((PERIPH) == TIM2) || \
|
||||
((PERIPH) == TIM3) || \
|
||||
((PERIPH) == TIM4) || \
|
||||
((PERIPH) == TIM5) || \
|
||||
((PERIPH) == TIM8))
|
||||
|
||||
#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
|
||||
((PERIPH) == TIM8))
|
||||
|
||||
#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
|
||||
((PERIPH) == TIM2) || \
|
||||
((PERIPH) == TIM3) || \
|
||||
((PERIPH) == TIM4) || \
|
||||
((PERIPH) == TIM5) || \
|
||||
((PERIPH) == TIM6) || \
|
||||
((PERIPH) == TIM7) || \
|
||||
((PERIPH) == TIM8))
|
||||
|
||||
#define IS_TIM_LIST6_PERIPH(TIMx) (((TIMx) == TIM2) || \
|
||||
((TIMx) == TIM5) || \
|
||||
((TIMx) == TIM11))
|
||||
|
||||
#define TIM_OCMode_Timing ((uint16_t)0x0000)
|
||||
#define TIM_OCMode_Active ((uint16_t)0x0010)
|
||||
#define TIM_OCMode_Inactive ((uint16_t)0x0020)
|
||||
#define TIM_OCMode_Toggle ((uint16_t)0x0030)
|
||||
#define TIM_OCMode_PWM1 ((uint16_t)0x0060)
|
||||
#define TIM_OCMode_PWM2 ((uint16_t)0x0070)
|
||||
//#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \
|
||||
// ((MODE) == TIM_OCMode_Active) || \
|
||||
// ((MODE) == TIM_OCMode_Inactive) || \
|
||||
// ((MODE) == TIM_OCMode_Toggle)|| \
|
||||
// ((MODE) == TIM_OCMode_PWM1) || \
|
||||
// ((MODE) == TIM_OCMode_PWM2))
|
||||
#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \
|
||||
((MODE) == TIM_OCMode_Active) || \
|
||||
((MODE) == TIM_OCMode_Inactive) || \
|
||||
((MODE) == TIM_OCMode_Toggle) || \
|
||||
((MODE) == TIM_OCMode_PWM1) || \
|
||||
((MODE) == TIM_OCMode_PWM2) || \
|
||||
((MODE) == TIM_ForcedAction_Active) || \
|
||||
((MODE) == TIM_ForcedAction_InActive))
|
||||
|
||||
#define TIM_OPMode_Single ((uint16_t)0x0008)
|
||||
#define TIM_OPMode_Repetitive ((uint16_t)0x0000)
|
||||
//#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \
|
||||
// ((MODE) == TIM_OPMode_Repetitive))
|
||||
|
||||
#define TIM_Channel_1 ((uint16_t)0x0000)
|
||||
#define TIM_Channel_2 ((uint16_t)0x0004)
|
||||
#define TIM_Channel_3 ((uint16_t)0x0008)
|
||||
#define TIM_Channel_4 ((uint16_t)0x000C)
|
||||
|
||||
#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
|
||||
((CHANNEL) == TIM_Channel_2) || \
|
||||
((CHANNEL) == TIM_Channel_3) || \
|
||||
((CHANNEL) == TIM_Channel_4))
|
||||
|
||||
#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
|
||||
((CHANNEL) == TIM_Channel_2))
|
||||
#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
|
||||
((CHANNEL) == TIM_Channel_2) || \
|
||||
((CHANNEL) == TIM_Channel_3))
|
||||
|
||||
#define TIM_CKD_DIV1 ((uint16_t)0x0000)
|
||||
#define TIM_CKD_DIV2 ((uint16_t)0x0100)
|
||||
#define TIM_CKD_DIV4 ((uint16_t)0x0200)
|
||||
#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \
|
||||
((DIV) == TIM_CKD_DIV2) || \
|
||||
((DIV) == TIM_CKD_DIV4))
|
||||
|
||||
#define TIM_CounterMode_Up ((uint16_t)0x0000)
|
||||
#define TIM_CounterMode_Down ((uint16_t)0x0010)
|
||||
#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020)
|
||||
#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040)
|
||||
#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060)
|
||||
//#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \
|
||||
// ((MODE) == TIM_CounterMode_Down) || \
|
||||
// ((MODE) == TIM_CounterMode_CenterAligned1) || \
|
||||
// ((MODE) == TIM_CounterMode_CenterAligned2) || \
|
||||
// ((MODE) == TIM_CounterMode_CenterAligned3))
|
||||
|
||||
#define TIM_OCPolarity_High ((uint16_t)0x0000)
|
||||
#define TIM_OCPolarity_Low ((uint16_t)0x0002)
|
||||
//#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \
|
||||
// ((POLARITY) == TIM_OCPolarity_Low))
|
||||
|
||||
#define TIM_OCNPolarity_High ((uint16_t)0x0000)
|
||||
#define TIM_OCNPolarity_Low ((uint16_t)0x0008)
|
||||
//#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \
|
||||
// ((POLARITY) == TIM_OCNPolarity_Low))
|
||||
|
||||
#define TIM_OutputState_Disable ((uint16_t)0x0000)
|
||||
#define TIM_OutputState_Enable ((uint16_t)0x0001)
|
||||
#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \
|
||||
((STATE) == TIM_OutputState_Enable))
|
||||
|
||||
#define TIM_OutputNState_Disable ((uint16_t)0x0000)
|
||||
#define TIM_OutputNState_Enable ((uint16_t)0x0004)
|
||||
#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \
|
||||
((STATE) == TIM_OutputNState_Enable))
|
||||
|
||||
#define TIM_CCx_Enable ((uint16_t)0x0001)
|
||||
#define TIM_CCx_Disable ((uint16_t)0x0000)
|
||||
#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \
|
||||
((CCX) == TIM_CCx_Disable))
|
||||
|
||||
#define TIM_CCxN_Enable ((uint16_t)0x0004)
|
||||
#define TIM_CCxN_Disable ((uint16_t)0x0000)
|
||||
#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \
|
||||
((CCXN) == TIM_CCxN_Disable))
|
||||
|
||||
#define TIM_Break_Enable ((uint16_t)0x1000)
|
||||
#define TIM_Break_Disable ((uint16_t)0x0000)
|
||||
//#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \
|
||||
// ((STATE) == TIM_Break_Disable))
|
||||
|
||||
#define TIM_BreakPolarity_Low ((uint16_t)0x0000)
|
||||
#define TIM_BreakPolarity_High ((uint16_t)0x2000)
|
||||
//#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \
|
||||
// ((POLARITY) == TIM_BreakPolarity_High))
|
||||
|
||||
#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000)
|
||||
#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000)
|
||||
//#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \
|
||||
// ((STATE) == TIM_AutomaticOutput_Disable))
|
||||
|
||||
#define TIM_LOCKLevel_OFF ((uint16_t)0x0000)
|
||||
#define TIM_LOCKLevel_1 ((uint16_t)0x0100)
|
||||
#define TIM_LOCKLevel_2 ((uint16_t)0x0200)
|
||||
#define TIM_LOCKLevel_3 ((uint16_t)0x0300)
|
||||
//#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \
|
||||
// ((LEVEL) == TIM_LOCKLevel_1) || \
|
||||
// ((LEVEL) == TIM_LOCKLevel_2) || \
|
||||
// ((LEVEL) == TIM_LOCKLevel_3))
|
||||
|
||||
#define TIM_OSSIState_Enable ((uint16_t)0x0400)
|
||||
#define TIM_OSSIState_Disable ((uint16_t)0x0000)
|
||||
//#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \
|
||||
// ((STATE) == TIM_OSSIState_Disable))
|
||||
|
||||
#define TIM_OSSRState_Enable ((uint16_t)0x0800)
|
||||
#define TIM_OSSRState_Disable ((uint16_t)0x0000)
|
||||
//#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \
|
||||
// ((STATE) == TIM_OSSRState_Disable))
|
||||
|
||||
#define TIM_OCIdleState_Set ((uint16_t)0x0100)
|
||||
#define TIM_OCIdleState_Reset ((uint16_t)0x0000)
|
||||
//#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \
|
||||
// ((STATE) == TIM_OCIdleState_Reset))
|
||||
//
|
||||
|
||||
#define TIM_OCNIdleState_Set ((uint16_t)0x0200)
|
||||
#define TIM_OCNIdleState_Reset ((uint16_t)0x0000)
|
||||
//#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \
|
||||
// ((STATE) == TIM_OCNIdleState_Reset))
|
||||
|
||||
#define TIM_ICPolarity_Rising ((uint16_t)0x0000)
|
||||
#define TIM_ICPolarity_Falling ((uint16_t)0x0002)
|
||||
#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A)
|
||||
//#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \
|
||||
// ((POLARITY) == TIM_ICPolarity_Falling)|| \
|
||||
// ((POLARITY) == TIM_ICPolarity_BothEdge))
|
||||
|
||||
#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be \
|
||||
connected to IC1, IC2, IC3 or IC4, respectively */
|
||||
#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be \
|
||||
connected to IC2, IC1, IC4 or IC3, respectively. */
|
||||
#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */
|
||||
//#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \
|
||||
// ((SELECTION) == TIM_ICSelection_IndirectTI) || \
|
||||
// ((SELECTION) == TIM_ICSelection_TRC))
|
||||
|
||||
// #define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */
|
||||
// #define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */
|
||||
// #define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */
|
||||
// #define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */
|
||||
// #define IS_TIM_IC_PRESCALER(PRESCALER) ( ((PRESCALER) == TIM_ICPSC_DIV1) || \
|
||||
// ((PRESCALER) == TIM_ICPSC_DIV2) || \
|
||||
// ((PRESCALER) == TIM_ICPSC_DIV4) || \
|
||||
// ((PRESCALER) == TIM_ICPSC_DIV8))
|
||||
|
||||
#define TIM_IT_Update ((uint16_t)0x0001)
|
||||
// #define TIM_IT_CC1 ((uint16_t)0x0002)
|
||||
// #define TIM_IT_CC2 ((uint16_t)0x0004)
|
||||
// #define TIM_IT_CC3 ((uint16_t)0x0008)
|
||||
// #define TIM_IT_CC4 ((uint16_t)0x0010)
|
||||
// #define TIM_IT_COM ((uint16_t)0x0020)
|
||||
#define TIM_IT_Trigger ((uint16_t)0x0040)
|
||||
#define TIM_IT_Break ((uint16_t)0x0080)
|
||||
#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000))
|
||||
|
||||
#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \
|
||||
((IT) == TIM_IT_CC1) || \
|
||||
((IT) == TIM_IT_CC2) || \
|
||||
((IT) == TIM_IT_CC3) || \
|
||||
((IT) == TIM_IT_CC4) || \
|
||||
((IT) == TIM_IT_COM) || \
|
||||
((IT) == TIM_IT_Trigger) || \
|
||||
((IT) == TIM_IT_Break))
|
||||
|
||||
// #define TIM_DMABase_CR1 ((uint16_t)0x0000)
|
||||
// #define TIM_DMABase_CR2 ((uint16_t)0x0001)
|
||||
// #define TIM_DMABase_SMCR ((uint16_t)0x0002)
|
||||
// #define TIM_DMABase_DIER ((uint16_t)0x0003)
|
||||
// #define TIM_DMABase_SR ((uint16_t)0x0004)
|
||||
// #define TIM_DMABase_EGR ((uint16_t)0x0005)
|
||||
// #define TIM_DMABase_CCMR1 ((uint16_t)0x0006)
|
||||
// #define TIM_DMABase_CCMR2 ((uint16_t)0x0007)
|
||||
// #define TIM_DMABase_CCER ((uint16_t)0x0008)
|
||||
// #define TIM_DMABase_CNT ((uint16_t)0x0009)
|
||||
// #define TIM_DMABase_PSC ((uint16_t)0x000A)
|
||||
// #define TIM_DMABase_ARR ((uint16_t)0x000B)
|
||||
// #define TIM_DMABase_RCR ((uint16_t)0x000C)
|
||||
// #define TIM_DMABase_CCR1 ((uint16_t)0x000D)
|
||||
// #define TIM_DMABase_CCR2 ((uint16_t)0x000E)
|
||||
// #define TIM_DMABase_CCR3 ((uint16_t)0x000F)
|
||||
// #define TIM_DMABase_CCR4 ((uint16_t)0x0010)
|
||||
// #define TIM_DMABase_BDTR ((uint16_t)0x0011)
|
||||
// #define TIM_DMABase_DCR ((uint16_t)0x0012)
|
||||
// #define TIM_DMABase_OR ((uint16_t)0x0013)
|
||||
// #define IS_TIM_DMA_BASE(BASE) ( ((BASE) == TIM_DMABase_CR1) || \
|
||||
// ((BASE) == TIM_DMABase_CR2) || \
|
||||
// ((BASE) == TIM_DMABase_SMCR) || \
|
||||
// ((BASE) == TIM_DMABase_DIER) || \
|
||||
// ((BASE) == TIM_DMABase_SR) || \
|
||||
// ((BASE) == TIM_DMABase_EGR) || \
|
||||
// ((BASE) == TIM_DMABase_CCMR1) || \
|
||||
// ((BASE) == TIM_DMABase_CCMR2) || \
|
||||
// ((BASE) == TIM_DMABase_CCER) || \
|
||||
// ((BASE) == TIM_DMABase_CNT) || \
|
||||
// ((BASE) == TIM_DMABase_PSC) || \
|
||||
// ((BASE) == TIM_DMABase_ARR) || \
|
||||
// ((BASE) == TIM_DMABase_RCR) || \
|
||||
// ((BASE) == TIM_DMABase_CCR1) || \
|
||||
// ((BASE) == TIM_DMABase_CCR2) || \
|
||||
// ((BASE) == TIM_DMABase_CCR3) || \
|
||||
// ((BASE) == TIM_DMABase_CCR4) || \
|
||||
// ((BASE) == TIM_DMABase_BDTR) || \
|
||||
// ((BASE) == TIM_DMABase_DCR) || \
|
||||
// ((BASE) == TIM_DMABase_OR))
|
||||
|
||||
// #define TIM_DMABurstLength_1Transfer ((uint16_t)0x0000)
|
||||
// #define TIM_DMABurstLength_2Transfers ((uint16_t)0x0100)
|
||||
// #define TIM_DMABurstLength_3Transfers ((uint16_t)0x0200)
|
||||
// #define TIM_DMABurstLength_4Transfers ((uint16_t)0x0300)
|
||||
// #define TIM_DMABurstLength_5Transfers ((uint16_t)0x0400)
|
||||
// #define TIM_DMABurstLength_6Transfers ((uint16_t)0x0500)
|
||||
// #define TIM_DMABurstLength_7Transfers ((uint16_t)0x0600)
|
||||
// #define TIM_DMABurstLength_8Transfers ((uint16_t)0x0700)
|
||||
// #define TIM_DMABurstLength_9Transfers ((uint16_t)0x0800)
|
||||
// #define TIM_DMABurstLength_10Transfers ((uint16_t)0x0900)
|
||||
// #define TIM_DMABurstLength_11Transfers ((uint16_t)0x0A00)
|
||||
// #define TIM_DMABurstLength_12Transfers ((uint16_t)0x0B00)
|
||||
// #define TIM_DMABurstLength_13Transfers ((uint16_t)0x0C00)
|
||||
// #define TIM_DMABurstLength_14Transfers ((uint16_t)0x0D00)
|
||||
// #define TIM_DMABurstLength_15Transfers ((uint16_t)0x0E00)
|
||||
// #define TIM_DMABurstLength_16Transfers ((uint16_t)0x0F00)
|
||||
// #define TIM_DMABurstLength_17Transfers ((uint16_t)0x1000)
|
||||
// #define TIM_DMABurstLength_18Transfers ((uint16_t)0x1100)
|
||||
// #define IS_TIM_DMA_LENGTH(LENGTH) ( ((LENGTH) == TIM_DMABurstLength_1Transfer) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_2Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_3Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_4Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_5Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_6Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_7Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_8Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_9Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_10Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_11Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_12Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_13Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_14Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_15Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_16Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_17Transfers) || \
|
||||
// ((LENGTH) == TIM_DMABurstLength_18Transfers))
|
||||
|
||||
// #define TIM_DMA_Update ((uint16_t)0x0100)
|
||||
// #define TIM_DMA_CC1 ((uint16_t)0x0200)
|
||||
// #define TIM_DMA_CC2 ((uint16_t)0x0400)
|
||||
// #define TIM_DMA_CC3 ((uint16_t)0x0800)
|
||||
// #define TIM_DMA_CC4 ((uint16_t)0x1000)
|
||||
// #define TIM_DMA_COM ((uint16_t)0x2000)
|
||||
// #define TIM_DMA_Trigger ((uint16_t)0x4000)
|
||||
// #define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000))
|
||||
|
||||
#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000)
|
||||
#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000)
|
||||
#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000)
|
||||
#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000)
|
||||
#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \
|
||||
((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \
|
||||
((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \
|
||||
((PRESCALER) == TIM_ExtTRGPSC_DIV8))
|
||||
|
||||
// #define TIM_TS_ITR0 ((uint16_t)0x0000)
|
||||
// #define TIM_TS_ITR1 ((uint16_t)0x0010)
|
||||
// #define TIM_TS_ITR2 ((uint16_t)0x0020)
|
||||
// #define TIM_TS_ITR3 ((uint16_t)0x0030)
|
||||
// #define TIM_TS_TI1F_ED ((uint16_t)0x0040)
|
||||
// #define TIM_TS_TI1FP1 ((uint16_t)0x0050)
|
||||
// #define TIM_TS_TI2FP2 ((uint16_t)0x0060)
|
||||
// #define TIM_TS_ETRF ((uint16_t)0x0070)
|
||||
// #def ine IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
|
||||
// ((SELECTION) == TIM_TS_ITR1) || \
|
||||
// ((SELECTION) == TIM_TS_ITR2) || \
|
||||
// ((SELECTION) == TIM_TS_ITR3) || \
|
||||
// ((SELECTION) == TIM_TS_TI1F_ED) || \
|
||||
// ((SELECTION) == TIM_TS_TI1FP1) || \
|
||||
// ((SELECTION) == TIM_TS_TI2FP2) || \
|
||||
// ((SELECTION) == TIM_TS_ETRF))
|
||||
#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
|
||||
((SELECTION) == TIM_TS_ITR1) || \
|
||||
((SELECTION) == TIM_TS_ITR2) || \
|
||||
((SELECTION) == TIM_TS_ITR3))
|
||||
|
||||
#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050)
|
||||
#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060)
|
||||
#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040)
|
||||
|
||||
#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000)
|
||||
#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000)
|
||||
#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \
|
||||
((POLARITY) == TIM_ExtTRGPolarity_NonInverted))
|
||||
|
||||
#define TIM_PSCReloadMode_Update ((uint16_t)0x0000)
|
||||
#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001)
|
||||
#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \
|
||||
((RELOAD) == TIM_PSCReloadMode_Immediate))
|
||||
|
||||
#define TIM_ForcedAction_Active ((uint16_t)0x0050)
|
||||
#define TIM_ForcedAction_InActive ((uint16_t)0x0040)
|
||||
#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \
|
||||
((ACTION) == TIM_ForcedAction_InActive))
|
||||
|
||||
#define TIM_EncoderMode_TI1 ((uint16_t)0x0001)
|
||||
#define TIM_EncoderMode_TI2 ((uint16_t)0x0002)
|
||||
#define TIM_EncoderMode_TI12 ((uint16_t)0x0003)
|
||||
//#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \
|
||||
// ((MODE) == TIM_EncoderMode_TI2) || \
|
||||
// ((MODE) == TIM_EncoderMode_TI12))
|
||||
|
||||
// #define TIM_EventSource_Update ((uint16_t)0x0001)
|
||||
// #define TIM_EventSource_CC1 ((uint16_t)0x0002)
|
||||
// #define TIM_EventSource_CC2 ((uint16_t)0x0004)
|
||||
// #define TIM_EventSource_CC3 ((uint16_t)0x0008)
|
||||
// #define TIM_EventSource_CC4 ((uint16_t)0x0010)
|
||||
// #define TIM_EventSource_COM ((uint16_t)0x0020)
|
||||
// #define TIM_EventSource_Trigger ((uint16_t)0x0040)
|
||||
// #define TIM_EventSource_Break ((uint16_t)0x0080)
|
||||
// #define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000))
|
||||
|
||||
#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow \
|
||||
or the setting of UG bit, or an update generation \
|
||||
through the slave mode controller. */
|
||||
#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */
|
||||
#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \
|
||||
((SOURCE) == TIM_UpdateSource_Regular))
|
||||
|
||||
#define TIM_OCPreload_Enable ((uint16_t)0x0008)
|
||||
#define TIM_OCPreload_Disable ((uint16_t)0x0000)
|
||||
#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \
|
||||
((STATE) == TIM_OCPreload_Disable))
|
||||
|
||||
#define TIM_OCFast_Enable ((uint16_t)0x0004)
|
||||
#define TIM_OCFast_Disable ((uint16_t)0x0000)
|
||||
#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \
|
||||
((STATE) == TIM_OCFast_Disable))
|
||||
|
||||
#define TIM_OCClear_Enable ((uint16_t)0x0080)
|
||||
#define TIM_OCClear_Disable ((uint16_t)0x0000)
|
||||
#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \
|
||||
((STATE) == TIM_OCClear_Disable))
|
||||
|
||||
#define TIM_TRGOSource_Reset ((uint16_t)0x0000)
|
||||
#define TIM_TRGOSource_Enable ((uint16_t)0x0010)
|
||||
#define TIM_TRGOSource_Update ((uint16_t)0x0020)
|
||||
#define TIM_TRGOSource_OC1 ((uint16_t)0x0030)
|
||||
#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040)
|
||||
#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050)
|
||||
#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060)
|
||||
#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070)
|
||||
//#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_Enable) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_Update) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_OC1) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_OC1Ref) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_OC2Ref) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_OC3Ref) || \
|
||||
// ((SOURCE) == TIM_TRGOSource_OC4Ref))
|
||||
|
||||
#define TIM_SlaveMode_Reset ((uint16_t)0x0004)
|
||||
#define TIM_SlaveMode_Gated ((uint16_t)0x0005)
|
||||
#define TIM_SlaveMode_Trigger ((uint16_t)0x0006)
|
||||
#define TIM_SlaveMode_External1 ((uint16_t)0x0007)
|
||||
//#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \
|
||||
// ((MODE) == TIM_SlaveMode_Gated) || \
|
||||
// ((MODE) == TIM_SlaveMode_Trigger) || \
|
||||
// ((MODE) == TIM_SlaveMode_External1))
|
||||
|
||||
#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080)
|
||||
#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000)
|
||||
//#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \
|
||||
// ((STATE) == TIM_MasterSlaveMode_Disable))
|
||||
|
||||
#define TIM2_TIM8_TRGO ((uint16_t)0x0000)
|
||||
#define TIM2_ETH_PTP ((uint16_t)0x0400)
|
||||
#define TIM2_USBFS_SOF ((uint16_t)0x0800)
|
||||
#define TIM2_USBHS_SOF ((uint16_t)0x0C00)
|
||||
|
||||
#define TIM5_GPIO ((uint16_t)0x0000)
|
||||
#define TIM5_LSI ((uint16_t)0x0040)
|
||||
#define TIM5_LSE ((uint16_t)0x0080)
|
||||
#define TIM5_RTC ((uint16_t)0x00C0)
|
||||
|
||||
#define TIM11_GPIO ((uint16_t)0x0000)
|
||||
#define TIM11_HSE ((uint16_t)0x0002)
|
||||
|
||||
class Encoder
|
||||
{
|
||||
private:
|
||||
int _pin;
|
||||
|
||||
public:
|
||||
TIM_TypeDef *tim_base;
|
||||
Encoder();
|
||||
void SetCount(int64_t Counter);
|
||||
uint16_t GetCount();
|
||||
};
|
||||
|
||||
void encoder_config();
|
||||
void encoder2_config(); // Experimental
|
||||
void GpioConfigPortA(GPIO_TypeDef *GPIOx);
|
||||
void GpioConfigPortC(GPIO_TypeDef *GPIOx);
|
||||
void GpioConfigPortD(GPIO_TypeDef *GPIOx);
|
||||
void TIM_EncoderInterConfig(TIM_TypeDef *TIMx, uint16_t TIM_EncoderMode, uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity);
|
||||
void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef *TIM_TimeBaseInitStruct);
|
||||
void TIM_TimeBaseInit(TIM_TypeDef *TIMx, TIM_TimeBaseInitTypeDef *TIM_TimeBaseInitStruct);
|
||||
#endif
|
||||
14
Cards/EaserCAT-2000/Firmware/include/extend32to64.h
Executable file
14
Cards/EaserCAT-2000/Firmware/include/extend32to64.h
Executable file
@@ -0,0 +1,14 @@
|
||||
#ifndef EXTEND32TO64
|
||||
#define EXTEND32TO54
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
class extend32to64
|
||||
{
|
||||
public:
|
||||
int64_t previousTimeValue = 0;
|
||||
const uint64_t ONE_PERIOD = 4294967296; // almost UINT32_MAX;
|
||||
const uint64_t HALF_PERIOD = 2147483648; // Half of that
|
||||
int64_t extendTime(uint32_t in);
|
||||
};
|
||||
#endif
|
||||
46
Cards/EaserCAT-2000/Firmware/lib/README
Executable file
46
Cards/EaserCAT-2000/Firmware/lib/README
Executable file
@@ -0,0 +1,46 @@
|
||||
|
||||
This directory is intended for project specific (private) libraries.
|
||||
PlatformIO will compile them to static libraries and link into executable file.
|
||||
|
||||
The source code of each library should be placed in a an own separate directory
|
||||
("lib/your_library_name/[here are source files]").
|
||||
|
||||
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||
|
||||
|--lib
|
||||
| |
|
||||
| |--Bar
|
||||
| | |--docs
|
||||
| | |--examples
|
||||
| | |--src
|
||||
| | |- Bar.c
|
||||
| | |- Bar.h
|
||||
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||
| |
|
||||
| |--Foo
|
||||
| | |- Foo.c
|
||||
| | |- Foo.h
|
||||
| |
|
||||
| |- README --> THIS FILE
|
||||
|
|
||||
|- platformio.ini
|
||||
|--src
|
||||
|- main.c
|
||||
|
||||
and a contents of `src/main.c`:
|
||||
```
|
||||
#include <Foo.h>
|
||||
#include <Bar.h>
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
|
||||
```
|
||||
|
||||
PlatformIO Library Dependency Finder will find automatically dependent
|
||||
libraries scanning project source files.
|
||||
|
||||
More information about PlatformIO Library Dependency Finder
|
||||
- https://docs.platformio.org/page/librarymanager/ldf.html
|
||||
29
Cards/EaserCAT-2000/Firmware/lib/soes/CMakeLists.txt
Executable file
29
Cards/EaserCAT-2000/Firmware/lib/soes/CMakeLists.txt
Executable file
@@ -0,0 +1,29 @@
|
||||
|
||||
# NOTE: add headers to make them show up in an IDE
|
||||
add_library (soes
|
||||
esc.c
|
||||
esc.h
|
||||
esc_coe.c
|
||||
esc_coe.h
|
||||
esc_foe.c
|
||||
esc_foe.h
|
||||
esc_eoe.c
|
||||
esc_eoe.h
|
||||
esc_eep.c
|
||||
esc_eep.h
|
||||
ecat_slv.c
|
||||
ecat_slv.h
|
||||
options.h
|
||||
${HAL_SOURCES}
|
||||
)
|
||||
|
||||
include_directories(${HAL_INCLUDES})
|
||||
|
||||
install (TARGETS soes DESTINATION bin)
|
||||
install (FILES
|
||||
esc.h
|
||||
esc_coe.h
|
||||
esc_foe.h
|
||||
esc_eoe.h
|
||||
esc_eep.h
|
||||
DESTINATION include)
|
||||
1742
Cards/EaserCAT-2000/Firmware/lib/soes/Doxyfile
Executable file
1742
Cards/EaserCAT-2000/Firmware/lib/soes/Doxyfile
Executable file
File diff suppressed because it is too large
Load Diff
88
Cards/EaserCAT-2000/Firmware/lib/soes/cc.h
Executable file
88
Cards/EaserCAT-2000/Firmware/lib/soes/cc.h
Executable file
@@ -0,0 +1,88 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#ifndef CC_H
|
||||
#define CC_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <assert.h>
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
#include <sys/param.h>
|
||||
#ifdef __linux__
|
||||
#include <endian.h>
|
||||
#else
|
||||
#include <machine/endian.h>
|
||||
#endif
|
||||
|
||||
#ifndef MIN
|
||||
#define MIN(a,b) (((a)<(b))?(a):(b))
|
||||
#endif
|
||||
|
||||
#ifndef MAX
|
||||
#define MAX(a,b) (((a)>(b))?(a):(b))
|
||||
#endif
|
||||
|
||||
#define CC_PACKED_BEGIN
|
||||
#define CC_PACKED_END
|
||||
#define CC_PACKED __attribute__((packed))
|
||||
|
||||
#ifdef __rtk__
|
||||
#define CC_ASSERT(exp) ASSERT (exp)
|
||||
#else
|
||||
#define CC_ASSERT(exp) assert (exp)
|
||||
#endif
|
||||
#define CC_STATIC_ASSERT(exp) _Static_assert (exp, "")
|
||||
|
||||
#define CC_DEPRECATED __attribute__((deprecated))
|
||||
|
||||
#define CC_SWAP32(x) __builtin_bswap32 (x)
|
||||
#define CC_SWAP16(x) __builtin_bswap16 (x)
|
||||
|
||||
#define CC_ATOMIC_SET(var,val) __atomic_store_n(&var,val,__ATOMIC_SEQ_CST)
|
||||
#define CC_ATOMIC_GET(var) __atomic_load_n(&var,__ATOMIC_SEQ_CST)
|
||||
#define CC_ATOMIC_ADD(var,val) __atomic_add_fetch(&var,val,__ATOMIC_SEQ_CST)
|
||||
#define CC_ATOMIC_SUB(var,val) __atomic_sub_fetch(&var,val,__ATOMIC_SEQ_CST)
|
||||
#define CC_ATOMIC_AND(var,val) __atomic_and_fetch(&var,val,__ATOMIC_SEQ_CST)
|
||||
#define CC_ATOMIC_OR(var,val) __atomic_or_fetch(&var,val,__ATOMIC_SEQ_CST)
|
||||
|
||||
#if BYTE_ORDER == BIG_ENDIAN
|
||||
#define htoes(x) CC_SWAP16 (x)
|
||||
#define htoel(x) CC_SWAP32 (x)
|
||||
#else
|
||||
#define htoes(x) (x)
|
||||
#define htoel(x) (x)
|
||||
#endif
|
||||
|
||||
#define etohs(x) htoes (x)
|
||||
#define etohl(x) htoel (x)
|
||||
|
||||
#if BYTE_ORDER == LITTLE_ENDIAN
|
||||
#define EC_LITTLE_ENDIAN
|
||||
#else
|
||||
#define EC_BIG_ENDIAN
|
||||
#endif
|
||||
|
||||
#ifdef ESC_DEBUG
|
||||
#ifdef __rtk__
|
||||
#include <rprint.h>
|
||||
#define DPRINT(...) rprintp ("soes: "__VA_ARGS__)
|
||||
#else
|
||||
#include <stdio.h>
|
||||
#define DPRINT(...) printf ("soes: "__VA_ARGS__)
|
||||
#endif
|
||||
#else
|
||||
#define DPRINT(...)
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CC_H */
|
||||
BIN
Cards/EaserCAT-2000/Firmware/lib/soes/doc/images/esi_pdo.png
Executable file
BIN
Cards/EaserCAT-2000/Firmware/lib/soes/doc/images/esi_pdo.png
Executable file
Binary file not shown.
|
After Width: | Height: | Size: 48 KiB |
BIN
Cards/EaserCAT-2000/Firmware/lib/soes/doc/images/sii_pdo.png
Executable file
BIN
Cards/EaserCAT-2000/Firmware/lib/soes/doc/images/sii_pdo.png
Executable file
Binary file not shown.
|
After Width: | Height: | Size: 58 KiB |
50
Cards/EaserCAT-2000/Firmware/lib/soes/doc/soes.dox
Executable file
50
Cards/EaserCAT-2000/Firmware/lib/soes/doc/soes.dox
Executable file
@@ -0,0 +1,50 @@
|
||||
/**
|
||||
* \mainpage Simple Open EtherCAT Slave or SOES
|
||||
*
|
||||
* \section start Tutorial
|
||||
* For a tutorial on SOES See tutorial.txt
|
||||
*
|
||||
* \section overview Overview
|
||||
* SOES is an EtherCAT slave stack written in c. Its purpose is to learn and
|
||||
* to use. All users are invited to study the source to get an understanding
|
||||
* how an EtherCAT slave function
|
||||
*
|
||||
* Features as of 1.0.0 :
|
||||
* - Address offset based HAL for easy ESC read/write access via any interface
|
||||
* - Mailbox with data link layer
|
||||
* - CoE
|
||||
* - Object dictionary
|
||||
* - SDO read and write for all sizes including segmented transfers
|
||||
* - Easy portable C-code suited for embedded applications
|
||||
* - Fixed PDO mapping
|
||||
* - FoE with bootstrap template
|
||||
* - Support for Little and Big endian targets.
|
||||
* - Polling for interrupts
|
||||
*
|
||||
* \section legal Legal notice
|
||||
* SOES Simple Open EtherCAT Slave \n
|
||||
* Copyright (C) 2007-2013 Arthur Ketels \n
|
||||
* Copyright (C) 2012-2013 rt-labs \n
|
||||
*
|
||||
* SOES is free software; you can redistribute it and/or modify it under
|
||||
* the terms of the GNU General Public License version 2 as published by the Free
|
||||
* Software Foundation.
|
||||
*
|
||||
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
|
||||
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
|
||||
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* As a special exception, if other files instantiate templates or use macros
|
||||
* or inline functions from this file, or you compile this file and link it
|
||||
* with other works to produce a work based on this file, this file does not
|
||||
* by itself cause the resulting work to be covered by the GNU General Public
|
||||
* License. However the source code for this file must still be made available
|
||||
* in accordance with section (3) of the GNU General Public License.
|
||||
*
|
||||
* This exception does not invalidate any other reasons why a work based on
|
||||
* this file might be covered by the GNU General Public License.
|
||||
*
|
||||
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
|
||||
* property of, and protected by Beckhoff Automation GmbH.
|
||||
*/
|
||||
476
Cards/EaserCAT-2000/Firmware/lib/soes/doc/tutorial.txt
Executable file
476
Cards/EaserCAT-2000/Firmware/lib/soes/doc/tutorial.txt
Executable file
@@ -0,0 +1,476 @@
|
||||
/** \file
|
||||
|
||||
\section general General
|
||||
|
||||
The SOES is a library that provides the Micro Controller user application with
|
||||
the means to access the EtherCAT fieldbus communication environment:
|
||||
- EtherCAT State Machine
|
||||
- Mailbox Interfaces
|
||||
- Protocols
|
||||
- CoE
|
||||
- FoE + bootstrap template
|
||||
|
||||
Support for mailbox and protocols are typical examples when you need a slave
|
||||
stack to control the Application Layer of EtherCAT. The PDI used for such
|
||||
applications is either SPI or some Micro Controller Interface
|
||||
|
||||
The following sections show some basic examples on how to get the SOES up
|
||||
and running, as well as a lightweight example on howto design your slave.
|
||||
Since all code is local to the application or global variables, it is possible
|
||||
to tweak and optimize when possible.
|
||||
|
||||
Our target Application:
|
||||
- Inputs 40bit
|
||||
- One button 8bit
|
||||
- One encoder value 32bit
|
||||
- Outputs 8bit
|
||||
- LED 8bit
|
||||
- Parameters
|
||||
- Encoder settings
|
||||
- Slave commands
|
||||
- Reset counter
|
||||
|
||||
Now to translate and implement on top of SOES.
|
||||
|
||||
First look on the start up code. This example shows how to add a
|
||||
main function that will be called by startup code. In this example
|
||||
main's only purpose is to spawn two new tasks. One that executes
|
||||
SOES and one that control the ERROR LED. Some ESCs provided a pin
|
||||
for the RUN LED, some even for the ERROR LED, if it don't you can
|
||||
control them from the slave Micro Controller. We'll focus on the "soes" task.
|
||||
|
||||
\code
|
||||
|
||||
int main (void)
|
||||
{
|
||||
rprintp ("SOES (Simple Open EtherCAT Slave)\nsoes test\n");
|
||||
|
||||
/* task_spawn ("led_run", led_error, 15, 512, NULL); /
|
||||
task_spawn ("led_error", led_error, 15, 512, NULL);
|
||||
task_spawn ("soes", soes, 9, 1024, NULL);
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
||||
\endcode
|
||||
|
||||
\section configuration Configuration
|
||||
The function soes is our EtherCAT slave device and can be split in 3 parts.
|
||||
Hardware Init, Software Init and Application loop. We will start with the
|
||||
Hardware Init.
|
||||
|
||||
- Hardware Init
|
||||
- esc_reset, special function used for ESC reset if no Physical
|
||||
EEPROM used. This is local to the Application not part of the generic
|
||||
ESC handling.
|
||||
- ESC_init, initialise SPI communication or similar
|
||||
- Wait for ESC is started, waiting for SPI to be up and running,
|
||||
we'll query the ESC register DL status if EEPROM loaded OK and PDI
|
||||
operational, eg. SPI OK.
|
||||
|
||||
\code
|
||||
|
||||
void soes (void *arg)
|
||||
{
|
||||
TXPDOsize = SM3_sml = sizeTXPDO ();
|
||||
RXPDOsize = SM2_sml = sizeRXPDO ();
|
||||
|
||||
esc_reset ();
|
||||
ESC_init ((void *)spi_name);
|
||||
|
||||
task_delay (tick_from_ms (200));
|
||||
|
||||
// wait until ESC is started up
|
||||
while ((ESCvar.DLstatus & 0x0001) == 0)
|
||||
{
|
||||
ESC_read (ESCREG_DLSTATUS, (void *) &ESCvar.DLstatus,
|
||||
sizeof (ESCvar.DLstatus));
|
||||
ESCvar.DLstatus = etohs (ESCvar.DLstatus);
|
||||
}
|
||||
|
||||
// reset ESC to init state
|
||||
ESC_ALstatus (ESCinit);
|
||||
...
|
||||
}
|
||||
|
||||
\endcode
|
||||
|
||||
- Software Init
|
||||
- Reset the slave into Init state by writing AL Status register.
|
||||
- Clear Errors by writing AL Status Code register.
|
||||
- Stop the Application Layer, basically we disable the SyncManagers
|
||||
that implicitly block the data exchange.
|
||||
|
||||
\code
|
||||
|
||||
void soes (void *arg)
|
||||
{
|
||||
...
|
||||
while ((ESCvar.DLstatus & 0x0001) == 0)
|
||||
{
|
||||
ESC_read (ESCREG_DLSTATUS, (void *) &ESCvar.DLstatus,
|
||||
sizeof (ESCvar.DLstatus));
|
||||
ESCvar.DLstatus = etohs (ESCvar.DLstatus);
|
||||
}
|
||||
|
||||
// reset ESC to init state
|
||||
ESC_ALstatus (ESCinit);
|
||||
ESC_ALerror (ALERR_NONE);
|
||||
ESC_stopmbx ();
|
||||
ESC_stopinput ();
|
||||
ESC_stopoutput ();
|
||||
|
||||
// application run loop
|
||||
while (1)
|
||||
...
|
||||
}
|
||||
\endcode
|
||||
|
||||
- Application loop
|
||||
- ALevent handling, ALevent hold information on changes in ALControl or
|
||||
SyncManagers. ALControl for state changes and SyncManagers for changes written
|
||||
by EtherCAT in local memory mapped to active SyncManagers
|
||||
- ESC_state for state handling, such as state step up or down with correct
|
||||
error and acknowledge response.
|
||||
- Mailbox handler, generic support of mailboxes used by all Application Layer
|
||||
protocols.
|
||||
- On mailbox actions we'll also check if we need to use a specific protocol
|
||||
handler to handle the incoming or outgoing Mailbox data.
|
||||
|
||||
Up until the now we're using the SOES protocol stack without any application specific
|
||||
calls. Next up we'll look at the application Code, here named DIG_process ().
|
||||
|
||||
\code
|
||||
|
||||
void soes (void *arg)
|
||||
{
|
||||
...
|
||||
// application run loop
|
||||
while (1)
|
||||
{
|
||||
if((ESCvar.ALstatus & 0x0f) == ESCinit)
|
||||
{
|
||||
txpdomap = DEFAULTTXPDOMAP;
|
||||
rxpdomap = DEFAULTRXPDOMAP;
|
||||
txpdoitems = DEFAULTTXPDOITEMS;
|
||||
rxpdoitems = DEFAULTTXPDOITEMS;
|
||||
}
|
||||
ESC_read (ESCREG_LOCALTIME, (void *) &ESCvar.Time, sizeof (ESCvar.Time));
|
||||
ESCvar.Time = etohl (ESCvar.Time);
|
||||
|
||||
ESC_state ();
|
||||
if (ESC_mbxprocess ())
|
||||
{
|
||||
ESC_coeprocess ();
|
||||
ESC_foeprocess ();
|
||||
ESC_xoeprocess ();
|
||||
}
|
||||
DIG_process ();
|
||||
};
|
||||
}
|
||||
|
||||
\endcode
|
||||
|
||||
\section application Application
|
||||
The function DIG_process is the User part of the application and could be joined
|
||||
by more cyclic User functions for executing other parts of the application.
|
||||
The example code can be split in 2 parts
|
||||
- Outputs
|
||||
- Start by evaluating if we're in a state supporting update of outputs, eg.
|
||||
Operational state.
|
||||
- If we're in OP we can read the current PDO data in the 3-buffer SyncManager
|
||||
mapped to the output SM, the default is SyncManager2, we read the ESC RAM address
|
||||
of SM2 and store it at the local address of the local variable Wb.LED.
|
||||
We'll read RXPDOsize bytes to trigger a complete SyncManager read.
|
||||
- After local variables have been refreshed we basically write the local
|
||||
PDO variables to the User application, ex. a GPIO.
|
||||
- Basically this is the API of the SOES toward the User Application.
|
||||
- This function also include a watchdog mechanism, if triggered it will
|
||||
shutdown the outputs and trigger a state changes to safe operational.
|
||||
AlError is updated with cause of error to inform the Master.
|
||||
|
||||
\code
|
||||
|
||||
void RXPDO_update (void)
|
||||
{
|
||||
ESC_read (SM2_sma, &Wb.LED, RXPDOsize);
|
||||
}
|
||||
|
||||
void DIG_process (void)
|
||||
{
|
||||
if (App.state & APPSTATE_OUTPUT)
|
||||
{
|
||||
if (ESCvar.ALevent & ESCREG_ALEVENT_SM2) // SM2 trigger ?
|
||||
{
|
||||
RXPDO_update ();
|
||||
reset_wd ();
|
||||
gpio_set(GPIO_LED, Wb.LED & BIT(0));
|
||||
|
||||
}
|
||||
if (!wd_cnt)
|
||||
{
|
||||
ESC_stopoutput ();
|
||||
// watchdog, invalid outputs
|
||||
ESC_ALerror (ALERR_WATCHDOG);
|
||||
// goto safe-op with error bit set
|
||||
ESC_ALstatus (ESCsafeop | ESCerror);
|
||||
wd_trigger = 1;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
reset_wd ();
|
||||
}
|
||||
...
|
||||
}
|
||||
|
||||
\endcode
|
||||
|
||||
- Inputs
|
||||
- Is handled a bit simpler than outputs but in reverse order, the slave will
|
||||
continue update the inputs in state Safe Operational.
|
||||
- Here we first read User application data from ex. GPIO and then write to
|
||||
local PDO variables.
|
||||
- After the local variables have been refreshed we write those to the current
|
||||
PDO data 3-buffer SyncManager mapped to the input SM, the default is SyncManager3.
|
||||
This way we update the ESC RAM address with User Application data accessed by
|
||||
the EtherCAT master.
|
||||
|
||||
\code
|
||||
|
||||
void TXPDO_update (void)
|
||||
{
|
||||
ESC_write (SM3_sma, &Rb.button, TXPDOsize);
|
||||
}
|
||||
|
||||
void DIG_process (void)
|
||||
{
|
||||
...
|
||||
Rb.button = gpio_get(GPIO_WAKEUP);
|
||||
Cb.reset_counter++;
|
||||
Rb.encoder = Cb.reset_counter;
|
||||
|
||||
TXPDO_update ();
|
||||
}
|
||||
|
||||
\endcode
|
||||
|
||||
\section ApplicationdataProcessdata ApplicationdataProcessdata
|
||||
To run application data through EtherCAT processdata we need to describe for
|
||||
the fieldbus what data we have and will read/write. For this we have 3 objects,
|
||||
the ESI file, SII-EEPROM and CoE Object Dictionary. The first 2 are mandatory
|
||||
and the third is a very convenient way of describing complex slaves.
|
||||
|
||||
Our strategy is to keep the ESI file and the SII-EEPROM as thin as possible to
|
||||
avoid duplication of data that need to be maintained. Both will hold the bare
|
||||
minimum of mandatory + optional data to pass CTT. Optional data will be
|
||||
included to tell EtherCAT that detailed information can be retrieved via CoE
|
||||
from the OD stored in the slave it self.
|
||||
|
||||
\section SII-EEPROM SII-EEPROM
|
||||
Snapshot from SII information matrix from EtherCAT communication slides.
|
||||
|
||||
\image html sii_pdo.png "Our target slave is Fixed PDO and OD"
|
||||
\image latex sii_pdo.png "Our target slave is Fixed PDO and OD" width=15cm
|
||||
|
||||
|
||||
\section ESI-file ESI-file
|
||||
Snapshot from ESI tree from EtherCAT communication slides.
|
||||
|
||||
\image html esi_pdo.png "mandatory and optional ESI data"
|
||||
\image latex esi_pdo.png "mandatory and optional ESI data" width=15cm
|
||||
|
||||
To briefly give a hint what are describe in the ESI and SII we're listing
|
||||
a set of included elements marked M for mandatory and O for optional.
|
||||
|
||||
\code
|
||||
- Vendor (M) , Describes the identity.
|
||||
- Id (M), Hex, EtherCAT Vendor ID, OD 1018.01
|
||||
- Name (M), NameType, Expedient vendor name
|
||||
- Descriptions (M), Describes the EtherCAT device(s) using elements.
|
||||
- Groups (M), Similar devices can be assigned to one group.
|
||||
- Group (M), One group groups similar devices with slightly different features
|
||||
- Type (M), A reference handle corresponding to the GroupType value in Description:Devices:Device:Group
|
||||
- Name (M), Name for this group show by a configuration tool
|
||||
- Devices (M), Element devices may describe one or several devices with their EtherCAT features such as SyncManagers, FMMUs and Dictionaries
|
||||
- Device (O), Holds all information about the device like syncmanagers and FMMU, object dictionary, data types and the PDO mapping and assign description
|
||||
- Device ATT: Physics (M),string, Physics at individual ports
|
||||
- Type (M), Device identity
|
||||
- Type ATT:ProductCode="#x98123467"
|
||||
- Type ATT:RevisionNo="#x00000001"
|
||||
- Name (M), Detailed name of device shown by a configuration tool (not used for identification)
|
||||
- GroupType (M), Reference to a group (described in element Groups) to which this device should be assigned to. Name of the handle used in element Groups:Group:Type
|
||||
- Fmmu (O), String to describe function, Outputs -> RxPDO, Inputs -> TxPDO , MBoxState -> FMMU is used to poll Input Mailbox
|
||||
- Sm (O), Description of SyncManager including start address and direction.
|
||||
- MBoxOut Mailbox Data Master -> Slave
|
||||
- MBoxIn Mailbox Data Slave -> Master
|
||||
- Outputs Process Data Master -> Slave
|
||||
- Inputs Process Data Slave -> master
|
||||
- Sm ATT:DefaultSize="128" , Size
|
||||
- Sm ATT:StartAddress="#x1000" , Start address
|
||||
- Sm ATT:ControlByte="#x26" , Settings , Bit [1][0] = 10, Operation mode Mailbox, 00 Buffered 3.
|
||||
- Sm ATT:Enable="1", Enabled
|
||||
- Mailbox (O), Description of available mailbox protocols
|
||||
- Mailbox ATT: DataLinkLayer="true", Support of Mailbox Data Link Layer is mandatory.
|
||||
- CoE (O), Device support CoE
|
||||
- CoE (O) ATT: SdoInfo="true" , SDO Information Service
|
||||
- CoE (O) ATT: CompleteAccess="false" , SDO complete access not supported
|
||||
- CoE (O) ATT: PdoUpload="true", PDO description uploaded from the slave's object dictionary and SyncManager length calculated based on the same
|
||||
- Dc (O), describes synchronization modes supported by the device.
|
||||
- OpMode (O), Definition of supported operation modes
|
||||
- Name (M), Internal Handle of operation mode
|
||||
- Desc (O(M)), description of operation mode, recommended, Free Run (no sync), SM Synchronous, DC Synchronous
|
||||
- AssignActive (M), Value of Latch and Sync Control registers
|
||||
- Eeprom (O, use is mandatory)
|
||||
- Data (M)
|
||||
Or
|
||||
- ByteSize (M), Byte Size of connected EEPROM device
|
||||
- ConfigData (M), First 7 words of EEPROM, Configuration Areas
|
||||
- BootStrap (O), Start address and length of mailboxes for BootStrap
|
||||
\endcode
|
||||
|
||||
So to describe the application we use CoE and Object Dictionary. The mapping between
|
||||
Object Dictionary and the User Application are done via local variables defined as
|
||||
user types. The Object Dictionary itself is stored in a matrix where all
|
||||
the indexes are listed. Every index then have a submatrix with its subindex.
|
||||
|
||||
\section ObjectDictionary ObjectDictionary
|
||||
The Object Dictionary used as example follow the CANopen DS301 ranges.
|
||||
|
||||
- 0x0000 - 0x0FFF, Data Type Area
|
||||
- 0x1000 - 0x1FFF, Communication Area
|
||||
- 0x2000 - 0x5FFF, Manufacture specific area
|
||||
- 0x6000 - 0x6FFF, Input area
|
||||
- 0x7000 - 0x7FFF, Output area
|
||||
- 0x8000 - 0x8FFF, Configuration area
|
||||
- 0x9000 - 0x9FFF, Information area
|
||||
- 0xA000 - 0xAFFF, Diagnosis Area
|
||||
- 0xB000 - 0xBFFF, Service Transfer Area
|
||||
- 0xC000 - 0xEFFF, Reserved Area
|
||||
- 0xF000 - 0xFFFF, Device Area
|
||||
|
||||
RxPDO , 0x1600 - 0x17FF
|
||||
TxPDO , 0x1A00 - 0x1BFF
|
||||
|
||||
Example, on how the the OD index are linked.
|
||||
Top index, SyncManagers Communication Types. In index 0 the 0x04 indicates we have 4
|
||||
SyncManagers defined. Every SyncManager is assigned a type, in index 1-4, we have standard
|
||||
settings SM0 = 1, SM1 = 2, SM2 = 3, SM3 = 4 from ETG 1000.6, 5.6.7.4.
|
||||
- 0, Unused
|
||||
- 1, MailBox Receive, master to slave
|
||||
- 2, MailBox Send, slave to master
|
||||
- 3, Processdata output, master to slave
|
||||
- 4, Processdata input, slave to master
|
||||
|
||||
\code
|
||||
objectlist.h
|
||||
FLASHSTORE _objectlist SDOobjects[] =
|
||||
...
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, &acName1C00[0], &SDO1C00[0]},
|
||||
|
||||
FLASHSTORE _objd SDO1C00[] =
|
||||
{ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_R, &acNameNOE[0], 0x04, nil},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_R, &acName1C00_01[0], 0x01, nil},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_R, &acName1C00_02[0], 0x02, nil},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_R, &acName1C00_03[0], 0x03, nil},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_R, &acName1C00_04[0], 0x04, nil}
|
||||
|
||||
\endcode
|
||||
|
||||
SyncManagers channels 0-31 are listed in SDO1C10-SDO1C2F. If we look
|
||||
at SyncManager channel 2, we see.
|
||||
|
||||
- Type 3, Processdata output, master to slave
|
||||
|
||||
It got one RxPDO index 0x1600 connected, and the submatrix for 0x1600 link
|
||||
one PDO object index 0x7000 subindex 1. The output object 0x70000108 give
|
||||
you the index 0x7000, subindex 1 and PDO object length 1(byte).
|
||||
|
||||
\code
|
||||
objectlist.h
|
||||
FLASHSTORE _objd SDO1C12[] =
|
||||
{ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_R, &acNameNOE[0], 0x01, nil},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_R, &acNameMO[0], 0x1600, nil}
|
||||
};
|
||||
|
||||
FLASHSTORE _objd SDO1600[] =
|
||||
{ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_R, &acNameNOE[0], 0x01, nil},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_R, &acNameMO[0], 0x70000108, nil}
|
||||
};
|
||||
|
||||
\endcode
|
||||
|
||||
At PDO level we make the connection between the local application and
|
||||
the object dictionary. For all subindex in the PDO the last element
|
||||
is the address to the local variable.
|
||||
|
||||
\code
|
||||
|
||||
objectlist.h
|
||||
FLASHSTORE _objd SDO7000[] =
|
||||
{ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_R, &acNameNOE[0], 0x01, nil},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RW, &acName7000_01[0], 0, &(Wb.LED)}
|
||||
};
|
||||
|
||||
utypes.h
|
||||
typedef struct
|
||||
{
|
||||
uint8 LED;
|
||||
} _Wbuffer;
|
||||
|
||||
\endcode
|
||||
|
||||
Beside SyncManager to PDO mapping we also have mandatory data as
|
||||
|
||||
0x1000 Device Type
|
||||
0x1018 Object Identity
|
||||
0x10C0 SyncManager Communication Type, as we used as top index when
|
||||
figuring out our PDOs in the Object Dictionary.
|
||||
|
||||
For a complete description of the object dictionary you can get guidance
|
||||
by the ETG1000.6 EcatAlProtocols
|
||||
|
||||
A useful feature is the Asynchronous use of SDO parameters. In the example
|
||||
we have Parameter set holding an encoder scale value, just for show we also
|
||||
have a read only mirror value of the encoder scale. Parameters defined as a
|
||||
RW SDO parameter and can be written/read by SDO Download or Upload. In
|
||||
addition there is a ESC_objecthandler Hook on SDO Download where you can
|
||||
add additional logic, ex. we execute the mirror of the encoder scale value
|
||||
by assigning the encoder scale value to the mirror.
|
||||
|
||||
\code
|
||||
|
||||
objectlist.h
|
||||
FLASHSTORE _objd SDO7100[] =
|
||||
{ {0x00, DTYPE_UNSIGNED8, 8, ATYPE_R, &acNameNOE[0], 0x02, nil},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RW, &acName7100_01[0], 0, &(encoder_scale)},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_R, &acName7100_02[0], 0, &(encoder_scale_mirror)}
|
||||
};
|
||||
|
||||
soes.c
|
||||
void ESC_objecthandler (uint16 index, uint8 subindex)
|
||||
{
|
||||
switch (index)
|
||||
{
|
||||
...
|
||||
case 0x7100:
|
||||
{
|
||||
switch (subindex)
|
||||
{
|
||||
case 0x01:
|
||||
{
|
||||
encoder_scale_mirror = encoder_scale;
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
...
|
||||
}
|
||||
|
||||
\endcode
|
||||
This tutorial is just one way of doing it.
|
||||
Enjoy and happy coding!
|
||||
|
||||
Andreas Karlsson, rt-labs AB, www.rt-labs.com
|
||||
*/
|
||||
42
Cards/EaserCAT-2000/Firmware/lib/soes/ecat_options.h
Executable file
42
Cards/EaserCAT-2000/Firmware/lib/soes/ecat_options.h
Executable file
@@ -0,0 +1,42 @@
|
||||
#ifndef __ECAT_OPTIONS_H__
|
||||
#define __ECAT_OPTIONS_H__
|
||||
|
||||
#define USE_FOE 0
|
||||
#define USE_EOE 0
|
||||
|
||||
#define MBXSIZE 512
|
||||
#define MBXSIZEBOOT 512
|
||||
#define MBXBUFFERS 3
|
||||
|
||||
#define MBX0_sma 0x1000
|
||||
#define MBX0_sml MBXSIZE
|
||||
#define MBX0_sme MBX0_sma+MBX0_sml-1
|
||||
#define MBX0_smc 0x26
|
||||
#define MBX1_sma MBX0_sma+MBX0_sml
|
||||
#define MBX1_sml MBXSIZE
|
||||
#define MBX1_sme MBX1_sma+MBX1_sml-1
|
||||
#define MBX1_smc 0x22
|
||||
|
||||
#define MBX0_sma_b 0x1000
|
||||
#define MBX0_sml_b MBXSIZEBOOT
|
||||
#define MBX0_sme_b MBX0_sma_b+MBX0_sml_b-1
|
||||
#define MBX0_smc_b 0x26
|
||||
#define MBX1_sma_b MBX0_sma_b+MBX0_sml_b
|
||||
#define MBX1_sml_b MBXSIZEBOOT
|
||||
#define MBX1_sme_b MBX1_sma_b+MBX1_sml_b-1
|
||||
#define MBX1_smc_b 0x22
|
||||
|
||||
#define SM2_sma 0x1600
|
||||
#define SM2_smc 0x24
|
||||
#define SM2_act 1
|
||||
#define SM3_sma 0x1A00
|
||||
#define SM3_smc 0x20
|
||||
#define SM3_act 1
|
||||
|
||||
#define MAX_MAPPINGS_SM2 5
|
||||
#define MAX_MAPPINGS_SM3 11
|
||||
|
||||
#define MAX_RXPDO_SIZE 512
|
||||
#define MAX_TXPDO_SIZE 512
|
||||
|
||||
#endif /* __ECAT_OPTIONS_H__ */
|
||||
386
Cards/EaserCAT-2000/Firmware/lib/soes/ecat_slv.c
Executable file
386
Cards/EaserCAT-2000/Firmware/lib/soes/ecat_slv.c
Executable file
@@ -0,0 +1,386 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
#include <stddef.h>
|
||||
#include "esc.h"
|
||||
#include "esc_coe.h"
|
||||
#include "esc_foe.h"
|
||||
#include "esc_eoe.h"
|
||||
#include "ecat_slv.h"
|
||||
|
||||
#define IS_RXPDO(index) ((index) >= 0x1600 && (index) < 0x1800)
|
||||
#define IS_TXPDO(index) ((index) >= 0x1A00 && (index) < 0x1C00)
|
||||
|
||||
/* Global variables used by the stack */
|
||||
uint8_t MBX[MBXBUFFERS * MAX(MBXSIZE, MBXSIZEBOOT)];
|
||||
_MBXcontrol MBXcontrol[MBXBUFFERS];
|
||||
_SMmap SMmap2[MAX_MAPPINGS_SM2];
|
||||
_SMmap SMmap3[MAX_MAPPINGS_SM3];
|
||||
_ESCvar ESCvar;
|
||||
|
||||
/* Private variables */
|
||||
static volatile int watchdog;
|
||||
|
||||
#if MAX_MAPPINGS_SM2 > 0
|
||||
static uint8_t rxpdo[MAX_RXPDO_SIZE] __attribute__((aligned(8)));
|
||||
#else
|
||||
extern uint8_t *rxpdo;
|
||||
#endif
|
||||
|
||||
#if MAX_MAPPINGS_SM3 > 0
|
||||
static uint8_t txpdo[MAX_TXPDO_SIZE] __attribute__((aligned(8)));
|
||||
#else
|
||||
extern uint8_t *txpdo;
|
||||
#endif
|
||||
|
||||
/** Function to pre-qualify the incoming SDO download.
|
||||
*
|
||||
* @param[in] index = index of SDO download request to check
|
||||
* @param[in] sub-index = sub-index of SDO download request to check
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_download_pre_objecthandler(uint16_t index,
|
||||
uint8_t subindex,
|
||||
void *data,
|
||||
size_t size,
|
||||
uint16_t flags)
|
||||
{
|
||||
if (IS_RXPDO(index) ||
|
||||
IS_TXPDO(index) ||
|
||||
index == RX_PDO_OBJIDX ||
|
||||
index == TX_PDO_OBJIDX)
|
||||
{
|
||||
uint8_t minSub = ((flags & COMPLETE_ACCESS_FLAG) == 0) ? 0 : 1;
|
||||
if (subindex > minSub && COE_maxSub(index) != 0)
|
||||
{
|
||||
return ABORT_SUBINDEX0_NOT_ZERO;
|
||||
}
|
||||
}
|
||||
|
||||
if (ESCvar.pre_object_download_hook)
|
||||
{
|
||||
return (ESCvar.pre_object_download_hook)(index,
|
||||
subindex,
|
||||
data,
|
||||
size,
|
||||
flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Hook called from the slave stack SDO Download handler to act on
|
||||
* user specified Index and Sub-index.
|
||||
*
|
||||
* @param[in] index = index of SDO download request to handle
|
||||
* @param[in] sub-index = sub-index of SDO download request to handle
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_download_post_objecthandler(uint16_t index, uint8_t subindex, uint16_t flags)
|
||||
{
|
||||
if (ESCvar.post_object_download_hook != NULL)
|
||||
{
|
||||
return (ESCvar.post_object_download_hook)(index, subindex, flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Function to pre-qualify the incoming SDO upload.
|
||||
*
|
||||
* @param[in] index = index of SDO upload request to handle
|
||||
* @param[in] sub-index = sub-index of SDO upload request to handle
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_upload_pre_objecthandler(uint16_t index,
|
||||
uint8_t subindex,
|
||||
void *data,
|
||||
size_t size,
|
||||
uint16_t flags)
|
||||
{
|
||||
if (ESCvar.pre_object_upload_hook != NULL)
|
||||
{
|
||||
return (ESCvar.pre_object_upload_hook)(index,
|
||||
subindex,
|
||||
data,
|
||||
size,
|
||||
flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Hook called from the slave stack SDO Upload handler to act on
|
||||
* user specified Index and Sub-index.
|
||||
*
|
||||
* @param[in] index = index of SDO upload request to handle
|
||||
* @param[in] sub-index = sub-index of SDO upload request to handle
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_upload_post_objecthandler(uint16_t index, uint8_t subindex, uint16_t flags)
|
||||
{
|
||||
if (ESCvar.post_object_upload_hook != NULL)
|
||||
{
|
||||
return (ESCvar.post_object_upload_hook)(index, subindex, flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Hook called from the slave stack ESC_stopoutputs to act on state changes
|
||||
* forcing us to stop outputs. Here we can set them to a safe state.
|
||||
*/
|
||||
void APP_safeoutput(void)
|
||||
{
|
||||
DPRINT("APP_safeoutput\n");
|
||||
|
||||
if (ESCvar.safeoutput_override != NULL)
|
||||
{
|
||||
(ESCvar.safeoutput_override)();
|
||||
}
|
||||
}
|
||||
|
||||
/** Write local process data to Sync Manager 3, Master Inputs.
|
||||
*/
|
||||
void TXPDO_update(void)
|
||||
{
|
||||
if (ESCvar.txpdo_override != NULL)
|
||||
{
|
||||
(ESCvar.txpdo_override)();
|
||||
}
|
||||
else
|
||||
{
|
||||
if (MAX_MAPPINGS_SM3 > 0)
|
||||
{
|
||||
COE_pdoPack(txpdo, ESCvar.sm3mappings, SMmap3);
|
||||
}
|
||||
ESC_write(ESC_SM3_sma, txpdo, ESCvar.ESC_SM3_sml);
|
||||
}
|
||||
}
|
||||
|
||||
/** Read Sync Manager 2 to local process data, Master Outputs.
|
||||
*/
|
||||
void RXPDO_update(void)
|
||||
{
|
||||
if (ESCvar.rxpdo_override != NULL)
|
||||
{
|
||||
(ESCvar.rxpdo_override)();
|
||||
}
|
||||
else
|
||||
{
|
||||
ESC_read(ESC_SM2_sma, rxpdo, ESCvar.ESC_SM2_sml);
|
||||
if (MAX_MAPPINGS_SM2 > 0)
|
||||
{
|
||||
COE_pdoUnpack(rxpdo, ESCvar.sm2mappings, SMmap2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Set the watchdog count value, don't have any affect when using
|
||||
* HW watchdog 0x4xx
|
||||
*
|
||||
* @param[in] watchdogcnt = new watchdog count value
|
||||
*/
|
||||
void APP_setwatchdog(int watchdogcnt)
|
||||
{
|
||||
CC_ATOMIC_SET(ESCvar.watchdogcnt, watchdogcnt);
|
||||
}
|
||||
|
||||
/* Function to update local I/O, call read ethercat outputs, call
|
||||
* write ethercat inputs. Implement watch-dog counter to count-out if we have
|
||||
* made state change affecting the App.state.
|
||||
*/
|
||||
|
||||
void DIG_process(uint16_t ALEvent, uint8_t flags)
|
||||
{
|
||||
/* Handle watchdog */
|
||||
if ((flags & DIG_PROCESS_WD_FLAG) > 0)
|
||||
{
|
||||
if (CC_ATOMIC_GET(watchdog) > 0)
|
||||
{
|
||||
CC_ATOMIC_SUB(watchdog, 1);
|
||||
}
|
||||
|
||||
if ((CC_ATOMIC_GET(watchdog) <= 0) &&
|
||||
((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0))
|
||||
{
|
||||
DPRINT("DIG_process watchdog expired\n");
|
||||
ESC_ALstatusgotoerror((ESCsafeop | ESCerror), ALERR_WATCHDOG);
|
||||
}
|
||||
else if (((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) == 0))
|
||||
{
|
||||
CC_ATOMIC_SET(watchdog, ESCvar.watchdogcnt);
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle Outputs */
|
||||
if ((flags & DIG_PROCESS_OUTPUTS_FLAG) > 0)
|
||||
{
|
||||
if (((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0) &&
|
||||
(ALEvent & ESCREG_ALEVENT_SM2))
|
||||
{
|
||||
RXPDO_update();
|
||||
CC_ATOMIC_SET(watchdog, ESCvar.watchdogcnt);
|
||||
/* Set outputs */
|
||||
cb_set_outputs();
|
||||
}
|
||||
else if (ALEvent & ESCREG_ALEVENT_SM2)
|
||||
{
|
||||
RXPDO_update();
|
||||
}
|
||||
}
|
||||
|
||||
/* Call application */
|
||||
if ((flags & DIG_PROCESS_APP_HOOK_FLAG) > 0)
|
||||
{
|
||||
/* Call application callback if set */
|
||||
if (ESCvar.application_hook != NULL)
|
||||
{
|
||||
(ESCvar.application_hook)();
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle Inputs */
|
||||
if ((flags & DIG_PROCESS_INPUTS_FLAG) > 0)
|
||||
{
|
||||
if (CC_ATOMIC_GET(ESCvar.App.state) > 0)
|
||||
{
|
||||
/* Update inputs */
|
||||
cb_get_inputs();
|
||||
TXPDO_update();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application
|
||||
* control what interrupts that should be served and re-activated with
|
||||
* event mask argument
|
||||
*/
|
||||
void ecat_slv_worker(uint32_t event_mask)
|
||||
{
|
||||
do
|
||||
{
|
||||
/* Check the state machine */
|
||||
ESC_state();
|
||||
/* Check the SM activation event */
|
||||
ESC_sm_act_event();
|
||||
|
||||
/* Check mailboxes */
|
||||
while ((ESC_mbxprocess() > 0) || (ESCvar.txcue > 0))
|
||||
{
|
||||
ESC_coeprocess();
|
||||
#if USE_FOE
|
||||
ESC_foeprocess();
|
||||
#endif
|
||||
#if USE_EOE
|
||||
ESC_eoeprocess();
|
||||
#endif
|
||||
ESC_xoeprocess();
|
||||
}
|
||||
#if USE_EOE
|
||||
ESC_eoeprocess_tx();
|
||||
#endif
|
||||
/* Call emulated eeprom handler if set */
|
||||
if (ESCvar.esc_hw_eep_handler != NULL)
|
||||
{
|
||||
(ESCvar.esc_hw_eep_handler)();
|
||||
}
|
||||
|
||||
CC_ATOMIC_SET(ESCvar.ALevent, ESC_ALeventread());
|
||||
|
||||
} while (ESCvar.ALevent & event_mask);
|
||||
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | event_mask);
|
||||
}
|
||||
|
||||
/*
|
||||
* Polling function. It should be called periodically for an application
|
||||
* when only SM2/DC interrupt is active.
|
||||
* Read and handle events for the EtherCAT state, status, mailbox and eeprom.
|
||||
*/
|
||||
void ecat_slv_poll(void)
|
||||
{
|
||||
/* Read local time from ESC*/
|
||||
ESC_read(ESCREG_LOCALTIME, (void *)&ESCvar.Time, sizeof(ESCvar.Time));
|
||||
ESCvar.Time = etohl(ESCvar.Time);
|
||||
|
||||
/* Check the state machine */
|
||||
ESC_state();
|
||||
/* Check the SM activation event */
|
||||
ESC_sm_act_event();
|
||||
|
||||
/* Check mailboxes */
|
||||
if (ESC_mbxprocess())
|
||||
{
|
||||
ESC_coeprocess();
|
||||
#if USE_FOE
|
||||
ESC_foeprocess();
|
||||
#endif
|
||||
#if USE_EOE
|
||||
ESC_eoeprocess();
|
||||
#endif
|
||||
ESC_xoeprocess();
|
||||
}
|
||||
#if USE_EOE
|
||||
ESC_eoeprocess_tx();
|
||||
#endif
|
||||
|
||||
/* Call emulated eeprom handler if set */
|
||||
if (ESCvar.esc_hw_eep_handler != NULL)
|
||||
{
|
||||
(ESCvar.esc_hw_eep_handler)();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Poll all events in a free-run application
|
||||
*/
|
||||
void ecat_slv(void)
|
||||
{
|
||||
ecat_slv_poll();
|
||||
DIG_process(ESC_ALeventread(), DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
|
||||
DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
|
||||
}
|
||||
|
||||
/*
|
||||
* Initialize the slave stack.
|
||||
*/
|
||||
void ecat_slv_init(esc_cfg_t *config)
|
||||
{
|
||||
/* Init watchdog */
|
||||
watchdog = config->watchdog_cnt;
|
||||
|
||||
/* Call stack configuration */
|
||||
ESC_config(config);
|
||||
/* Call HW init */
|
||||
ESC_init(config);
|
||||
|
||||
/* wait until ESC is started up */
|
||||
while ((ESCvar.DLstatus & 0x0001) == 0)
|
||||
{
|
||||
ESC_read(ESCREG_DLSTATUS, (void *)&ESCvar.DLstatus,
|
||||
sizeof(ESCvar.DLstatus));
|
||||
ESCvar.DLstatus = etohs(ESCvar.DLstatus);
|
||||
}
|
||||
|
||||
#if USE_FOE
|
||||
/* Init FoE */
|
||||
FOE_init();
|
||||
#endif
|
||||
|
||||
#if USE_EOE
|
||||
/* Init EoE */
|
||||
EOE_init();
|
||||
#endif
|
||||
|
||||
/* reset ESC to init state */
|
||||
ESC_ALstatus(ESCinit);
|
||||
ESC_ALerror(ALERR_NONE);
|
||||
ESC_stopmbx();
|
||||
ESC_stopinput();
|
||||
ESC_stopoutput();
|
||||
/* Init Object Dictionary default values */
|
||||
COE_initDefaultValues();
|
||||
}
|
||||
69
Cards/EaserCAT-2000/Firmware/lib/soes/ecat_slv.h
Executable file
69
Cards/EaserCAT-2000/Firmware/lib/soes/ecat_slv.h
Executable file
@@ -0,0 +1,69 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#ifndef __ECAT_SLV_H__
|
||||
#define __ECAT_SLV_H__
|
||||
|
||||
#include "ecat_options.h"
|
||||
#include "esc.h"
|
||||
|
||||
/**
|
||||
* This function is called when to get input values
|
||||
*/
|
||||
void cb_get_inputs();
|
||||
|
||||
/**
|
||||
* This function is called when to set outputs values
|
||||
*/
|
||||
void cb_set_outputs();
|
||||
|
||||
/** Set the watchdog count value
|
||||
*
|
||||
* @param[in] watchdogcnt = new watchdog count value
|
||||
*/
|
||||
void APP_setwatchdog(int watchdogcnt);
|
||||
|
||||
#define DIG_PROCESS_INPUTS_FLAG 0x01
|
||||
#define DIG_PROCESS_OUTPUTS_FLAG 0x02
|
||||
#define DIG_PROCESS_WD_FLAG 0x04
|
||||
#define DIG_PROCESS_APP_HOOK_FLAG 0x08
|
||||
/** Implements the watch-dog counter to count if we should make a state change
|
||||
* due to missing incoming SM2 events. Updates local I/O and run the application
|
||||
* in the following order, call read EtherCAT outputs, execute user provided
|
||||
* application hook and call write EtherCAT inputs.
|
||||
*
|
||||
* @param[in] flags = User input what to execute
|
||||
*/
|
||||
void DIG_process(uint16_t ALEvent, uint8_t flags);
|
||||
|
||||
/**
|
||||
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application
|
||||
* control what interrupts that should be served and re-activated with
|
||||
* event mask argument
|
||||
*
|
||||
* @param[in] event_mask = Event mask for interrupts to serve and re-activate
|
||||
* after served
|
||||
*/
|
||||
void ecat_slv_worker(uint32_t event_mask);
|
||||
|
||||
/**
|
||||
* Poll SM0/1, EEPROM and AL CONTROL events in a SM/DC synchronization
|
||||
* application
|
||||
*/
|
||||
void ecat_slv_poll(void);
|
||||
|
||||
/**
|
||||
* Poll all events in a free-run application
|
||||
*/
|
||||
void ecat_slv(void);
|
||||
|
||||
/**
|
||||
* Initialize the slave stack
|
||||
*
|
||||
* @param[in] config = User input how to configure the stack
|
||||
*/
|
||||
void ecat_slv_init(esc_cfg_t *config);
|
||||
|
||||
#endif /* __ECAT_SLV_H__ */
|
||||
BIN
Cards/EaserCAT-2000/Firmware/lib/soes/eeprom.bin
Executable file
BIN
Cards/EaserCAT-2000/Firmware/lib/soes/eeprom.bin
Executable file
Binary file not shown.
65
Cards/EaserCAT-2000/Firmware/lib/soes/eeprom.hex
Executable file
65
Cards/EaserCAT-2000/Firmware/lib/soes/eeprom.hex
Executable file
@@ -0,0 +1,65 @@
|
||||
:2000000080060344640000000000000000001400AA0A0000CCBCBB000200000001000000A1
|
||||
:20002000000000000000000000000000000000000010000200120002040000000000000096
|
||||
:200040000000000000000000000000000000000000000000000000000000000000000000A0
|
||||
:20006000000000000000000000000000000000000000000000000000000000000F00010070
|
||||
:200080000A002000040C4561736572434154323030300E4D616368696E65436F6E74726F64
|
||||
:2000A0006C06494D474342591A4D6574616C4D7573696E67732045617365724341542032E6
|
||||
:2000C000303030001E00100002030104001300000000000000000000110000000000000034
|
||||
:2000E000000000000000000028000200010203002900100000100002260001010012000249
|
||||
:20010000220001020016000024000103001A000020000104FFFFFFFFFFFFFFFFFFFFFFFF49
|
||||
:20012000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDF
|
||||
:20014000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBF
|
||||
:20016000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9F
|
||||
:20018000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7F
|
||||
:2001A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF5F
|
||||
:2001C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF3F
|
||||
:2001E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF1F
|
||||
:20020000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFE
|
||||
:20022000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDE
|
||||
:20024000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBE
|
||||
:20026000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9E
|
||||
:20028000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7E
|
||||
:2002A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF5E
|
||||
:2002C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF3E
|
||||
:2002E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF1E
|
||||
:20030000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFD
|
||||
:20032000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDD
|
||||
:20034000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBD
|
||||
:20036000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9D
|
||||
:20038000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7D
|
||||
:2003A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF5D
|
||||
:2003C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF3D
|
||||
:2003E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF1D
|
||||
:20040000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFC
|
||||
:20042000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDC
|
||||
:20044000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBC
|
||||
:20046000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9C
|
||||
:20048000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7C
|
||||
:2004A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF5C
|
||||
:2004C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF3C
|
||||
:2004E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF1C
|
||||
:20050000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFB
|
||||
:20052000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDB
|
||||
:20054000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBB
|
||||
:20056000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9B
|
||||
:20058000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7B
|
||||
:2005A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF5B
|
||||
:2005C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF3B
|
||||
:2005E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF1B
|
||||
:20060000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFA
|
||||
:20062000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFDA
|
||||
:20064000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFBA
|
||||
:20066000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9A
|
||||
:20068000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF7A
|
||||
:2006A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF5A
|
||||
:2006C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF3A
|
||||
:2006E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF1A
|
||||
:20070000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF9
|
||||
:20072000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFD9
|
||||
:20074000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFB9
|
||||
:20076000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF99
|
||||
:20078000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF79
|
||||
:2007A000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF59
|
||||
:2007C000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF39
|
||||
:2007E000FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF19
|
||||
:00000001FF
|
||||
1179
Cards/EaserCAT-2000/Firmware/lib/soes/esc.c
Executable file
1179
Cards/EaserCAT-2000/Firmware/lib/soes/esc.c
Executable file
File diff suppressed because it is too large
Load Diff
769
Cards/EaserCAT-2000/Firmware/lib/soes/esc.h
Executable file
769
Cards/EaserCAT-2000/Firmware/lib/soes/esc.h
Executable file
@@ -0,0 +1,769 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for esc.h
|
||||
*/
|
||||
|
||||
#ifndef __esc__
|
||||
#define __esc__
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <cc.h>
|
||||
#include <esc_coe.h>
|
||||
#include "ecat_options.h"
|
||||
|
||||
#define ESCREG_ADDRESS 0x0010
|
||||
#define ESCREG_DLSTATUS 0x0110
|
||||
#define ESCREG_ALCONTROL 0x0120
|
||||
#define ESCREG_ALSTATUS 0x0130
|
||||
#define ESCREG_ALERROR 0x0134
|
||||
#define ESCREG_ALEVENTMASK 0x0204
|
||||
#define ESCREG_ALEVENT 0x0220
|
||||
#define ESCREG_ALEVENT_SM_MASK 0x0310
|
||||
#define ESCREG_ALEVENT_SMCHANGE 0x0010
|
||||
#define ESCREG_ALEVENT_CONTROL 0x0001
|
||||
#define ESCREG_ALEVENT_DC_LATCH 0x0002
|
||||
#define ESCREG_ALEVENT_DC_SYNC0 0x0004
|
||||
#define ESCREG_ALEVENT_DC_SYNC1 0x0008
|
||||
#define ESCREG_ALEVENT_EEP 0x0020
|
||||
#define ESCREG_ALEVENT_WD 0x0040
|
||||
#define ESCREG_ALEVENT_SM0 0x0100
|
||||
#define ESCREG_ALEVENT_SM1 0x0200
|
||||
#define ESCREG_ALEVENT_SM2 0x0400
|
||||
#define ESCREG_ALEVENT_SM3 0x0800
|
||||
#define ESCREG_WDSTATUS 0x0440
|
||||
#define ESCREG_EECONTSTAT 0x0502
|
||||
#define ESCREG_EEDATA 0x0508
|
||||
#define ESCREG_SM0 0x0800
|
||||
#define ESCREG_SM0STATUS (ESCREG_SM0 + 5)
|
||||
#define ESCREG_SM0ACTIVATE (ESCREG_SM0 + 6)
|
||||
#define ESCREG_SM0PDI (ESCREG_SM0 + 7)
|
||||
#define ESCREG_SM1 (ESCREG_SM0 + 0x08)
|
||||
#define ESCREG_SM2 (ESCREG_SM0 + 0x10)
|
||||
#define ESCREG_SM3 (ESCREG_SM0 + 0x18)
|
||||
#define ESCREG_LOCALTIME 0x0910
|
||||
#define ESCREG_LOCALTIME_OFFSET 0x0920
|
||||
#define ESCREG_SYNC_ACT 0x0981
|
||||
#define ESCREG_SYNC_ACT_ACTIVATED 0x01
|
||||
#define ESCREG_SYNC_SYNC0_EN 0x02
|
||||
#define ESCREG_SYNC_SYNC1_EN 0x04
|
||||
#define ESCREG_SYNC_AUTO_ACTIVATED 0x08
|
||||
#define ESCREG_SYNC0_CYCLE_TIME 0x09A0
|
||||
#define ESCREG_SYNC1_CYCLE_TIME 0x09A4
|
||||
#define ESCREG_SMENABLE_BIT 0x01
|
||||
#define ESCREG_AL_STATEMASK 0x001f
|
||||
#define ESCREG_AL_ALLBUTINITMASK 0x0e
|
||||
#define ESCREG_AL_ERRACKMASK 0x0f
|
||||
|
||||
#define SYNCTYPE_SUPPORT_FREERUN 0x01
|
||||
#define SYNCTYPE_SUPPORT_SYNCHRON 0x02
|
||||
#define SYNCTYPE_SUPPORT_DCSYNC0 0x04
|
||||
#define SYNCTYPE_SUPPORT_DCSYNC1 0x08
|
||||
#define SYNCTYPE_SUPPORT_SUBCYCLE 0x10
|
||||
|
||||
#define ESCinit 0x01
|
||||
#define ESCpreop 0x02
|
||||
#define ESCboot 0x03
|
||||
#define ESCsafeop 0x04
|
||||
#define ESCop 0x08
|
||||
#define ESCerror 0x10
|
||||
|
||||
#define INIT_TO_INIT 0x11
|
||||
#define INIT_TO_PREOP 0x21
|
||||
#define INIT_TO_BOOT 0x31
|
||||
#define INIT_TO_SAFEOP 0x41
|
||||
#define INIT_TO_OP 0x81
|
||||
#define PREOP_TO_INIT 0x12
|
||||
#define PREOP_TO_PREOP 0x22
|
||||
#define PREOP_TO_BOOT 0x32
|
||||
#define PREOP_TO_SAFEOP 0x42
|
||||
#define PREOP_TO_OP 0x82
|
||||
#define BOOT_TO_INIT 0x13
|
||||
#define BOOT_TO_PREOP 0x23
|
||||
#define BOOT_TO_BOOT 0x33
|
||||
#define BOOT_TO_SAFEOP 0x43
|
||||
#define BOOT_TO_OP 0x83
|
||||
#define SAFEOP_TO_INIT 0x14
|
||||
#define SAFEOP_TO_PREOP 0x24
|
||||
#define SAFEOP_TO_BOOT 0x34
|
||||
#define SAFEOP_TO_SAFEOP 0x44
|
||||
#define SAFEOP_TO_OP 0x84
|
||||
#define OP_TO_INIT 0x18
|
||||
#define OP_TO_PREOP 0x28
|
||||
#define OP_TO_BOOT 0x38
|
||||
#define OP_TO_SAFEOP 0x48
|
||||
#define OP_TO_OP 0x88
|
||||
|
||||
#define ALERR_NONE 0x0000
|
||||
#define ALERR_UNSPECIFIEDERROR 0x0001
|
||||
#define ALERR_NOMEMORY 0x0002
|
||||
#define ALERR_INVALIDSTATECHANGE 0x0011
|
||||
#define ALERR_UNKNOWNSTATE 0x0012
|
||||
#define ALERR_BOOTNOTSUPPORTED 0x0013
|
||||
#define ALERR_NOVALIDFIRMWARE 0x0014
|
||||
#define ALERR_INVALIDBOOTMBXCONFIG 0x0015
|
||||
#define ALERR_INVALIDMBXCONFIG 0x0016
|
||||
#define ALERR_INVALIDSMCONFIG 0x0017
|
||||
#define ALERR_NOVALIDINPUTS 0x0018
|
||||
#define ALERR_NOVALIDOUTPUTS 0x0019
|
||||
#define ALERR_SYNCERROR 0x001A
|
||||
#define ALERR_WATCHDOG 0x001B
|
||||
#define ALERR_INVALIDSYNCMANAGERTYP 0x001C
|
||||
#define ALERR_INVALIDOUTPUTSM 0x001D
|
||||
#define ALERR_INVALIDINPUTSM 0x001E
|
||||
#define ALERR_INVALIDWDTCFG 0x001F
|
||||
#define ALERR_SLAVENEEDSCOLDSTART 0x0020
|
||||
#define ALERR_SLAVENEEDSINIT 0x0021
|
||||
#define ALERR_SLAVENEEDSPREOP 0x0022
|
||||
#define ALERR_SLAVENEEDSSAFEOP 0x0023
|
||||
#define ALERR_INVALIDINPUTMAPPING 0x0024
|
||||
#define ALERR_INVALIDOUTPUTMAPPING 0x0025
|
||||
#define ALERR_INCONSISTENTSETTINGS 0x0026
|
||||
#define ALERR_FREERUNNOTSUPPORTED 0x0027
|
||||
#define ALERR_SYNCNOTSUPPORTED 0x0028
|
||||
#define ALERR_FREERUNNEEDS3BUFFMODE 0x0029
|
||||
#define ALERR_BACKGROUNDWATCHDOG 0x002A
|
||||
#define ALERR_NOVALIDINPUTSOUTPUTS 0x002B
|
||||
#define ALERR_FATALSYNCERROR 0x002C
|
||||
#define ALERR_NOSYNCERROR 0x002D
|
||||
#define ALERR_INVALIDINPUTFMMUCFG 0x002E
|
||||
#define ALERR_DCINVALIDSYNCCFG 0x0030
|
||||
#define ALERR_INVALIDDCLATCHCFG 0x0031
|
||||
#define ALERR_PLLERROR 0x0032
|
||||
#define ALERR_DCSYNCIOERROR 0x0033
|
||||
#define ALERR_DCSYNCTIMEOUT 0x0034
|
||||
#define ALERR_DCSYNCCYCLETIME 0x0035
|
||||
#define ALERR_DCSYNC0CYCLETIME 0x0036
|
||||
#define ALERR_DCSYNC1CYCLETIME 0x0037
|
||||
#define ALERR_MBXAOE 0x0041
|
||||
#define ALERR_MBXEOE 0x0042
|
||||
#define ALERR_MBXCOE 0x0043
|
||||
#define ALERR_MBXFOE 0x0044
|
||||
#define ALERR_MBXSOE 0x0045
|
||||
#define ALERR_MBXVOE 0x004F
|
||||
#define ALERR_EEPROMNOACCESS 0x0050
|
||||
#define ALERR_EEPROMERROR 0x0051
|
||||
#define ALERR_SLAVERESTARTEDLOCALLY 0x0060
|
||||
#define ALERR_DEVICEIDVALUEUPDATED 0x0061
|
||||
#define ALERR_APPLCTRLAVAILABLE 0x00f0
|
||||
#define ALERR_UNKNOWN 0xffff
|
||||
|
||||
#define MBXERR_SYNTAX 0x0001
|
||||
#define MBXERR_UNSUPPORTEDPROTOCOL 0x0002
|
||||
#define MBXERR_INVALIDCHANNEL 0x0003
|
||||
#define MBXERR_SERVICENOTSUPPORTED 0x0004
|
||||
#define MBXERR_INVALIDHEADER 0x0005
|
||||
#define MBXERR_SIZETOOSHORT 0x0006
|
||||
#define MBXERR_NOMOREMEMORY 0x0007
|
||||
#define MBXERR_INVALIDSIZE 0x0008
|
||||
|
||||
#define ABORT_NOTOGGLE 0x05030000
|
||||
#define ABORT_TRANSFER_TIMEOUT 0x05040000
|
||||
#define ABORT_UNKNOWN 0x05040001
|
||||
#define ABORT_INVALID_BLOCK_SIZE 0x05040002
|
||||
#define ABORT_INVALID_SEQUENCE_NUMBER 0x05040003
|
||||
#define ABORT_BLOCK_CRC_ERROR 0x05040004
|
||||
#define ABORT_OUT_OF_MEMORY 0x05040005
|
||||
#define ABORT_UNSUPPORTED 0x06010000
|
||||
#define ABORT_WRITEONLY 0x06010001
|
||||
#define ABORT_READONLY 0x06010002
|
||||
#define ABORT_SUBINDEX0_NOT_ZERO 0x06010003
|
||||
#define ABORT_CA_NOT_SUPPORTED 0x06010004
|
||||
#define ABORT_EXCEEDS_MBOX_SIZE 0x06010005
|
||||
#define ABORT_SDO_DOWNLOAD_BLOCKED 0x06010006
|
||||
#define ABORT_NOOBJECT 0x06020000
|
||||
#define ABORT_MAPPING_OBJECT_ERROR 0x06040041
|
||||
#define ABORT_MAPPING_LENGTH_ERROR 0x06040042
|
||||
#define ABORT_GENERAL_PARAMETER_ERROR 0x06040043
|
||||
#define ABORT_GENERAL_DEVICE_ERROR 0x06040047
|
||||
#define ABORT_HARDWARE_ERROR 0x06060000
|
||||
#define ABORT_TYPEMISMATCH 0x06070010
|
||||
#define ABORT_DATATYPE_TOO_HIGH 0x06070012
|
||||
#define ABORT_DATATYPE_TOO_LOW 0x06070013
|
||||
#define ABORT_NOSUBINDEX 0x06090011
|
||||
#define ABORT_VALUE_EXCEEDED 0x06090030
|
||||
#define ABORT_VALUE_TOO_HIGH 0x06090031
|
||||
#define ABORT_VALUE_TOO_LOW 0x06090032
|
||||
#define ABORT_MODULE_LIST_MISMATCH 0x06090033
|
||||
#define ABORT_MAX_VAL_LESS_THAN_MIN_VAL 0x06090036
|
||||
#define ABORT_RESOURCE_NOT_AVAILABLE 0x060A0023
|
||||
#define ABORT_GENERALERROR 0x08000000
|
||||
#define ABORT_DATA_STORE_ERROR 0x08000020
|
||||
#define ABORT_DATA_STORE_LOCAL_ERROR 0x08000021
|
||||
#define ABORT_NOTINTHISSTATE 0x08000022
|
||||
#define ABORT_OBJECT_DICTIONARY_ERROR 0x08000023
|
||||
#define ABORT_NO_DATA_AVAILABLE 0x08000024
|
||||
|
||||
#define MBXstate_idle 0x00
|
||||
#define MBXstate_inclaim 0x01
|
||||
#define MBXstate_outclaim 0x02
|
||||
#define MBXstate_outreq 0x03
|
||||
#define MBXstate_outpost 0x04
|
||||
#define MBXstate_backup 0x05
|
||||
#define MBXstate_again 0x06
|
||||
|
||||
#define COE_DEFAULTLENGTH 0x0a
|
||||
#define COE_HEADERSIZE 0x0a
|
||||
#define COE_SEGMENTHEADERSIZE 0x03
|
||||
#define COE_SDOREQUEST 0x02
|
||||
#define COE_SDORESPONSE 0x03
|
||||
#define COE_SDOINFORMATION 0x08
|
||||
#define COE_COMMAND_SDOABORT 0x80
|
||||
#define COE_COMMAND_UPLOADREQUEST 0x40
|
||||
#define COE_COMMAND_UPLOADRESPONSE 0x40
|
||||
#define COE_COMMAND_UPLOADSEGMENT 0x00
|
||||
#define COE_COMMAND_UPLOADSEGREQ 0x60
|
||||
#define COE_COMMAND_DOWNLOADREQUEST 0x20
|
||||
#define COE_COMMAND_DOWNLOADRESPONSE 0x60
|
||||
#define COE_COMMAND_DOWNLOADSEGREQ 0x00
|
||||
#define COE_COMMAND_DOWNLOADSEGRESP 0x20
|
||||
#define COE_COMMAND_LASTSEGMENTBIT 0x01
|
||||
#define COE_SIZE_INDICATOR 0x01
|
||||
#define COE_EXPEDITED_INDICATOR 0x02
|
||||
#define COE_COMPLETEACCESS 0x10
|
||||
#define COE_TOGGLEBIT 0x10
|
||||
#define COE_INFOERROR 0x07
|
||||
#define COE_GETODLISTRESPONSE 0x02
|
||||
#define COE_GETODRESPONSE 0x04
|
||||
#define COE_ENTRYDESCRIPTIONRESPONSE 0x06
|
||||
#define COE_VALUEINFO_ACCESS 0x01
|
||||
#define COE_VALUEINFO_OBJECT 0x02
|
||||
#define COE_VALUEINFO_MAPPABLE 0x04
|
||||
#define COE_VALUEINFO_TYPE 0x08
|
||||
#define COE_VALUEINFO_DEFAULT 0x10
|
||||
#define COE_VALUEINFO_MINIMUM 0x20
|
||||
#define COE_VALUEINFO_MAXIMUM 0x40
|
||||
#define COE_MINIMUM_LENGTH 8
|
||||
|
||||
#define MBXERR 0x00
|
||||
#define MBXAOE 0x01
|
||||
#define MBXEOE 0x02
|
||||
#define MBXCOE 0x03
|
||||
#define MBXFOE 0x04
|
||||
#define MBXODL 0x10
|
||||
#define MBXOD 0x20
|
||||
#define MBXED 0x30
|
||||
#define MBXSEU 0x40
|
||||
#define MBXSED 0x50
|
||||
|
||||
#define SMRESULT_ERRSM0 0x01
|
||||
#define SMRESULT_ERRSM1 0x02
|
||||
#define SMRESULT_ERRSM2 0x04
|
||||
#define SMRESULT_ERRSM3 0x08
|
||||
|
||||
#define FOE_ERR_NOTDEFINED 0x8000
|
||||
#define FOE_ERR_NOTFOUND 0x8001
|
||||
#define FOE_ERR_ACCESS 0x8002
|
||||
#define FOE_ERR_DISKFULL 0x8003
|
||||
#define FOE_ERR_ILLEGAL 0x8004
|
||||
#define FOE_ERR_PACKETNO 0x8005
|
||||
#define FOE_ERR_EXISTS 0x8006
|
||||
#define FOE_ERR_NOUSER 0x8007
|
||||
#define FOE_ERR_BOOTSTRAPONLY 0x8008
|
||||
#define FOE_ERR_NOTINBOOTSTRAP 0x8009
|
||||
#define FOE_ERR_NORIGHTS 0x800A
|
||||
#define FOE_ERR_PROGERROR 0x800B
|
||||
#define FOE_ERR_CHECKSUM 0x800C
|
||||
|
||||
#define FOE_OP_RRQ 1
|
||||
#define FOE_OP_WRQ 2
|
||||
#define FOE_OP_DATA 3
|
||||
#define FOE_OP_ACK 4
|
||||
#define FOE_OP_ERR 5
|
||||
#define FOE_OP_BUSY 6
|
||||
|
||||
#define FOE_READY 0
|
||||
#define FOE_WAIT_FOR_ACK 1
|
||||
#define FOE_WAIT_FOR_FINAL_ACK 2
|
||||
#define FOE_WAIT_FOR_DATA 3
|
||||
|
||||
#define EOE_RESULT_SUCCESS 0x0000
|
||||
#define EOE_RESULT_UNSPECIFIED_ERROR 0x0001
|
||||
#define EOE_RESULT_UNSUPPORTED_FRAME_TYPE 0x0002
|
||||
#define EOE_RESULT_NO_IP_SUPPORT 0x0201
|
||||
#define EOE_RESULT_NO_DHCP_SUPPORT 0x0202
|
||||
#define EOE_RESULT_NO_FILTER_SUPPORT 0x0401
|
||||
|
||||
#define APPSTATE_IDLE 0x00
|
||||
#define APPSTATE_INPUT 0x01
|
||||
#define APPSTATE_OUTPUT 0x02
|
||||
|
||||
#define PREALLOC_FACTOR 3
|
||||
#define PREALLOC_BUFFER_SIZE (PREALLOC_FACTOR * MBXSIZE)
|
||||
|
||||
typedef struct sm_cfg
|
||||
{
|
||||
uint16_t cfg_sma;
|
||||
uint16_t cfg_sml;
|
||||
uint16_t cfg_sme;
|
||||
uint8_t cfg_smc;
|
||||
uint8_t cfg_smact;
|
||||
}sm_cfg_t;
|
||||
|
||||
typedef struct esc_cfg
|
||||
{
|
||||
void * user_arg;
|
||||
int use_interrupt;
|
||||
int watchdog_cnt;
|
||||
bool skip_default_initialization;
|
||||
void (*set_defaults_hook) (void);
|
||||
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
void (*application_hook) (void);
|
||||
void (*safeoutput_override) (void);
|
||||
uint32_t (*pre_object_download_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
uint32_t (*post_object_download_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
uint32_t (*pre_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
uint32_t (*post_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
void (*rxpdo_override) (void);
|
||||
void (*txpdo_override) (void);
|
||||
void (*esc_hw_interrupt_enable) (uint32_t mask);
|
||||
void (*esc_hw_interrupt_disable) (uint32_t mask);
|
||||
void (*esc_hw_eep_handler) (void);
|
||||
uint16_t (*esc_check_dc_handler) (void);
|
||||
} esc_cfg_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t state;
|
||||
} _App;
|
||||
|
||||
// Attention! this struct is always little-endian
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t PSA;
|
||||
uint16_t Length;
|
||||
|
||||
#if defined(EC_LITTLE_ENDIAN)
|
||||
uint8_t Mode:2;
|
||||
uint8_t Direction:2;
|
||||
uint8_t IntECAT:1;
|
||||
uint8_t IntPDI:1;
|
||||
uint8_t WTE:1;
|
||||
uint8_t R1:1;
|
||||
|
||||
uint8_t IntW:1;
|
||||
uint8_t IntR:1;
|
||||
uint8_t R2:1;
|
||||
uint8_t MBXstat:1;
|
||||
uint8_t BUFstat:2;
|
||||
uint8_t R3:2;
|
||||
|
||||
uint8_t ECsm:1;
|
||||
uint8_t ECrep:1;
|
||||
uint8_t ECr4:4;
|
||||
uint8_t EClatchEC:1;
|
||||
uint8_t EClatchPDI:1;
|
||||
|
||||
uint8_t PDIsm:1;
|
||||
uint8_t PDIrep:1;
|
||||
uint8_t PDIr5:6;
|
||||
#endif
|
||||
|
||||
#if defined(EC_BIG_ENDIAN)
|
||||
uint8_t R1:1;
|
||||
uint8_t WTE:1;
|
||||
uint8_t IntPDI:1;
|
||||
uint8_t IntECAT:1;
|
||||
uint8_t Direction:2;
|
||||
uint8_t Mode:2;
|
||||
|
||||
uint8_t R3:2;
|
||||
uint8_t BUFstat:2;
|
||||
uint8_t MBXstat:1;
|
||||
uint8_t R2:1;
|
||||
uint8_t IntR:1;
|
||||
uint8_t IntW:1;
|
||||
|
||||
uint8_t EClatchPDI:1;
|
||||
uint8_t EClatchEC:1;
|
||||
uint8_t ECr4:4;
|
||||
uint8_t ECrep:1;
|
||||
uint8_t ECsm:1;
|
||||
|
||||
uint8_t PDIr5:6;
|
||||
uint8_t PDIrep:1;
|
||||
uint8_t PDIsm:1;
|
||||
#endif
|
||||
} _ESCsm;
|
||||
CC_PACKED_END
|
||||
|
||||
/* Attention! this struct is always little-endian */
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t PSA;
|
||||
uint16_t Length;
|
||||
uint8_t Command;
|
||||
uint8_t Status;
|
||||
uint8_t ActESC;
|
||||
uint8_t ActPDI;
|
||||
} _ESCsm2;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t PSA;
|
||||
uint16_t Length;
|
||||
uint8_t Command;
|
||||
} _ESCsmCompact;
|
||||
CC_PACKED_END
|
||||
|
||||
typedef struct
|
||||
{
|
||||
/* Configuration input is saved so the user variable may go out-of-scope */
|
||||
int use_interrupt;
|
||||
sm_cfg_t mb[2];
|
||||
sm_cfg_t mbboot[2];
|
||||
bool skip_default_initialization;
|
||||
void (*set_defaults_hook) (void);
|
||||
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
void (*application_hook) (void);
|
||||
void (*safeoutput_override) (void);
|
||||
uint32_t (*pre_object_download_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
uint32_t (*post_object_download_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
uint32_t (*pre_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
uint32_t (*post_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
void (*rxpdo_override) (void);
|
||||
void (*txpdo_override) (void);
|
||||
void (*esc_hw_interrupt_enable) (uint32_t mask);
|
||||
void (*esc_hw_interrupt_disable) (uint32_t mask);
|
||||
void (*esc_hw_eep_handler) (void);
|
||||
uint16_t (*esc_check_dc_handler) (void);
|
||||
uint8_t MBXrun;
|
||||
size_t activembxsize;
|
||||
sm_cfg_t * activemb0;
|
||||
sm_cfg_t * activemb1;
|
||||
uint16_t ESC_SM2_sml;
|
||||
uint16_t ESC_SM3_sml;
|
||||
uint8_t dcsync;
|
||||
uint16_t synccounterlimit;
|
||||
uint16_t ALstatus;
|
||||
uint16_t ALcontrol;
|
||||
uint16_t ALerror;
|
||||
uint16_t DLstatus;
|
||||
uint16_t address;
|
||||
uint8_t mbxcnt;
|
||||
uint8_t mbxincnt;
|
||||
uint8_t mbxoutpost;
|
||||
uint8_t mbxbackup;
|
||||
uint8_t xoe;
|
||||
uint8_t txcue;
|
||||
uint8_t mbxfree;
|
||||
uint8_t segmented;
|
||||
void *data;
|
||||
uint16_t entries;
|
||||
uint16_t frags;
|
||||
uint16_t fragsleft;
|
||||
uint16_t index;
|
||||
uint8_t subindex;
|
||||
uint16_t flags;
|
||||
|
||||
uint8_t toggle;
|
||||
|
||||
int sm2mappings;
|
||||
int sm3mappings;
|
||||
|
||||
uint8_t SMtestresult;
|
||||
uint32_t PrevTime;
|
||||
_ESCsm SM[4];
|
||||
/* Volatile since it may be read from ISR */
|
||||
volatile int watchdogcnt;
|
||||
volatile uint32_t Time;
|
||||
volatile uint16_t ALevent;
|
||||
volatile int8_t synccounter;
|
||||
volatile _App App;
|
||||
uint8_t mbxdata[PREALLOC_BUFFER_SIZE];
|
||||
} _ESCvar;
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t length;
|
||||
uint16_t address;
|
||||
|
||||
#if defined(EC_LITTLE_ENDIAN)
|
||||
uint8_t channel:6;
|
||||
uint8_t priority:2;
|
||||
|
||||
uint8_t mbxtype:4;
|
||||
uint8_t mbxcnt:4;
|
||||
#endif
|
||||
|
||||
#if defined(EC_BIG_ENDIAN)
|
||||
uint8_t priority:2;
|
||||
uint8_t channel:6;
|
||||
|
||||
uint8_t mbxcnt:4;
|
||||
uint8_t mbxtype:4;
|
||||
#endif
|
||||
} _MBXh;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh header;
|
||||
uint8_t b[0];
|
||||
} _MBX;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t numberservice;
|
||||
} _COEh;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
#if defined(EC_LITTLE_ENDIAN)
|
||||
uint8_t opcode:7;
|
||||
uint8_t incomplete:1;
|
||||
#endif
|
||||
|
||||
#if defined(EC_BIG_ENDIAN)
|
||||
uint8_t incomplete:1;
|
||||
uint8_t opcode:7;
|
||||
#endif
|
||||
|
||||
uint8_t reserved;
|
||||
uint16_t fragmentsleft;
|
||||
} _INFOh;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
uint16_t type;
|
||||
uint16_t detail;
|
||||
} _MBXerr;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_COEh coeheader;
|
||||
uint8_t command;
|
||||
uint16_t index;
|
||||
uint8_t subindex;
|
||||
uint32_t size;
|
||||
} _COEsdo;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_COEh coeheader;
|
||||
_INFOh infoheader;
|
||||
uint16_t index;
|
||||
uint16_t datatype;
|
||||
uint8_t maxsub;
|
||||
uint8_t objectcode;
|
||||
char name;
|
||||
} _COEobjdesc;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_COEh coeheader;
|
||||
_INFOh infoheader;
|
||||
uint16_t index;
|
||||
uint8_t subindex;
|
||||
uint8_t valueinfo;
|
||||
uint16_t datatype;
|
||||
uint16_t bitlength;
|
||||
uint16_t access;
|
||||
char name;
|
||||
} _COEentdesc;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint8_t opcode;
|
||||
uint8_t reserved;
|
||||
union
|
||||
{
|
||||
uint32_t password;
|
||||
uint32_t packetnumber;
|
||||
uint32_t errorcode;
|
||||
};
|
||||
} _FOEh;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_FOEh foeheader;
|
||||
union
|
||||
{
|
||||
char filename[0];
|
||||
uint8_t data[0];
|
||||
char errortext[0];
|
||||
};
|
||||
} _FOE;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t frameinfo1;
|
||||
union
|
||||
{
|
||||
uint16_t frameinfo2;
|
||||
uint16_t result;
|
||||
};
|
||||
} _EOEh;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_EOEh eoeheader;
|
||||
uint8_t data[0];
|
||||
} _EOE;
|
||||
CC_PACKED_END
|
||||
|
||||
/* state definition in mailbox
|
||||
* 0 : idle
|
||||
* 1 : claimed for inbox
|
||||
* 2 : claimed for outbox
|
||||
* 3 : request post outbox
|
||||
* 4 : outbox posted not send
|
||||
* 5 : backup outbox
|
||||
* 6 : mailbox needs to be transmitted again
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t state;
|
||||
} _MBXcontrol;
|
||||
|
||||
/* Stack reference to application configuration of the ESC */
|
||||
#define ESC_MBXSIZE (ESCvar.activembxsize)
|
||||
#define ESC_MBX0_sma (ESCvar.activemb0->cfg_sma)
|
||||
#define ESC_MBX0_sml (ESCvar.activemb0->cfg_sml)
|
||||
#define ESC_MBX0_sme (ESCvar.activemb0->cfg_sme)
|
||||
#define ESC_MBX0_smc (ESCvar.activemb0->cfg_smc)
|
||||
#define ESC_MBX1_sma (ESCvar.activemb1->cfg_sma)
|
||||
#define ESC_MBX1_sml (ESCvar.activemb1->cfg_sml)
|
||||
#define ESC_MBX1_sme (ESCvar.activemb1->cfg_sme)
|
||||
#define ESC_MBX1_smc (ESCvar.activemb1->cfg_smc)
|
||||
#define ESC_MBXBUFFERS (MBXBUFFERS)
|
||||
#define ESC_SM2_sma (SM2_sma)
|
||||
#define ESC_SM2_smc (SM2_smc)
|
||||
#define ESC_SM2_act (SM2_act)
|
||||
#define ESC_SM3_sma (SM3_sma)
|
||||
#define ESC_SM3_smc (SM3_smc)
|
||||
#define ESC_SM3_act (SM3_act)
|
||||
|
||||
#define ESC_MBXHSIZE sizeof(_MBXh)
|
||||
#define ESC_MBXDSIZE (ESC_MBXSIZE - ESC_MBXHSIZE)
|
||||
#define ESC_FOEHSIZE sizeof(_FOEh)
|
||||
#define ESC_FOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_FOEHSIZE))
|
||||
#define ESC_EOEHSIZE sizeof(_EOEh)
|
||||
#define ESC_EOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_EOEHSIZE))
|
||||
|
||||
void ESC_config (esc_cfg_t * cfg);
|
||||
void ESC_ALerror (uint16_t errornumber);
|
||||
void ESC_ALeventwrite (uint32_t event);
|
||||
uint32_t ESC_ALeventread (void);
|
||||
void ESC_ALeventmaskwrite (uint32_t mask);
|
||||
uint32_t ESC_ALeventmaskread (void);
|
||||
void ESC_ALstatus (uint8_t status);
|
||||
void ESC_ALstatusgotoerror (uint8_t status, uint16_t errornumber);
|
||||
void ESC_SMstatus (uint8_t n);
|
||||
uint8_t ESC_WDstatus (void);
|
||||
uint8_t ESC_claimbuffer (void);
|
||||
uint8_t ESC_startmbx (uint8_t state);
|
||||
void ESC_stopmbx (void);
|
||||
void MBX_error (uint16_t error);
|
||||
uint8_t ESC_mbxprocess (void);
|
||||
void ESC_xoeprocess (void);
|
||||
uint8_t ESC_startinput (uint8_t state);
|
||||
void ESC_stopinput (void);
|
||||
uint8_t ESC_startoutput (uint8_t state);
|
||||
void ESC_stopoutput (void);
|
||||
void ESC_state (void);
|
||||
void ESC_sm_act_event (void);
|
||||
|
||||
/* From hardware file */
|
||||
void ESC_read (uint16_t address, void *buf, uint16_t len);
|
||||
void ESC_write (uint16_t address, void *buf, uint16_t len);
|
||||
void ESC_init (const esc_cfg_t * cfg);
|
||||
void ESC_reset (void);
|
||||
|
||||
/* From application */
|
||||
extern void APP_safeoutput ();
|
||||
extern _ESCvar ESCvar;
|
||||
extern _MBXcontrol MBXcontrol[];
|
||||
extern uint8_t MBX[];
|
||||
extern _SMmap SMmap2[];
|
||||
extern _SMmap SMmap3[];
|
||||
|
||||
/* ATOMIC operations are used when running interrupt driven */
|
||||
#ifndef CC_ATOMIC_SET
|
||||
#define CC_ATOMIC_SET(var,val) (var = val)
|
||||
#endif
|
||||
|
||||
#ifndef CC_ATOMIC_GET
|
||||
#define CC_ATOMIC_GET(var) (var)
|
||||
#endif
|
||||
|
||||
#ifndef CC_ATOMIC_ADD
|
||||
#define CC_ATOMIC_ADD(var,val) (var += val)
|
||||
#endif
|
||||
|
||||
#ifndef CC_ATOMIC_SUB
|
||||
#define CC_ATOMIC_SUB(var,val) (var -= val)
|
||||
#endif
|
||||
|
||||
#ifndef CC_ATOMIC_AND
|
||||
#define CC_ATOMIC_AND(var,val) (var &= val)
|
||||
#endif
|
||||
|
||||
#ifndef CC_ATOMIC_OR
|
||||
#define CC_ATOMIC_OR(var,val) (var |= val)
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
||||
1783
Cards/EaserCAT-2000/Firmware/lib/soes/esc_coe.c
Executable file
1783
Cards/EaserCAT-2000/Firmware/lib/soes/esc_coe.c
Executable file
File diff suppressed because it is too large
Load Diff
135
Cards/EaserCAT-2000/Firmware/lib/soes/esc_coe.h
Executable file
135
Cards/EaserCAT-2000/Firmware/lib/soes/esc_coe.h
Executable file
@@ -0,0 +1,135 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for esc_coe.c
|
||||
*/
|
||||
|
||||
#ifndef __esc_coe__
|
||||
#define __esc_coe__
|
||||
|
||||
#include <cc.h>
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t subindex;
|
||||
uint16_t datatype;
|
||||
uint16_t bitlength;
|
||||
uint16_t flags;
|
||||
const char *name;
|
||||
uint32_t value;
|
||||
void *data;
|
||||
} _objd;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
uint16_t index;
|
||||
uint16_t objtype;
|
||||
uint8_t maxsub;
|
||||
uint8_t pad1;
|
||||
const char *name;
|
||||
const _objd *objdesc;
|
||||
} _objectlist;
|
||||
CC_PACKED_END
|
||||
|
||||
typedef struct
|
||||
{
|
||||
const _objd * obj;
|
||||
uint16_t offset;
|
||||
} _SMmap;
|
||||
|
||||
#define OBJH_READ 0
|
||||
#define OBJH_WRITE 1
|
||||
|
||||
#define OTYPE_DOMAIN 0x0002
|
||||
#define OTYPE_DEFTYPE 0x0005
|
||||
#define OTYPE_DEFSTRUCT 0x0006
|
||||
#define OTYPE_VAR 0x0007
|
||||
#define OTYPE_ARRAY 0x0008
|
||||
#define OTYPE_RECORD 0x0009
|
||||
|
||||
#define DTYPE_BOOLEAN 0x0001
|
||||
#define DTYPE_INTEGER8 0x0002
|
||||
#define DTYPE_INTEGER16 0x0003
|
||||
#define DTYPE_INTEGER32 0x0004
|
||||
#define DTYPE_UNSIGNED8 0x0005
|
||||
#define DTYPE_UNSIGNED16 0x0006
|
||||
#define DTYPE_UNSIGNED32 0x0007
|
||||
#define DTYPE_REAL32 0x0008
|
||||
#define DTYPE_VISIBLE_STRING 0x0009
|
||||
#define DTYPE_OCTET_STRING 0x000A
|
||||
#define DTYPE_UNICODE_STRING 0x000B
|
||||
#define DTYPE_INTEGER24 0x0010
|
||||
#define DTYPE_UNSIGNED24 0x0016
|
||||
#define DTYPE_INTEGER64 0x0015
|
||||
#define DTYPE_UNSIGNED64 0x001B
|
||||
#define DTYPE_REAL64 0x0011
|
||||
#define DTYPE_PDO_MAPPING 0x0021
|
||||
#define DTYPE_IDENTITY 0x0023
|
||||
#define DTYPE_BITARR8 0x002D
|
||||
#define DTYPE_BITARR16 0x002E
|
||||
#define DTYPE_BITARR32 0x002F
|
||||
#define DTYPE_BIT1 0x0030
|
||||
#define DTYPE_BIT2 0x0031
|
||||
#define DTYPE_BIT3 0x0032
|
||||
#define DTYPE_BIT4 0x0033
|
||||
#define DTYPE_BIT5 0x0034
|
||||
#define DTYPE_BIT6 0x0035
|
||||
#define DTYPE_BIT7 0x0036
|
||||
#define DTYPE_BIT8 0x0037
|
||||
#define DTYPE_ARRAY_OF_INT 0x0260
|
||||
#define DTYPE_ARRAY_OF_SINT 0x0261
|
||||
#define DTYPE_ARRAY_OF_DINT 0x0262
|
||||
#define DTYPE_ARRAY_OF_UDINT 0x0263
|
||||
|
||||
#define ATYPE_Rpre 0x01
|
||||
#define ATYPE_Rsafe 0x02
|
||||
#define ATYPE_Rop 0x04
|
||||
#define ATYPE_Wpre 0x08
|
||||
#define ATYPE_Wsafe 0x10
|
||||
#define ATYPE_Wop 0x20
|
||||
#define ATYPE_RXPDO 0x40
|
||||
#define ATYPE_TXPDO 0x80
|
||||
|
||||
#define ATYPE_RO (ATYPE_Rpre | ATYPE_Rsafe | ATYPE_Rop)
|
||||
#define ATYPE_WO (ATYPE_Wpre | ATYPE_Wsafe | ATYPE_Wop)
|
||||
#define ATYPE_RW (ATYPE_RO | ATYPE_WO)
|
||||
#define ATYPE_RWpre (ATYPE_Wpre | ATYPE_RO)
|
||||
|
||||
#define TX_PDO_OBJIDX 0x1c13
|
||||
#define RX_PDO_OBJIDX 0x1c12
|
||||
|
||||
#define COMPLETE_ACCESS_FLAG (1 << 15)
|
||||
|
||||
void ESC_coeprocess (void);
|
||||
int16_t SDO_findsubindex (int16_t nidx, uint8_t subindex);
|
||||
int32_t SDO_findobject (uint16_t index);
|
||||
uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * sm, int max_mappings);
|
||||
void SDO_abort (uint16_t index, uint8_t subindex, uint32_t abortcode);
|
||||
void COE_initDefaultValues (void);
|
||||
|
||||
void COE_pdoPack (uint8_t * buffer, int nmappings, _SMmap * sm);
|
||||
void COE_pdoUnpack (uint8_t * buffer, int nmappings, _SMmap * sm);
|
||||
uint8_t COE_maxSub (uint16_t index);
|
||||
|
||||
extern uint32_t ESC_download_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
|
||||
extern uint32_t ESC_download_pre_objecthandler (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
extern uint32_t ESC_upload_pre_objecthandler (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
extern uint32_t ESC_upload_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
|
||||
extern const _objectlist SDOobjects[];
|
||||
|
||||
#endif
|
||||
80
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eep.c
Executable file
80
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eep.c
Executable file
@@ -0,0 +1,80 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* ESI EEPROM emulator module.
|
||||
*/
|
||||
|
||||
#include "cc.h"
|
||||
#include "esc.h"
|
||||
#include "esc_eep.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
static uint8_t eep_buf[8];
|
||||
|
||||
/** EPP periodic task of ESC side EEPROM emulation.
|
||||
*
|
||||
*/
|
||||
void EEP_process (void)
|
||||
{
|
||||
eep_stat_t stat;
|
||||
|
||||
/* check for eeprom event */
|
||||
if ((ESCvar.ALevent & ESCREG_ALEVENT_EEP) == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
while (1) {
|
||||
/* read eeprom status */
|
||||
ESC_read (ESCREG_EECONTSTAT, &stat, sizeof (eep_stat_t));
|
||||
stat.contstat.reg = etohs(stat.contstat.reg);
|
||||
stat.addr = etohl(stat.addr);
|
||||
|
||||
/* check busy flag, exit if job finished */
|
||||
if (!stat.contstat.bits.busy) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* clear error bits */
|
||||
stat.contstat.bits.csumErr = 0;
|
||||
stat.contstat.bits.eeLoading = 0;
|
||||
stat.contstat.bits.ackErr = 0;
|
||||
stat.contstat.bits.wrErr = 0;
|
||||
|
||||
/* process commands */
|
||||
switch (stat.contstat.bits.cmdReg) {
|
||||
case EEP_CMD_IDLE:
|
||||
break;
|
||||
|
||||
case EEP_CMD_READ:
|
||||
case EEP_CMD_RELOAD:
|
||||
/* handle read request */
|
||||
if (EEP_read (stat.addr * sizeof(uint16_t), eep_buf, EEP_READ_SIZE) != 0) {
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
} else {
|
||||
ESC_write (ESCREG_EEDATA, eep_buf, EEP_READ_SIZE);
|
||||
}
|
||||
break;
|
||||
|
||||
case EEP_CMD_WRITE:
|
||||
/* handle write request */
|
||||
ESC_read (ESCREG_EEDATA, eep_buf, EEP_WRITE_SIZE);
|
||||
if (EEP_write (stat.addr * sizeof(uint16_t), eep_buf, EEP_WRITE_SIZE) != 0) {
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
}
|
||||
|
||||
/* acknowledge command */
|
||||
stat.contstat.reg = htoes(stat.contstat.reg);
|
||||
ESC_write (ESCREG_EECONTSTAT, &stat.contstat.reg, sizeof(uint16_t));
|
||||
}
|
||||
}
|
||||
|
||||
77
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eep.h
Executable file
77
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eep.h
Executable file
@@ -0,0 +1,77 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for esc_eep.c
|
||||
*/
|
||||
|
||||
#ifndef __esc_eep__
|
||||
#define __esc_eep__
|
||||
|
||||
#include <cc.h>
|
||||
#include "esc.h"
|
||||
|
||||
/* EEPROM commands */
|
||||
#define EEP_CMD_IDLE 0x0
|
||||
#define EEP_CMD_READ 0x1
|
||||
#define EEP_CMD_WRITE 0x2
|
||||
#define EEP_CMD_RELOAD 0x3
|
||||
|
||||
/* read/write size */
|
||||
#define EEP_READ_SIZE 8
|
||||
#define EEP_WRITE_SIZE 2
|
||||
|
||||
/* CONSTAT register content */
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
union {
|
||||
uint16_t reg;
|
||||
struct {
|
||||
uint8_t wrEnable:1;
|
||||
uint8_t reserved:4;
|
||||
uint8_t eeEmulated:1;
|
||||
uint8_t eightByteRead:1;
|
||||
uint8_t twoByteAddr:1;
|
||||
|
||||
uint8_t cmdReg:3;
|
||||
uint8_t csumErr:1;
|
||||
uint8_t eeLoading:1;
|
||||
uint8_t ackErr:1;
|
||||
uint8_t wrErr:1;
|
||||
uint8_t busy:1;
|
||||
} bits;
|
||||
} contstat;
|
||||
|
||||
uint32_t addr;
|
||||
} eep_stat_t;
|
||||
|
||||
/**
|
||||
* ECAT EEPROM configuration area data structure
|
||||
*/
|
||||
typedef union eep_config
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint16_t pdi_control;
|
||||
uint16_t pdi_configuration;
|
||||
uint16_t sync_impulse_len;
|
||||
uint16_t pdi_configuration2;
|
||||
uint16_t configured_station_alias;
|
||||
uint8_t reserved[4];
|
||||
uint16_t checksum;
|
||||
};
|
||||
uint32_t dword[4]; /**< Four 32 bit double word equivalent to 8 16 bit configuration area word. */
|
||||
}eep_config_t;
|
||||
|
||||
/* periodic task */
|
||||
void EEP_process (void);
|
||||
|
||||
/* From hardware file */
|
||||
void EEP_init (void);
|
||||
int8_t EEP_read (uint32_t addr, uint8_t *data, uint16_t size);
|
||||
int8_t EEP_write (uint32_t addr, uint8_t *data, uint16_t size);
|
||||
|
||||
#endif
|
||||
1066
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eoe.c
Executable file
1066
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eoe.c
Executable file
File diff suppressed because it is too large
Load Diff
68
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eoe.h
Executable file
68
Cards/EaserCAT-2000/Firmware/lib/soes/esc_eoe.h
Executable file
@@ -0,0 +1,68 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for esc_eoe.c
|
||||
*/
|
||||
|
||||
#ifndef __esc_eoe__
|
||||
#define __esc_eoe__
|
||||
|
||||
#include <cc.h>
|
||||
|
||||
typedef struct eoe_pbuf
|
||||
{
|
||||
/** Pointer to frame buffer type used by a TCP/IP stack. (Not mandatory) */
|
||||
void * pbuf;
|
||||
/** Pointer to frame buffer to send or read from */
|
||||
uint8_t * payload;
|
||||
/** Length of data in frame buffer */
|
||||
size_t len;
|
||||
} eoe_pbuf_t;
|
||||
|
||||
typedef struct eoe_cfg
|
||||
{
|
||||
/** Callback function to get a frame buffer for storage of received frame */
|
||||
void (*get_buffer) (eoe_pbuf_t * ebuf);
|
||||
/** Callback function to free a frame buffer */
|
||||
void (*free_buffer) (eoe_pbuf_t * ebuf);
|
||||
/** Callback function to read local settings and update EtherCAT variables
|
||||
* to be delivered to the EtherCAT Master
|
||||
*/
|
||||
int (*load_eth_settings) (void);
|
||||
/** Callback function to read settings provided by the EtherCAT master
|
||||
* and store to local settings.
|
||||
*/
|
||||
int (*store_ethernet_settings) (void);
|
||||
/** Callback to frame receive function in TCP(IP stack,
|
||||
* caller should free the buffer
|
||||
* */
|
||||
void (*handle_recv_buffer) (uint8_t port, eoe_pbuf_t * ebuf);
|
||||
/** Callback to fetch a buffer to send */
|
||||
int (*fetch_send_buffer) (uint8_t port, eoe_pbuf_t * ebuf);
|
||||
/** Callback to notify the application fragment sent */
|
||||
void (*fragment_sent_event) (void);
|
||||
} eoe_cfg_t;
|
||||
|
||||
int EOE_ecat_get_mac (uint8_t port, uint8_t mac[]);
|
||||
int EOE_ecat_get_ip (uint8_t port, uint32_t * ip);
|
||||
int EOE_ecat_get_subnet (uint8_t port, uint32_t * subnet);
|
||||
int EOE_ecat_get_gateway (uint8_t port, uint32_t * default_gateway);
|
||||
int EOE_ecat_get_dns_ip (uint8_t port, uint32_t * dns_ip);
|
||||
int EOE_ecat_get_dns_name (uint8_t port, char * dns_name);
|
||||
int EOE_ecat_set_mac (uint8_t port, uint8_t mac[]);
|
||||
int EOE_ecat_set_ip (uint8_t port, uint32_t ip);
|
||||
int EOE_ecat_set_subnet (uint8_t port, uint32_t subnet);
|
||||
int EOE_ecat_set_gateway (uint8_t port, uint32_t default_gateway);
|
||||
int EOE_ecat_set_dns_ip (uint8_t port, uint32_t dns_ip);
|
||||
int EOE_ecat_set_dns_name (uint8_t port, char * dns_name);
|
||||
|
||||
void EOE_config (eoe_cfg_t * cfg);
|
||||
void EOE_init (void);
|
||||
void ESC_eoeprocess (void);
|
||||
void ESC_eoeprocess_tx (void);
|
||||
|
||||
#endif
|
||||
627
Cards/EaserCAT-2000/Firmware/lib/soes/esc_foe.c
Executable file
627
Cards/EaserCAT-2000/Firmware/lib/soes/esc_foe.c
Executable file
@@ -0,0 +1,627 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* File over EtherCAT (FoE) module.
|
||||
*/
|
||||
|
||||
|
||||
#include <cc.h>
|
||||
#include "esc.h"
|
||||
#include "esc_foe.h"
|
||||
#include <string.h>
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* File over EtherCAT (FoE) module.
|
||||
*
|
||||
* FOE read / write and FOE service functions
|
||||
*/
|
||||
|
||||
//define if FOE_read should be supported
|
||||
//#define FOE_READ_SUPPORTED
|
||||
|
||||
/** Variable holding current filename read at FOE Open.
|
||||
*/
|
||||
static char foe_file_name[FOE_FN_MAX + 1];
|
||||
|
||||
|
||||
/** Main FoE configuration pointer data array. Structure is allocated and filled
|
||||
* by the application defining what preferences it requires.
|
||||
*/
|
||||
static foe_cfg_t * foe_cfg;
|
||||
/** Pointer to current file configuration item used by FoE.
|
||||
*/
|
||||
static foe_file_cfg_t * foe_file;
|
||||
/** Main FoE status data array. Structure gets filled with current status
|
||||
* variables during FoE usage.
|
||||
*/
|
||||
static _FOEvar FOEvar;
|
||||
|
||||
/** Validate a write or read request by checking filename and password.
|
||||
*
|
||||
* @param[in] name = Filename
|
||||
* @param[in] num_chars = Length of filename
|
||||
* @param[in] pass = Numeric variable of password
|
||||
* @param[in] op = Request op-code
|
||||
* @return 0= if we succeed, FOE_ERR_NOTFOUND something wrong with filename or
|
||||
* password
|
||||
*/
|
||||
static int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
|
||||
{
|
||||
uint32_t i;
|
||||
|
||||
/* Unpack the file name into characters we can look at. */
|
||||
if (num_chars > FOE_FN_MAX)
|
||||
{
|
||||
num_chars = FOE_FN_MAX;
|
||||
}
|
||||
|
||||
for (i = 0; i < num_chars; i++)
|
||||
{
|
||||
foe_file_name[i] = name[i];
|
||||
}
|
||||
foe_file_name[i] = '\0';
|
||||
|
||||
/* Figure out what file they're talking about. */
|
||||
for (i = 0; i < foe_cfg->n_files; i++)
|
||||
{
|
||||
if (0 == strncmp (foe_file_name, foe_cfg->files[i].name, num_chars))
|
||||
{
|
||||
if (pass != foe_cfg->files[i].filepass)
|
||||
{
|
||||
return FOE_ERR_NORIGHTS;
|
||||
}
|
||||
|
||||
if (op == FOE_OP_WRQ &&
|
||||
(foe_cfg->files[i].write_only_in_boot) &&
|
||||
(ESCvar.ALstatus != ESCboot))
|
||||
{
|
||||
return FOE_ERR_NOTINBOOTSTRAP;
|
||||
}
|
||||
|
||||
foe_file = &foe_cfg->files[i];
|
||||
foe_file->address_offset = 0;
|
||||
foe_file->total_size = 0;
|
||||
switch (op)
|
||||
{
|
||||
case FOE_OP_RRQ:
|
||||
{
|
||||
FOEvar.fposition = 0;
|
||||
FOEvar.fend = foe_cfg->files[i].max_data;
|
||||
return 0;
|
||||
}
|
||||
case FOE_OP_WRQ:
|
||||
{
|
||||
FOEvar.fposition = 0;
|
||||
FOEvar.fend = foe_cfg->files[i].max_data;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return FOE_ERR_NOTFOUND;
|
||||
}
|
||||
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
/** Function writing local data to mailbox buffer to be sent as next FoE frame.
|
||||
* It will try to fill the Mailbox buffer available if there is enough data
|
||||
* left to read.
|
||||
*
|
||||
* @param[in] data = pointer to buffer
|
||||
* @param[in] maxlength = max length of data possible to read, controlled by
|
||||
* Mailbox - FoE and Mailbox frame headers.
|
||||
|
||||
* @return Number of copied bytes.
|
||||
*/
|
||||
static uint16_t FOE_fread (uint8_t * data, uint16_t maxlength)
|
||||
{
|
||||
uint16_t ncopied = 0;
|
||||
|
||||
while (maxlength && (FOEvar.fend - FOEvar.fposition))
|
||||
{
|
||||
maxlength--;
|
||||
*(data++) = foe_cfg->fbuffer[FOEvar.fposition++];
|
||||
ncopied++;
|
||||
}
|
||||
|
||||
return ncopied;
|
||||
}
|
||||
#endif
|
||||
|
||||
/** Function reading mailbox buffer to local buffer to be handled by
|
||||
* application write hook. Ex. flash routine used by software update.
|
||||
* It will consume the buffer and call the write hook every time the configured
|
||||
* flush buffer limit is reached.
|
||||
*
|
||||
*
|
||||
* @param[in] data = Pointer to buffer
|
||||
* @param[in] length = Length of data to read
|
||||
|
||||
* @return Number of copied bytes.
|
||||
*/
|
||||
static uint16_t FOE_fwrite (uint8_t *data, uint16_t length)
|
||||
{
|
||||
uint16_t ncopied = 0;
|
||||
uint32_t failed = 0;
|
||||
|
||||
DPRINT("FOE_fwrite\n");
|
||||
FOEvar.fprevposition = FOEvar.fposition;
|
||||
while (length && (FOEvar.fend - FOEvar.fposition) && !failed)
|
||||
{
|
||||
length--;
|
||||
foe_cfg->fbuffer[FOEvar.fbufposition++] = *(data++);
|
||||
if(FOEvar.fbufposition >= foe_cfg->buffer_size)
|
||||
{
|
||||
failed = foe_file->write_function (foe_file, foe_cfg->fbuffer, FOEvar.fbufposition);
|
||||
FOEvar.fbufposition = 0;
|
||||
foe_file->address_offset += foe_cfg->buffer_size;
|
||||
}
|
||||
FOEvar.fposition++;
|
||||
ncopied++;
|
||||
}
|
||||
|
||||
foe_file->total_size += ncopied;
|
||||
|
||||
DPRINT("FOE_fwrite END with : %d\n",ncopied);
|
||||
return ncopied;
|
||||
}
|
||||
|
||||
|
||||
/** Function handling the final FOE_fwrite when we close up regardless
|
||||
* if we have filled the buffers or not.
|
||||
*
|
||||
* @return Number of copied bytes on success, 0= if failed.
|
||||
*/
|
||||
static uint32_t FOE_fclose (void)
|
||||
{
|
||||
uint32_t failed = 0;
|
||||
|
||||
DPRINT("FOE_fclose\n");
|
||||
|
||||
failed = foe_file->write_function (foe_file, foe_cfg->fbuffer, FOEvar.fbufposition);
|
||||
foe_file->address_offset += FOEvar.fbufposition;
|
||||
FOEvar.fbufposition = 0;
|
||||
|
||||
return failed;
|
||||
}
|
||||
|
||||
/** Initialize by clearing all current status variables.
|
||||
*
|
||||
*/
|
||||
void FOE_init ()
|
||||
{
|
||||
DPRINT("FOE_init\n");
|
||||
FOEvar.foepacket = 0;
|
||||
FOEvar.foestate = FOE_READY;
|
||||
FOEvar.fposition = 0;
|
||||
FOEvar.fprevposition = 0;
|
||||
FOEvar.fbufposition = 0;
|
||||
}
|
||||
|
||||
/** Function for sending an FOE abort frame.
|
||||
*
|
||||
* @param[in] code = abort code
|
||||
*/
|
||||
static void FOE_abort (uint32_t code)
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint8_t mbxhandle;
|
||||
|
||||
if (code)
|
||||
{
|
||||
/* Send back an error packet. */
|
||||
mbxhandle = ESC_claimbuffer ();
|
||||
if (mbxhandle)
|
||||
{
|
||||
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
|
||||
foembx->mbxheader.length = htoes (ESC_FOEHSIZE); /* Don't bother with error text for now. */
|
||||
foembx->mbxheader.mbxtype = MBXFOE;
|
||||
foembx->foeheader.opcode = FOE_OP_ERR;
|
||||
foembx->foeheader.errorcode = htoel (code);
|
||||
MBXcontrol[mbxhandle].state = MBXstate_outreq;
|
||||
}
|
||||
/* Nothing we can do if we can't get an outbound mailbox. */
|
||||
}
|
||||
DPRINT("FOE_abort: 0x%X\n", code);
|
||||
FOE_init ();
|
||||
}
|
||||
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
/** Sends an FoE data frame, returning the number of data bytes
|
||||
* written or an error number.
|
||||
* Error numbers will be greater than FOE_DATA_SIZE.
|
||||
|
||||
* @param[in] data = pointer to buffer
|
||||
* @param[in] length = length of data to read
|
||||
|
||||
* @return Number of data bytes written or an error number. Error numbers
|
||||
* will be greater than FOE_DATA_SIZE.
|
||||
*/
|
||||
static int FOE_send_data_packet ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint16_t data_len;
|
||||
uint8_t mbxhandle;
|
||||
|
||||
mbxhandle = ESC_claimbuffer ();
|
||||
if (mbxhandle)
|
||||
{
|
||||
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
|
||||
data_len = FOE_fread (foembx->data, ESC_FOE_DATA_SIZE);
|
||||
foembx->foeheader.opcode = FOE_OP_DATA;
|
||||
foembx->foeheader.packetnumber = htoel (FOEvar.foepacket);
|
||||
FOEvar.foepacket++;
|
||||
foembx->mbxheader.length = htoes (data_len + ESC_FOEHSIZE);
|
||||
foembx->mbxheader.mbxtype = MBXFOE;
|
||||
/* Mark the outbound mailbox as filled. */
|
||||
MBXcontrol[mbxhandle].state = MBXstate_outreq;
|
||||
return data_len;
|
||||
}
|
||||
else
|
||||
{
|
||||
return FOE_ERR_PROGERROR;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/** Sends an FoE ack data frame.
|
||||
|
||||
* @return 0= or error number.
|
||||
*/
|
||||
static int FOE_send_ack ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint8_t mbxhandle;
|
||||
|
||||
mbxhandle = ESC_claimbuffer ();
|
||||
if (mbxhandle)
|
||||
{
|
||||
DPRINT("FOE_send_ack\n");
|
||||
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
|
||||
foembx->mbxheader.length = htoes (ESC_FOEHSIZE);
|
||||
foembx->mbxheader.mbxtype = MBXFOE;
|
||||
foembx->foeheader.opcode = FOE_OP_ACK;
|
||||
foembx->foeheader.packetnumber = htoel (FOEvar.foepacket);
|
||||
FOEvar.foepacket++;
|
||||
MBXcontrol[mbxhandle].state = MBXstate_outreq;
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
DPRINT("ERROR:FOE_send_ack\n");
|
||||
return FOE_ERR_PROGERROR;
|
||||
}
|
||||
}
|
||||
|
||||
/* Handlers for various FoE states. */
|
||||
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
/** FoE read request handler. Starts with Initialize, Open and Sending one frame.
|
||||
* When first frame have been sent we will send data from Ack.
|
||||
* On error we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
static void FOE_read ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint32_t data_len;
|
||||
uint32_t password;
|
||||
int res;
|
||||
|
||||
if (FOEvar.foestate != FOE_READY)
|
||||
{
|
||||
FOE_abort (FOE_ERR_ILLEGAL);
|
||||
return;
|
||||
}
|
||||
|
||||
FOE_init ();
|
||||
foembx = (_FOE *) &MBX[0];
|
||||
/* Get the length of the file name in octets. */
|
||||
data_len = etohs (foembx->mbxheader.length) - ESC_FOEHSIZE;
|
||||
password = etohl (foembx->foeheader.password);
|
||||
|
||||
res = FOE_fopen (foembx->filename, data_len, password, FOE_OP_RRQ);
|
||||
if (res == 0)
|
||||
{
|
||||
FOEvar.foepacket = 1;
|
||||
/*
|
||||
* Attempt to send the packet
|
||||
*/
|
||||
res = FOE_send_data_packet ();
|
||||
if (res <= (int)ESC_FOE_DATA_SIZE)
|
||||
{
|
||||
FOEvar.foestate = FOE_WAIT_FOR_ACK;
|
||||
}
|
||||
else
|
||||
{
|
||||
FOE_abort (res);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
FOE_abort (res);
|
||||
}
|
||||
}
|
||||
|
||||
/** FoE data ack handler. Will continue sending next frame until finished.
|
||||
* On error we will send FOE Abort.
|
||||
*/
|
||||
static void FOE_ack ()
|
||||
{
|
||||
int res;
|
||||
|
||||
/* Make sure we're able to take this. */
|
||||
if (FOEvar.foestate == FOE_WAIT_FOR_FINAL_ACK)
|
||||
{
|
||||
/* Move us back to ready state. */
|
||||
FOE_init ();
|
||||
return;
|
||||
}
|
||||
else if (FOEvar.foestate != FOE_WAIT_FOR_ACK)
|
||||
{
|
||||
FOE_abort (FOE_ERR_ILLEGAL);
|
||||
return;
|
||||
}
|
||||
res = FOE_send_data_packet ();
|
||||
if (res < (int)ESC_FOE_DATA_SIZE)
|
||||
{
|
||||
FOEvar.foestate = FOE_WAIT_FOR_FINAL_ACK;
|
||||
}
|
||||
else if (res >= FOE_ERR_NOTDEFINED)
|
||||
{
|
||||
FOE_abort (FOE_ERR_PROGERROR);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/** FoE write request handler. Starts with Initialize, Open and Ack that we can/will
|
||||
* receive data. On error we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
static void FOE_write ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint32_t data_len;
|
||||
uint32_t password;
|
||||
int res;
|
||||
|
||||
if (FOEvar.foestate != FOE_READY)
|
||||
{
|
||||
FOE_abort (FOE_ERR_ILLEGAL);
|
||||
return;
|
||||
}
|
||||
|
||||
FOE_init ();
|
||||
foembx = (_FOE *) &MBX[0];
|
||||
data_len = etohs (foembx->mbxheader.length) - ESC_FOEHSIZE;
|
||||
password = etohl (foembx->foeheader.password);
|
||||
|
||||
/* Get an address we can write the file to, if possible. */
|
||||
res = FOE_fopen (foembx->filename, data_len, password, FOE_OP_WRQ);
|
||||
DPRINT("%s %sOK, file \"%s\"\n", __func__, (res == 0) ? "" : "N", foe_file_name);
|
||||
if (res == 0)
|
||||
{
|
||||
res = FOE_send_ack ();
|
||||
if (res)
|
||||
{
|
||||
FOE_abort (res);
|
||||
}
|
||||
else
|
||||
{
|
||||
FOEvar.foestate = FOE_WAIT_FOR_DATA;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
FOE_abort (res);
|
||||
}
|
||||
}
|
||||
/** FoE data request handler. Validates and reads data until we're finished. Every
|
||||
* read frame followed by an Ack frame. On error we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
static void FOE_data ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint32_t packet;
|
||||
uint16_t data_len, ncopied;
|
||||
int res;
|
||||
|
||||
if(FOEvar.foestate != FOE_WAIT_FOR_DATA)
|
||||
{
|
||||
FOE_abort(FOE_ERR_ILLEGAL);
|
||||
return;
|
||||
}
|
||||
|
||||
foembx = (_FOE*)&MBX[0];
|
||||
data_len = etohs(foembx->mbxheader.length) - ESC_FOEHSIZE;
|
||||
packet = etohl(foembx->foeheader.packetnumber);
|
||||
|
||||
if (packet != FOEvar.foepacket)
|
||||
{
|
||||
DPRINT("FOE_data packet error, packet: %d, foeheader.packet: %d\n",packet,FOEvar.foepacket);
|
||||
FOE_abort (FOE_ERR_PACKETNO);
|
||||
}
|
||||
else if (data_len == 0)
|
||||
{
|
||||
DPRINT("FOE_data completed\n");
|
||||
FOE_fclose ();
|
||||
res = FOE_send_ack ();
|
||||
FOE_init ();
|
||||
}
|
||||
else if (FOEvar.fposition + data_len > FOEvar.fend)
|
||||
{
|
||||
DPRINT("FOE_data disk full\n");
|
||||
FOE_abort (FOE_ERR_DISKFULL);
|
||||
}
|
||||
else
|
||||
{
|
||||
ncopied = FOE_fwrite (foembx->data, data_len);
|
||||
if (!ncopied)
|
||||
{
|
||||
DPRINT("FOE_data no copied\n");
|
||||
FOE_abort (FOE_ERR_PROGERROR);
|
||||
}
|
||||
else if (data_len == ESC_FOE_DATA_SIZE)
|
||||
{
|
||||
DPRINT("FOE_data data_len == FOE_DATA_SIZE\n");
|
||||
if (ncopied != data_len)
|
||||
{
|
||||
DPRINT("FOE_data only %d of %d copied\n",ncopied, data_len);
|
||||
FOE_abort (FOE_ERR_PROGERROR);
|
||||
}
|
||||
res = FOE_send_ack ();
|
||||
if (res)
|
||||
{
|
||||
FOE_abort (res);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if ((ncopied != data_len) || FOE_fclose ())
|
||||
{
|
||||
DPRINT("FOE_fclose failed to write extra buffer\n");
|
||||
FOE_abort (FOE_ERR_PROGERROR);
|
||||
}
|
||||
else
|
||||
{
|
||||
DPRINT("FOE_data completed\n");
|
||||
res = FOE_send_ack ();
|
||||
FOE_init ();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
/** FoE read request busy handler. Send an Ack of last frame again. On error
|
||||
* we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
static void FOE_busy ()
|
||||
{
|
||||
/* Only valid if we're servicing a read request. */
|
||||
if (FOEvar.foestate != FOE_WAIT_FOR_ACK)
|
||||
{
|
||||
FOE_abort (FOE_ERR_ILLEGAL);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Send the last part again. */
|
||||
FOEvar.fposition = FOEvar.fprevposition;
|
||||
FOEvar.foepacket--;
|
||||
FOE_ack ();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/** FoE error requesthandler. Send an FOE Abort.
|
||||
*
|
||||
*/
|
||||
static void FOE_error ()
|
||||
{
|
||||
/* Master panic! abort the transfer. */
|
||||
FOE_abort (0);
|
||||
}
|
||||
|
||||
/** Function copying the application configuration variable
|
||||
* to the FoE module local pointer variable.
|
||||
*
|
||||
* @param[in] cfg = Pointer to by the Application static declared
|
||||
* configuration variable holding application specific details.
|
||||
*/
|
||||
void FOE_config (foe_cfg_t * cfg)
|
||||
{
|
||||
foe_cfg = cfg;
|
||||
}
|
||||
|
||||
/** Main FoE function checking the status on current mailbox buffers carrying
|
||||
* data, distributing the mailboxes to appropriate FOE functions depending
|
||||
* on requested opcode.
|
||||
* On Error an FoE Error or FoE Abort will be sent.
|
||||
*/
|
||||
void ESC_foeprocess (void)
|
||||
{
|
||||
_MBXh *mbh;
|
||||
_FOE *foembx;
|
||||
|
||||
if (ESCvar.MBXrun == 0)
|
||||
{
|
||||
return;
|
||||
}
|
||||
if (!ESCvar.xoe && (MBXcontrol[0].state == MBXstate_inclaim))
|
||||
{
|
||||
mbh = (_MBXh *) &MBX[0];
|
||||
if (mbh->mbxtype == MBXFOE)
|
||||
{
|
||||
ESCvar.xoe = MBXFOE;
|
||||
}
|
||||
}
|
||||
if (ESCvar.xoe == MBXFOE)
|
||||
{
|
||||
foembx = (_FOE *) &MBX[0];
|
||||
/* Verify the size of the file data. */
|
||||
if (etohs (foembx->mbxheader.length) < ESC_FOEHSIZE)
|
||||
{
|
||||
FOE_abort (MBXERR_SIZETOOSHORT);
|
||||
}
|
||||
else
|
||||
{
|
||||
switch (foembx->foeheader.opcode)
|
||||
{
|
||||
case FOE_OP_WRQ:
|
||||
{
|
||||
DPRINT("FOE_OP_WRQ\n");
|
||||
FOE_write ();
|
||||
break;
|
||||
}
|
||||
case FOE_OP_DATA:
|
||||
{
|
||||
DPRINT("FOE_OP_DATA\n");
|
||||
FOE_data ();
|
||||
break;
|
||||
}
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
case FOE_OP_RRQ:
|
||||
{
|
||||
DPRINT("FOE_OP_RRQ\n");
|
||||
FOE_read ();
|
||||
break;
|
||||
}
|
||||
case FOE_OP_ACK:
|
||||
{
|
||||
DPRINT("FOE_OP_ACK\n");
|
||||
FOE_ack ();
|
||||
break;
|
||||
}
|
||||
|
||||
case FOE_OP_BUSY:
|
||||
{
|
||||
DPRINT("FOE_OP_BUSY\n");
|
||||
FOE_busy ();
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
case FOE_OP_ERR:
|
||||
{
|
||||
DPRINT("FOE_OP_ERR\n");
|
||||
FOE_error ();
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
DPRINT("FOE_ERR_NOTDEFINED\n");
|
||||
FOE_abort (FOE_ERR_NOTDEFINED);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
MBXcontrol[0].state = MBXstate_idle;
|
||||
ESCvar.xoe = 0;
|
||||
}
|
||||
}
|
||||
77
Cards/EaserCAT-2000/Firmware/lib/soes/esc_foe.h
Executable file
77
Cards/EaserCAT-2000/Firmware/lib/soes/esc_foe.h
Executable file
@@ -0,0 +1,77 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for esc_foe.c
|
||||
*/
|
||||
|
||||
#ifndef __esc_foe__
|
||||
#define __esc_foe__
|
||||
|
||||
#include <cc.h>
|
||||
|
||||
/** Maximum number of characters allowed in a file name. */
|
||||
#define FOE_FN_MAX 31
|
||||
|
||||
typedef struct foe_file_cfg foe_file_cfg_t;
|
||||
struct foe_file_cfg
|
||||
{
|
||||
/** Name of file to receive from master */
|
||||
const char * name;
|
||||
/** Size of file,sizeof data we can recv */
|
||||
uint32_t max_data;
|
||||
/** Where to store the data initially */
|
||||
uint32_t dest_start_address;
|
||||
/** Current address during write of file */
|
||||
uint32_t address_offset;
|
||||
/** Calculated size of file received */
|
||||
uint32_t total_size;
|
||||
/** FoE password */
|
||||
uint32_t filepass;
|
||||
/** This file can be written only in BOOT state. Intended for FW files */
|
||||
uint8_t write_only_in_boot;
|
||||
/** for feature use */
|
||||
uint32_t padding:24;
|
||||
/** Pointer to application foe write function */
|
||||
uint32_t (*write_function) (foe_file_cfg_t * self, uint8_t * data, size_t length);
|
||||
};
|
||||
|
||||
typedef struct foe_cfg
|
||||
{
|
||||
/** Allocate static in caller func to fit buffer_size */
|
||||
uint8_t * fbuffer;
|
||||
/** Buffer size before we flush to destination */
|
||||
uint32_t buffer_size;
|
||||
/** Number of files used in firmware update */
|
||||
uint32_t n_files;
|
||||
/** Pointer to files configured to be used by FoE */
|
||||
foe_file_cfg_t * files;
|
||||
} foe_cfg_t;
|
||||
|
||||
typedef struct CC_PACKED
|
||||
{
|
||||
/** Current FoE state, ex. Waiting for ACK, Waiting for DATA */
|
||||
uint8_t foestate;
|
||||
/** Current file buffer position, evaluated against foe file buffer size
|
||||
* when to flush
|
||||
*/
|
||||
uint16_t fbufposition;
|
||||
/** Frame number in read or write sequence */
|
||||
uint32_t foepacket;
|
||||
/** Current position in file to be handled by FoE request */
|
||||
uint32_t fposition;
|
||||
/** Previous position in file to be handled by FoE request */
|
||||
uint32_t fprevposition;
|
||||
/** End position of allocated disk space for FoE requested file */
|
||||
uint32_t fend;
|
||||
} _FOEvar;
|
||||
|
||||
/* Initializes FoE state. */
|
||||
void FOE_config (foe_cfg_t * cfg);
|
||||
void FOE_init (void);
|
||||
void ESC_foeprocess (void);
|
||||
|
||||
#endif
|
||||
263
Cards/EaserCAT-2000/Firmware/lib/soes/esi.json
Executable file
263
Cards/EaserCAT-2000/Firmware/lib/soes/esi.json
Executable file
@@ -0,0 +1,263 @@
|
||||
{
|
||||
"form": {
|
||||
"VendorName": "MetalMusings",
|
||||
"VendorID": "0xaaa",
|
||||
"ProductCode": "0xbbbccc",
|
||||
"ProfileNo": "5001",
|
||||
"RevisionNumber": "0x002",
|
||||
"SerialNumber": "0x001",
|
||||
"HWversion": "0.0.1",
|
||||
"SWversion": "0.0.1",
|
||||
"EEPROMsize": "2048",
|
||||
"RxMailboxOffset": "0x1000",
|
||||
"TxMailboxOffset": "0x1200",
|
||||
"MailboxSize": "512",
|
||||
"SM2Offset": "0x1600",
|
||||
"SM3Offset": "0x1A00",
|
||||
"TextGroupType": "MachineControl",
|
||||
"TextGroupName5": "Incremental encoder",
|
||||
"ImageName": "IMGCBY",
|
||||
"TextDeviceType": "EaserCAT2000",
|
||||
"TextDeviceName": "MetalMusings EaserCAT 2000",
|
||||
"Port0Physical": "Y",
|
||||
"Port1Physical": "Y",
|
||||
"Port2Physical": " ",
|
||||
"Port3Physical": " ",
|
||||
"ESC": "LAN9252",
|
||||
"SPImode": "3",
|
||||
"CoeDetailsEnableSDO": "EnableSDO",
|
||||
"CoeDetailsEnableSDOInfo": "EnableSDOInfo",
|
||||
"CoeDetailsEnablePDOAssign": "EnablePDOAssign",
|
||||
"CoeDetailsEnablePDOConfiguration": "EnablePDOConfiguration",
|
||||
"CoeDetailsEnableUploadAtStartup": "EnableUploadAtStartup",
|
||||
"CoeDetailsEnableSDOCompleteAccess": "EnableSDOCompleteAccess"
|
||||
},
|
||||
"od": {
|
||||
"sdo": {
|
||||
"A": {
|
||||
"otype": "RECORD",
|
||||
"name": "Error Settings",
|
||||
"access": "RO",
|
||||
"items": [
|
||||
{
|
||||
"name": "Max SubIndex"
|
||||
},
|
||||
{
|
||||
"name": "New record subitem",
|
||||
"dtype": "UNSIGNED8"
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"txpdo": {
|
||||
"6000": {
|
||||
"otype": "VAR",
|
||||
"name": "EncPos",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"data": "&Obj.EncPos"
|
||||
},
|
||||
"6001": {
|
||||
"otype": "VAR",
|
||||
"name": "EncFrequency",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"data": "&Obj.EncFrequency"
|
||||
},
|
||||
"6002": {
|
||||
"otype": "VAR",
|
||||
"name": "DiffT",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED16",
|
||||
"value": "0",
|
||||
"data": "&Obj.DiffT"
|
||||
},
|
||||
"6003": {
|
||||
"otype": "VAR",
|
||||
"name": "IndexByte",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED32",
|
||||
"value": "0",
|
||||
"data": "&Obj.IndexByte"
|
||||
},
|
||||
"6004": {
|
||||
"otype": "VAR",
|
||||
"name": "IndexStatus",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED32",
|
||||
"value": "0",
|
||||
"data": "&Obj.IndexStatus"
|
||||
},
|
||||
"6005": {
|
||||
"otype": "VAR",
|
||||
"name": "ActualPosition1",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"data": "&Obj.ActualPosition1"
|
||||
},
|
||||
"6006": {
|
||||
"otype": "VAR",
|
||||
"name": "ActualPosition2",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"data": "&Obj.ActualPosition2"
|
||||
},
|
||||
"6007": {
|
||||
"otype": "VAR",
|
||||
"name": "D1",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "INTEGER16",
|
||||
"value": "0",
|
||||
"data": "&Obj.D1"
|
||||
},
|
||||
"6008": {
|
||||
"otype": "VAR",
|
||||
"name": "D2",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "INTEGER16",
|
||||
"value": "0",
|
||||
"data": "&Obj.D2"
|
||||
},
|
||||
"6009": {
|
||||
"otype": "VAR",
|
||||
"name": "D3",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "INTEGER16",
|
||||
"value": "0",
|
||||
"data": "&Obj.D3"
|
||||
},
|
||||
"600A": {
|
||||
"otype": "VAR",
|
||||
"name": "D4",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"txpdo"
|
||||
],
|
||||
"dtype": "INTEGER16",
|
||||
"value": "0",
|
||||
"data": "&Obj.D4"
|
||||
}
|
||||
},
|
||||
"rxpdo": {
|
||||
"7000": {
|
||||
"otype": "VAR",
|
||||
"name": "IndexLatchEnable",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "UNSIGNED32",
|
||||
"value": "0",
|
||||
"data": "&Obj.IndexLatchEnable"
|
||||
},
|
||||
"7001": {
|
||||
"otype": "VAR",
|
||||
"name": "CommandedPosition1",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"data": "&Obj.CommandedPosition1"
|
||||
},
|
||||
"7002": {
|
||||
"otype": "VAR",
|
||||
"name": "CommandedPosition2",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "REAL32",
|
||||
"value": "0",
|
||||
"data": "&Obj.CommandedPosition2"
|
||||
},
|
||||
"7003": {
|
||||
"otype": "VAR",
|
||||
"name": "StepsPerMM1",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER16",
|
||||
"value": "0",
|
||||
"data": "&Obj.StepsPerMM1"
|
||||
},
|
||||
"7004": {
|
||||
"otype": "VAR",
|
||||
"name": "StepsPerMM2",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER16",
|
||||
"value": "0",
|
||||
"data": "&Obj.StepsPerMM2"
|
||||
},
|
||||
"60664": {
|
||||
"otype": "VAR",
|
||||
"name": "ActualPosition",
|
||||
"access": "RO",
|
||||
"pdo_mappings": [
|
||||
"rxpdo"
|
||||
],
|
||||
"dtype": "INTEGER32",
|
||||
"value": "0"
|
||||
}
|
||||
}
|
||||
},
|
||||
"dc": [
|
||||
{
|
||||
"Name": "SM-Synchron",
|
||||
"Description": "SM-Synchron",
|
||||
"AssignActivate": "#x000",
|
||||
"Sync0cycleTime": "0",
|
||||
"Sync0shiftTime": "0",
|
||||
"Sync1cycleTime": "0",
|
||||
"Sync1shiftTime": "0"
|
||||
},
|
||||
{
|
||||
"Name": "DC",
|
||||
"Description": "DC-Synchron",
|
||||
"AssignActivate": "#x300",
|
||||
"Sync0cycleTime": "0",
|
||||
"Sync0shiftTime": "0",
|
||||
"Sync1cycleTime": "0",
|
||||
"Sync1shiftTime": "0"
|
||||
}
|
||||
]
|
||||
}
|
||||
458
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/esc_hw.c
Executable file
458
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/esc_hw.c
Executable file
@@ -0,0 +1,458 @@
|
||||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* ESC hardware layer functions for LAN9252.
|
||||
*
|
||||
* Function to read and write commands to the ESC. Used to read/write ESC
|
||||
* registers and memory.
|
||||
*/
|
||||
#include "esc.h"
|
||||
#include "spi.h"
|
||||
#include <string.h>
|
||||
|
||||
|
||||
#define O_RDWR 1
|
||||
|
||||
#define BIT(x) 1 << (x)
|
||||
|
||||
#define ESC_CMD_SERIAL_WRITE 0x02
|
||||
#define ESC_CMD_SERIAL_READ 0x03
|
||||
#define ESC_CMD_FAST_READ 0x0B
|
||||
#define ESC_CMD_RESET_SQI 0xFF
|
||||
|
||||
#define ESC_CMD_FAST_READ_DUMMY 1
|
||||
#define ESC_CMD_ADDR_INC BIT(6)
|
||||
|
||||
#define ESC_PRAM_RD_FIFO_REG 0x000
|
||||
#define ESC_PRAM_WR_FIFO_REG 0x020
|
||||
#define ESC_PRAM_RD_ADDR_LEN_REG 0x308
|
||||
#define ESC_PRAM_RD_CMD_REG 0x30C
|
||||
#define ESC_PRAM_WR_ADDR_LEN_REG 0x310
|
||||
#define ESC_PRAM_WR_CMD_REG 0x314
|
||||
|
||||
#define ESC_PRAM_CMD_BUSY BIT(31)
|
||||
#define ESC_PRAM_CMD_ABORT BIT(30)
|
||||
|
||||
#define ESC_PRAM_CMD_CNT(x) ((x >> 8) & 0x1F)
|
||||
#define ESC_PRAM_CMD_AVAIL BIT(0)
|
||||
|
||||
#define ESC_PRAM_SIZE(x) ((x) << 16)
|
||||
#define ESC_PRAM_ADDR(x) ((x) << 0)
|
||||
|
||||
#define ESC_CSR_DATA_REG 0x300
|
||||
#define ESC_CSR_CMD_REG 0x304
|
||||
|
||||
#define ESC_CSR_CMD_BUSY BIT(31)
|
||||
#define ESC_CSR_CMD_READ (BIT(31) | BIT(30))
|
||||
#define ESC_CSR_CMD_WRITE BIT(31)
|
||||
#define ESC_CSR_CMD_SIZE(x) (x << 16)
|
||||
|
||||
#define ESC_RESET_CTRL_REG 0x1F8
|
||||
#define ESC_RESET_CTRL_RST BIT(6)
|
||||
#define ESC_DIGITAL_RST 0x00000001
|
||||
|
||||
#define ESC_ID_REV_REG 0x050
|
||||
#define LAN9252_ID_REV 0x9252
|
||||
|
||||
#define ESC_IRQ_CFG_REG 0x054
|
||||
#define ESC_INT_EN_REG 0x05C
|
||||
#define ESC_BYTE_TEST_REG 0x064
|
||||
#define ESC_TEST_VALUE 0x87654321
|
||||
|
||||
#define ESC_HW_CFG_REG 0x074
|
||||
#define ESC_READY BIT(27)
|
||||
|
||||
|
||||
static int lan9252 = -1;
|
||||
|
||||
/* lan9252 singel write */
|
||||
static void lan9252_write_32 (uint16_t address, uint32_t val)
|
||||
{
|
||||
uint8_t data[7];
|
||||
|
||||
data[0] = ESC_CMD_SERIAL_WRITE;
|
||||
data[1] = ((address >> 8) & 0xFF);
|
||||
data[2] = (address & 0xFF);
|
||||
data[3] = (val & 0xFF);
|
||||
data[4] = ((val >> 8) & 0xFF);
|
||||
data[5] = ((val >> 16) & 0xFF);
|
||||
data[6] = ((val >> 24) & 0xFF);
|
||||
|
||||
/* Select device. */
|
||||
spi_select (lan9252);
|
||||
/* Write data */
|
||||
write (lan9252, data, sizeof(data));
|
||||
/* Un-select device. */
|
||||
spi_unselect (lan9252);
|
||||
}
|
||||
|
||||
/* lan9252 single read */
|
||||
static uint32_t lan9252_read_32 (uint32_t address)
|
||||
{
|
||||
uint8_t data[4];
|
||||
uint8_t result[4];
|
||||
|
||||
data[0] = ESC_CMD_FAST_READ;
|
||||
data[1] = ((address >> 8) & 0xFF);
|
||||
data[2] = (address & 0xFF);
|
||||
data[3] = ESC_CMD_FAST_READ_DUMMY;
|
||||
|
||||
/* Select device. */
|
||||
spi_select (lan9252);
|
||||
/* Read data */
|
||||
write (lan9252, data, sizeof(data));
|
||||
read (lan9252, result, sizeof(result));
|
||||
/* Un-select device. */
|
||||
spi_unselect (lan9252);
|
||||
|
||||
return ((result[3] << 24) |
|
||||
(result[2] << 16) |
|
||||
(result[1] << 8) |
|
||||
result[0]);
|
||||
}
|
||||
|
||||
/* ESC read CSR function */
|
||||
static void ESC_read_csr (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
|
||||
value = (ESC_CSR_CMD_READ | ESC_CSR_CMD_SIZE(len) | address);
|
||||
lan9252_write_32(ESC_CSR_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_CSR_CMD_REG);
|
||||
} while(value & ESC_CSR_CMD_BUSY);
|
||||
|
||||
value = lan9252_read_32(ESC_CSR_DATA_REG);
|
||||
memcpy(buf, (uint8_t *)&value, len);
|
||||
}
|
||||
|
||||
/* ESC write CSR function */
|
||||
static void ESC_write_csr (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
|
||||
memcpy((uint8_t*)&value, buf,len);
|
||||
lan9252_write_32(ESC_CSR_DATA_REG, value);
|
||||
value = (ESC_CSR_CMD_WRITE | ESC_CSR_CMD_SIZE(len) | address);
|
||||
lan9252_write_32(ESC_CSR_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_CSR_CMD_REG);
|
||||
} while(value & ESC_CSR_CMD_BUSY);
|
||||
}
|
||||
|
||||
/* ESC read process data ram function */
|
||||
/*static*/ void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
uint8_t * temp_buf = (uint8_t *)buf;
|
||||
uint16_t byte_offset = 0;
|
||||
uint8_t fifo_cnt, first_byte_position, temp_len, data[4];
|
||||
|
||||
value = ESC_PRAM_CMD_ABORT;
|
||||
lan9252_write_32(ESC_PRAM_RD_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_PRAM_RD_CMD_REG);
|
||||
}while(value & ESC_PRAM_CMD_BUSY);
|
||||
|
||||
value = ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address);
|
||||
lan9252_write_32(ESC_PRAM_RD_ADDR_LEN_REG, value);
|
||||
|
||||
value = ESC_PRAM_CMD_BUSY;
|
||||
lan9252_write_32(ESC_PRAM_RD_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_PRAM_RD_CMD_REG);
|
||||
}while((value & ESC_PRAM_CMD_AVAIL) == 0);
|
||||
|
||||
/* Fifo count */
|
||||
fifo_cnt = ESC_PRAM_CMD_CNT(value);
|
||||
|
||||
/* Read first value from FIFO */
|
||||
value = lan9252_read_32(ESC_PRAM_RD_FIFO_REG);
|
||||
fifo_cnt--;
|
||||
|
||||
/* Find out first byte position and adjust the copy from that
|
||||
* according to LAN9252 datasheet and MicroChip SDK code
|
||||
*/
|
||||
first_byte_position = (address & 0x03);
|
||||
temp_len = ((4 - first_byte_position) > len) ? len : (4 - first_byte_position);
|
||||
|
||||
memcpy(temp_buf ,((uint8_t *)&value + first_byte_position), temp_len);
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
|
||||
/* Select device. */
|
||||
spi_select (lan9252);
|
||||
/* Send command and address for fifo read */
|
||||
data[0] = ESC_CMD_FAST_READ;
|
||||
data[1] = ((ESC_PRAM_RD_FIFO_REG >> 8) & 0xFF);
|
||||
data[2] = (ESC_PRAM_RD_FIFO_REG & 0xFF);
|
||||
data[3] = ESC_CMD_FAST_READ_DUMMY;
|
||||
write (lan9252, data, sizeof(data));
|
||||
|
||||
/* Continue reading until we have read len */
|
||||
while(len > 0)
|
||||
{
|
||||
temp_len = (len > 4) ? 4: len;
|
||||
/* Always read 4 byte */
|
||||
read (lan9252, (temp_buf + byte_offset), sizeof(uint32_t));
|
||||
|
||||
fifo_cnt--;
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
}
|
||||
/* Un-select device. */
|
||||
spi_unselect (lan9252);
|
||||
}
|
||||
|
||||
/* ESC write process data ram function */
|
||||
/* static */ void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
uint8_t * temp_buf = (uint8_t *)buf;
|
||||
uint16_t byte_offset = 0;
|
||||
uint8_t fifo_cnt, first_byte_position, temp_len, data[3];
|
||||
|
||||
value = ESC_PRAM_CMD_ABORT;
|
||||
lan9252_write_32(ESC_PRAM_WR_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_PRAM_WR_CMD_REG);
|
||||
}while(value & ESC_PRAM_CMD_BUSY);
|
||||
|
||||
value = ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address);
|
||||
lan9252_write_32(ESC_PRAM_WR_ADDR_LEN_REG, value);
|
||||
|
||||
value = ESC_PRAM_CMD_BUSY;
|
||||
lan9252_write_32(ESC_PRAM_WR_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_PRAM_WR_CMD_REG);
|
||||
}while((value & ESC_PRAM_CMD_AVAIL) == 0);
|
||||
|
||||
/* Fifo count */
|
||||
fifo_cnt = ESC_PRAM_CMD_CNT(value);
|
||||
|
||||
/* Find out first byte position and adjust the copy from that
|
||||
* according to LAN9252 datasheet
|
||||
*/
|
||||
first_byte_position = (address & 0x03);
|
||||
temp_len = ((4 - first_byte_position) > len) ? len : (4 - first_byte_position);
|
||||
|
||||
memcpy(((uint8_t *)&value + first_byte_position), temp_buf, temp_len);
|
||||
|
||||
/* Write first value from FIFO */
|
||||
lan9252_write_32(ESC_PRAM_WR_FIFO_REG, value);
|
||||
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
fifo_cnt--;
|
||||
|
||||
/* Select device. */
|
||||
spi_select (lan9252);
|
||||
/* Send command and address for incrementing write */
|
||||
data[0] = ESC_CMD_SERIAL_WRITE;
|
||||
data[1] = ((ESC_PRAM_WR_FIFO_REG >> 8) & 0xFF);
|
||||
data[2] = (ESC_PRAM_WR_FIFO_REG & 0xFF);
|
||||
write (lan9252, data, sizeof(data));
|
||||
|
||||
/* Continue reading until we have read len */
|
||||
while(len > 0)
|
||||
{
|
||||
temp_len = (len > 4) ? 4 : len;
|
||||
value = 0;
|
||||
memcpy((uint8_t *)&value, (temp_buf + byte_offset), temp_len);
|
||||
/* Always write 4 byte */
|
||||
write (lan9252, (uint8_t *)&value, sizeof(value));
|
||||
|
||||
fifo_cnt--;
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
}
|
||||
/* Un-select device. */
|
||||
spi_unselect (lan9252);
|
||||
}
|
||||
|
||||
|
||||
/** ESC read function used by the Slave stack.
|
||||
*
|
||||
* @param[in] address = address of ESC register to read
|
||||
* @param[out] buf = pointer to buffer to read in
|
||||
* @param[in] len = number of bytes to read
|
||||
*/
|
||||
void ESC_read (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
/* Select Read function depending on address, process data ram or not */
|
||||
if (address >= 0x1000)
|
||||
{
|
||||
ESC_read_pram(address, buf, len);
|
||||
}
|
||||
else
|
||||
{
|
||||
uint16_t size;
|
||||
uint8_t *temp_buf = (uint8_t *)buf;
|
||||
|
||||
while(len > 0)
|
||||
{
|
||||
/* We write maximum 4 bytes at the time */
|
||||
size = (len > 4) ? 4 : len;
|
||||
/* Make size aligned to address according to LAN9252 datasheet
|
||||
* Table 12-14 EtherCAT CSR Address VS size and MicroChip SDK code
|
||||
*/
|
||||
/* If we got an odd address size is 1 , 01b 11b is captured */
|
||||
if(address & BIT(0))
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* If address 1xb and size != 1 and 3 , allow size 2 else size 1 */
|
||||
else if (address & BIT(1))
|
||||
{
|
||||
size = (size & BIT(0)) ? 1 : 2;
|
||||
}
|
||||
/* size 3 not valid */
|
||||
else if (size == 3)
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* else size is kept AS IS */
|
||||
ESC_read_csr(address, temp_buf, size);
|
||||
|
||||
/* next address */
|
||||
len -= size;
|
||||
temp_buf += size;
|
||||
address += size;
|
||||
}
|
||||
}
|
||||
/* To mimic the ET1100 always providing AlEvent on every read or write */
|
||||
ESC_read_csr(ESCREG_ALEVENT,(void *)&ESCvar.ALevent,sizeof(ESCvar.ALevent));
|
||||
ESCvar.ALevent = etohs (ESCvar.ALevent);
|
||||
|
||||
}
|
||||
|
||||
/** ESC write function used by the Slave stack.
|
||||
*
|
||||
* @param[in] address = address of ESC register to write
|
||||
* @param[out] buf = pointer to buffer to write from
|
||||
* @param[in] len = number of bytes to write
|
||||
*/
|
||||
void ESC_write (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
/* Select Write function depending on address, process data ram or not */
|
||||
if (address >= 0x1000)
|
||||
{
|
||||
ESC_write_pram(address, buf, len);
|
||||
}
|
||||
else
|
||||
{
|
||||
uint16_t size;
|
||||
uint8_t *temp_buf = (uint8_t *)buf;
|
||||
|
||||
while(len > 0)
|
||||
{
|
||||
/* We write maximum 4 bytes at the time */
|
||||
size = (len > 4) ? 4 : len;
|
||||
/* Make size aligned to address according to LAN9252 datasheet
|
||||
* Table 12-14 EtherCAT CSR Address VS size and MicroChip SDK code
|
||||
*/
|
||||
/* If we got an odd address size is 1 , 01b 11b is captured */
|
||||
if(address & BIT(0))
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* If address 1xb and size != 1 and 3 , allow size 2 else size 1 */
|
||||
else if (address & BIT(1))
|
||||
{
|
||||
size = (size & BIT(0)) ? 1 : 2;
|
||||
}
|
||||
/* size 3 not valid */
|
||||
else if (size == 3)
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* else size is kept AS IS */
|
||||
ESC_write_csr(address, temp_buf, size);
|
||||
|
||||
/* next address */
|
||||
len -= size;
|
||||
temp_buf += size;
|
||||
address += size;
|
||||
}
|
||||
}
|
||||
|
||||
/* To mimic the ET1x00 always providing AlEvent on every read or write */
|
||||
ESC_read_csr(ESCREG_ALEVENT,(void *)&ESCvar.ALevent,sizeof(ESCvar.ALevent));
|
||||
ESCvar.ALevent = etohs (ESCvar.ALevent);
|
||||
}
|
||||
|
||||
/* Un-used due to evb-lan9252-digio not havning any possability to
|
||||
* reset except over SPI.
|
||||
*/
|
||||
void ESC_reset (void)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
uint8_t ESC_IsLAN9252()
|
||||
{
|
||||
volatile uint32_t value;
|
||||
uint16_t detectedChip, revision;
|
||||
|
||||
/* Read */
|
||||
value = lan9252_read_32(ESC_ID_REV_REG);
|
||||
detectedChip = value >> 16;
|
||||
revision = value & 0xFF;
|
||||
|
||||
return detectedChip == LAN9252_ID_REV
|
||||
&& revision >= 1;
|
||||
}
|
||||
|
||||
|
||||
void ESC_init (const esc_cfg_t * config)
|
||||
{
|
||||
uint32_t value;
|
||||
|
||||
spi_setup();
|
||||
|
||||
/* Reset the ecat core here due to evb-lan9252-digio not having any GPIO
|
||||
* for that purpose.
|
||||
*/
|
||||
lan9252_write_32(ESC_RESET_CTRL_REG, ESC_DIGITAL_RST);
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_RESET_CTRL_REG);
|
||||
}
|
||||
while(value & ESC_RESET_CTRL_RST);
|
||||
|
||||
/* Read test register */
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_BYTE_TEST_REG);
|
||||
}
|
||||
while (value != ESC_TEST_VALUE);
|
||||
|
||||
/* Check Ready flag */
|
||||
do
|
||||
{
|
||||
value = lan9252_read_32(ESC_HW_CFG_REG);
|
||||
}
|
||||
while ((value & ESC_READY) == 0);
|
||||
|
||||
if(!ESC_IsLAN9252())
|
||||
{
|
||||
while (1);
|
||||
}
|
||||
}
|
||||
66
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/spi.cpp
Executable file
66
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/spi.cpp
Executable file
@@ -0,0 +1,66 @@
|
||||
#include "spi.hpp"
|
||||
// #include <Arduino.h>
|
||||
#include <SPI.h>
|
||||
|
||||
|
||||
char SCS = ESC_GPIO_Pin_CS;
|
||||
|
||||
|
||||
void spi_setup(void)
|
||||
{
|
||||
SPI.begin();
|
||||
pinMode(SCS, OUTPUT);
|
||||
spi_unselect(0);
|
||||
delay(100);
|
||||
SPI.beginTransaction(SPISettings(SPIX_ESC_SPEED, MSBFIRST, SPI_MODE0));
|
||||
|
||||
}
|
||||
|
||||
void spi_select (int8_t board)
|
||||
{
|
||||
// Soft CSN
|
||||
#if SCS_ACTIVE_POLARITY == SCS_LOW
|
||||
digitalWrite(SCS, LOW);
|
||||
#endif
|
||||
}
|
||||
|
||||
void spi_unselect (int8_t board)
|
||||
{
|
||||
// Soft CSN
|
||||
#if SCS_ACTIVE_POLARITY == SCS_LOW
|
||||
digitalWrite(SCS, HIGH);
|
||||
#endif
|
||||
}
|
||||
|
||||
inline static uint8_t spi_transfer_byte(uint8_t byte)
|
||||
{
|
||||
return SPI.transfer(byte);
|
||||
// AVR will need handling last byte transfer difference,
|
||||
// but then again they pobably wont even fit EtherCAT stack in RAM
|
||||
// so no need to care for now
|
||||
}
|
||||
|
||||
void write (int8_t board, uint8_t *data, uint8_t size)
|
||||
{
|
||||
for(int i = 0; i < size; ++i)
|
||||
{
|
||||
spi_transfer_byte(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void read (int8_t board, uint8_t *result, uint8_t size)
|
||||
{
|
||||
for(int i = 0; i < size; ++i)
|
||||
{
|
||||
result[i] = spi_transfer_byte(DUMMY_BYTE);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void spi_bidirectionally_transfer (int8_t board, uint8_t *result, uint8_t *data, uint8_t size)
|
||||
{
|
||||
for(int i = 0; i < size; ++i)
|
||||
{
|
||||
result[i] = spi_transfer_byte(data[i]);
|
||||
}
|
||||
}
|
||||
15
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/spi.h
Executable file
15
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/spi.h
Executable file
@@ -0,0 +1,15 @@
|
||||
#ifndef SRC_APP_SPI_H_
|
||||
#define SRC_APP_SPI_H_
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
void spi_setup(void);
|
||||
void spi_select (int8_t board);
|
||||
void spi_unselect (int8_t board);
|
||||
void write (int8_t board, uint8_t *data, uint8_t size);
|
||||
void read (int8_t board, uint8_t *result, uint8_t size);
|
||||
void spi_bidirectionally_transfer (int8_t board, uint8_t *result, uint8_t *data, uint8_t size);
|
||||
|
||||
|
||||
#endif /* SRC_APP_SPI_H_ */
|
||||
25
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/spi.hpp
Executable file
25
Cards/EaserCAT-2000/Firmware/lib/soes/hal/arduino-lan9252/spi.hpp
Executable file
@@ -0,0 +1,25 @@
|
||||
#ifndef SRC_APP_SPI_H_
|
||||
#define SRC_APP_SPI_H_
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define SCS_LOW 0
|
||||
#define SCS_HIGH 1
|
||||
#define SCS_ACTIVE_POLARITY SCS_LOW
|
||||
|
||||
#define SPIX_ESC SPI1
|
||||
//#define SPIX_ESC_SPEED 18000000
|
||||
#define SPIX_ESC_SPEED 50000000
|
||||
#define ESC_GPIO_Pin_CS PC4
|
||||
|
||||
#define DUMMY_BYTE 0xFF
|
||||
|
||||
extern "C" void spi_setup(void);
|
||||
extern "C" void spi_select (int8_t board);
|
||||
extern "C" void spi_unselect (int8_t board);
|
||||
extern "C" void write (int8_t board, uint8_t *data, uint8_t size);
|
||||
extern "C" void read (int8_t board, uint8_t *result, uint8_t size);
|
||||
extern "C" void spi_bidirectionally_transfer (int8_t board, uint8_t *result, uint8_t *data, uint8_t size);
|
||||
|
||||
|
||||
#endif /* SRC_APP_SPI_H_ */
|
||||
351
Cards/EaserCAT-2000/Firmware/lib/soes/objectlist.c
Executable file
351
Cards/EaserCAT-2000/Firmware/lib/soes/objectlist.c
Executable file
@@ -0,0 +1,351 @@
|
||||
#include "esc_coe.h"
|
||||
#include "utypes.h"
|
||||
#include <stddef.h>
|
||||
|
||||
|
||||
static const char acName1000[] = "Device Type";
|
||||
static const char acName1008[] = "Device Name";
|
||||
static const char acName1009[] = "Hardware Version";
|
||||
static const char acName100A[] = "Software Version";
|
||||
static const char acName1018[] = "Identity Object";
|
||||
static const char acName1018_00[] = "Max SubIndex";
|
||||
static const char acName1018_01[] = "Vendor ID";
|
||||
static const char acName1018_02[] = "Product Code";
|
||||
static const char acName1018_03[] = "Revision Number";
|
||||
static const char acName1018_04[] = "Serial Number";
|
||||
static const char acName1600[] = "IndexLatchEnable";
|
||||
static const char acName1600_00[] = "Max SubIndex";
|
||||
static const char acName1600_01[] = "IndexLatchEnable";
|
||||
static const char acName1601[] = "CommandedPosition1";
|
||||
static const char acName1601_00[] = "Max SubIndex";
|
||||
static const char acName1601_01[] = "CommandedPosition1";
|
||||
static const char acName1602[] = "CommandedPosition2";
|
||||
static const char acName1602_00[] = "Max SubIndex";
|
||||
static const char acName1602_01[] = "CommandedPosition2";
|
||||
static const char acName1603[] = "StepsPerMM1";
|
||||
static const char acName1603_00[] = "Max SubIndex";
|
||||
static const char acName1603_01[] = "StepsPerMM1";
|
||||
static const char acName1604[] = "StepsPerMM2";
|
||||
static const char acName1604_00[] = "Max SubIndex";
|
||||
static const char acName1604_01[] = "StepsPerMM2";
|
||||
static const char acName1A00[] = "EncPos";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "EncPos";
|
||||
static const char acName1A01[] = "EncFrequency";
|
||||
static const char acName1A01_00[] = "Max SubIndex";
|
||||
static const char acName1A01_01[] = "EncFrequency";
|
||||
static const char acName1A02[] = "DiffT";
|
||||
static const char acName1A02_00[] = "Max SubIndex";
|
||||
static const char acName1A02_01[] = "DiffT";
|
||||
static const char acName1A03[] = "IndexByte";
|
||||
static const char acName1A03_00[] = "Max SubIndex";
|
||||
static const char acName1A03_01[] = "IndexByte";
|
||||
static const char acName1A04[] = "IndexStatus";
|
||||
static const char acName1A04_00[] = "Max SubIndex";
|
||||
static const char acName1A04_01[] = "IndexStatus";
|
||||
static const char acName1A05[] = "ActualPosition1";
|
||||
static const char acName1A05_00[] = "Max SubIndex";
|
||||
static const char acName1A05_01[] = "ActualPosition1";
|
||||
static const char acName1A06[] = "ActualPosition2";
|
||||
static const char acName1A06_00[] = "Max SubIndex";
|
||||
static const char acName1A06_01[] = "ActualPosition2";
|
||||
static const char acName1A07[] = "D1";
|
||||
static const char acName1A07_00[] = "Max SubIndex";
|
||||
static const char acName1A07_01[] = "D1";
|
||||
static const char acName1A08[] = "D2";
|
||||
static const char acName1A08_00[] = "Max SubIndex";
|
||||
static const char acName1A08_01[] = "D2";
|
||||
static const char acName1A09[] = "D3";
|
||||
static const char acName1A09_00[] = "Max SubIndex";
|
||||
static const char acName1A09_01[] = "D3";
|
||||
static const char acName1A0A[] = "D4";
|
||||
static const char acName1A0A_00[] = "Max SubIndex";
|
||||
static const char acName1A0A_01[] = "D4";
|
||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||
static const char acName1C00_00[] = "Max SubIndex";
|
||||
static const char acName1C00_01[] = "Communications Type SM0";
|
||||
static const char acName1C00_02[] = "Communications Type SM1";
|
||||
static const char acName1C00_03[] = "Communications Type SM2";
|
||||
static const char acName1C00_04[] = "Communications Type SM3";
|
||||
static const char acName1C12[] = "Sync Manager 2 PDO Assignment";
|
||||
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";
|
||||
static const char acName1C13_02[] = "PDO Mapping";
|
||||
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 acName1C13_08[] = "PDO Mapping";
|
||||
static const char acName1C13_09[] = "PDO Mapping";
|
||||
static const char acName1C13_10[] = "PDO Mapping";
|
||||
static const char acName1C13_11[] = "PDO Mapping";
|
||||
static const char acName6000[] = "EncPos";
|
||||
static const char acName6001[] = "EncFrequency";
|
||||
static const char acName6002[] = "DiffT";
|
||||
static const char acName6003[] = "IndexByte";
|
||||
static const char acName6004[] = "IndexStatus";
|
||||
static const char acName6005[] = "ActualPosition1";
|
||||
static const char acName6006[] = "ActualPosition2";
|
||||
static const char acName6007[] = "D1";
|
||||
static const char acName6008[] = "D2";
|
||||
static const char acName6009[] = "D3";
|
||||
static const char acName600A[] = "D4";
|
||||
static const char acName7000[] = "IndexLatchEnable";
|
||||
static const char acName7001[] = "CommandedPosition1";
|
||||
static const char acName7002[] = "CommandedPosition2";
|
||||
static const char acName7003[] = "StepsPerMM1";
|
||||
static const char acName7004[] = "StepsPerMM2";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1000, 5001, NULL},
|
||||
};
|
||||
const _objd SDO1008[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 208, ATYPE_RO, acName1008, 0, "MetalMusings EaserCAT 2000"},
|
||||
};
|
||||
const _objd SDO1009[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 40, ATYPE_RO, acName1009, 0, "0.0.1"},
|
||||
};
|
||||
const _objd SDO100A[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 40, ATYPE_RO, acName100A, 0, "0.0.1"},
|
||||
};
|
||||
const _objd SDO1018[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 2730, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 12303564, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 2, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 1, &Obj.serial},
|
||||
};
|
||||
const _objd SDO1600[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000020, NULL},
|
||||
};
|
||||
const _objd SDO1601[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010020, NULL},
|
||||
};
|
||||
const _objd SDO1602[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1602_01, 0x70020020, NULL},
|
||||
};
|
||||
const _objd SDO1603[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1603_01, 0x70030010, NULL},
|
||||
};
|
||||
const _objd SDO1604[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1604_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1604_01, 0x70040010, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000020, NULL},
|
||||
};
|
||||
const _objd SDO1A01[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60010020, NULL},
|
||||
};
|
||||
const _objd SDO1A02[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A02_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A02_01, 0x60020010, NULL},
|
||||
};
|
||||
const _objd SDO1A03[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A03_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A03_01, 0x60030020, NULL},
|
||||
};
|
||||
const _objd SDO1A04[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A04_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A04_01, 0x60040020, NULL},
|
||||
};
|
||||
const _objd SDO1A05[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A05_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A05_01, 0x60050020, NULL},
|
||||
};
|
||||
const _objd SDO1A06[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A06_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A06_01, 0x60060020, NULL},
|
||||
};
|
||||
const _objd SDO1A07[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A07_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A07_01, 0x60070010, NULL},
|
||||
};
|
||||
const _objd SDO1A08[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A08_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A08_01, 0x60080010, NULL},
|
||||
};
|
||||
const _objd SDO1A09[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A09_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A09_01, 0x60090010, NULL},
|
||||
};
|
||||
const _objd SDO1A0A[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A0A_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A0A_01, 0x600A0010, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_01, 1, NULL},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_02, 2, NULL},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_03, 3, NULL},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_04, 4, NULL},
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{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, 11, 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},
|
||||
{0x08, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_08, 0x1A07, NULL},
|
||||
{0x09, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_09, 0x1A08, NULL},
|
||||
{0x0a, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_10, 0x1A09, NULL},
|
||||
{0x0b, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_11, 0x1A0A, NULL},
|
||||
};
|
||||
const _objd SDO6000[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6000, 0x00000000, &Obj.EncPos},
|
||||
};
|
||||
const _objd SDO6001[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6001, 0x00000000, &Obj.EncFrequency},
|
||||
};
|
||||
const _objd SDO6002[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED16, 16, ATYPE_RO | ATYPE_TXPDO, acName6002, 0, &Obj.DiffT},
|
||||
};
|
||||
const _objd SDO6003[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6003, 0, &Obj.IndexByte},
|
||||
};
|
||||
const _objd SDO6004[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO, acName6004, 0, &Obj.IndexStatus},
|
||||
};
|
||||
const _objd SDO6005[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6005, 0x00000000, &Obj.ActualPosition1},
|
||||
};
|
||||
const _objd SDO6006[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_TXPDO, acName6006, 0x00000000, &Obj.ActualPosition2},
|
||||
};
|
||||
const _objd SDO6007[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName6007, 0, &Obj.D1},
|
||||
};
|
||||
const _objd SDO6008[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName6008, 0, &Obj.D2},
|
||||
};
|
||||
const _objd SDO6009[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName6009, 0, &Obj.D3},
|
||||
};
|
||||
const _objd SDO600A[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_TXPDO, acName600A, 0, &Obj.D4},
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_RXPDO, acName7000, 0, &Obj.IndexLatchEnable},
|
||||
};
|
||||
const _objd SDO7001[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7001, 0x00000000, &Obj.CommandedPosition1},
|
||||
};
|
||||
const _objd SDO7002[] =
|
||||
{
|
||||
{0x0, DTYPE_REAL32, 32, ATYPE_RO | ATYPE_RXPDO, acName7002, 0x00000000, &Obj.CommandedPosition2},
|
||||
};
|
||||
const _objd SDO7003[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_RXPDO, acName7003, 0, &Obj.StepsPerMM1},
|
||||
};
|
||||
const _objd SDO7004[] =
|
||||
{
|
||||
{0x0, DTYPE_INTEGER16, 16, ATYPE_RO | ATYPE_RXPDO, acName7004, 0, &Obj.StepsPerMM2},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
{
|
||||
{0x1000, OTYPE_VAR, 0, 0, acName1000, SDO1000},
|
||||
{0x1008, OTYPE_VAR, 0, 0, acName1008, SDO1008},
|
||||
{0x1009, OTYPE_VAR, 0, 0, acName1009, SDO1009},
|
||||
{0x100A, OTYPE_VAR, 0, 0, acName100A, SDO100A},
|
||||
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
||||
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
|
||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
|
||||
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
|
||||
{0x1604, OTYPE_RECORD, 1, 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},
|
||||
{0x1A07, OTYPE_RECORD, 1, 0, acName1A07, SDO1A07},
|
||||
{0x1A08, OTYPE_RECORD, 1, 0, acName1A08, SDO1A08},
|
||||
{0x1A09, OTYPE_RECORD, 1, 0, acName1A09, SDO1A09},
|
||||
{0x1A0A, OTYPE_RECORD, 1, 0, acName1A0A, SDO1A0A},
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||
{0x1C12, OTYPE_ARRAY, 5, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 11, 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_VAR, 0, 0, acName6005, SDO6005},
|
||||
{0x6006, OTYPE_VAR, 0, 0, acName6006, SDO6006},
|
||||
{0x6007, OTYPE_VAR, 0, 0, acName6007, SDO6007},
|
||||
{0x6008, OTYPE_VAR, 0, 0, acName6008, SDO6008},
|
||||
{0x6009, OTYPE_VAR, 0, 0, acName6009, SDO6009},
|
||||
{0x600A, OTYPE_VAR, 0, 0, acName600A, SDO600A},
|
||||
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
|
||||
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
|
||||
{0x7002, OTYPE_VAR, 0, 0, acName7002, SDO7002},
|
||||
{0x7003, OTYPE_VAR, 0, 0, acName7003, SDO7003},
|
||||
{0x7004, OTYPE_VAR, 0, 0, acName7004, SDO7004},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
||||
40
Cards/EaserCAT-2000/Firmware/lib/soes/utypes.h
Executable file
40
Cards/EaserCAT-2000/Firmware/lib/soes/utypes.h
Executable file
@@ -0,0 +1,40 @@
|
||||
#ifndef __UTYPES_H__
|
||||
#define __UTYPES_H__
|
||||
|
||||
#include "cc.h"
|
||||
|
||||
/* Object dictionary storage */
|
||||
|
||||
typedef struct
|
||||
{
|
||||
/* Identity */
|
||||
|
||||
uint32_t serial;
|
||||
|
||||
/* Inputs */
|
||||
|
||||
float EncPos;
|
||||
float EncFrequency;
|
||||
uint16_t DiffT;
|
||||
uint32_t IndexByte;
|
||||
uint32_t IndexStatus;
|
||||
float ActualPosition1;
|
||||
float ActualPosition2;
|
||||
int16_t D1;
|
||||
int16_t D2;
|
||||
int16_t D3;
|
||||
int16_t D4;
|
||||
|
||||
/* Outputs */
|
||||
|
||||
uint32_t IndexLatchEnable;
|
||||
float CommandedPosition1;
|
||||
float CommandedPosition2;
|
||||
int16_t StepsPerMM1;
|
||||
int16_t StepsPerMM2;
|
||||
|
||||
} _Objects;
|
||||
|
||||
extern _Objects Obj;
|
||||
|
||||
#endif /* __UTYPES_H__ */
|
||||
24
Cards/EaserCAT-2000/Firmware/platformio.ini
Executable file
24
Cards/EaserCAT-2000/Firmware/platformio.ini
Executable file
@@ -0,0 +1,24 @@
|
||||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[env:genericSTM32F407VGT6]
|
||||
framework = arduino
|
||||
platform = ststm32
|
||||
board = genericSTM32F407VGT6
|
||||
upload_protocol = stlink
|
||||
debug_tool = stlink
|
||||
debug_build_flags = -O0 -g -ggdb
|
||||
monitor_port = COM7
|
||||
monitor_filters = send_on_enter, time, colorize, log2file
|
||||
monitor_speed = 115200
|
||||
build_flags = -Wl,--no-warn-rwx-segment
|
||||
lib_deps =
|
||||
SPI
|
||||
rlogiacco/CircularBuffer
|
||||
99
Cards/EaserCAT-2000/Firmware/src/MyEncoder.cpp
Executable file
99
Cards/EaserCAT-2000/Firmware/src/MyEncoder.cpp
Executable file
@@ -0,0 +1,99 @@
|
||||
#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;
|
||||
double frequency;
|
||||
TDelta.push(time); // Running average over the length of the circular buffer
|
||||
Pos.push(curPos);
|
||||
if (Pos.size() == RINGBUFFERLEN)
|
||||
{
|
||||
diffT = 1.0e-6 * (TDelta.last() - TDelta.first()); // Time is in microseconds
|
||||
diffPos = fabs(Pos.last() - Pos.first());
|
||||
frequency = diffPos / diffT;
|
||||
oldFrequency = frequency;
|
||||
return frequency; // Revolutions per second
|
||||
}
|
||||
else
|
||||
return oldFrequency;
|
||||
}
|
||||
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
Cards/EaserCAT-2000/Firmware/src/StepGen.cpp
Executable file
148
Cards/EaserCAT-2000/Firmware/src/StepGen.cpp
Executable 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;
|
||||
124
Cards/EaserCAT-2000/Firmware/src/StepGen2.cpp
Executable file
124
Cards/EaserCAT-2000/Firmware/src/StepGen2.cpp
Executable file
@@ -0,0 +1,124 @@
|
||||
#include <Arduino.h>
|
||||
#include <stdio.h>
|
||||
#include "StepGen2.h"
|
||||
#include "extend32to64.h"
|
||||
|
||||
extern "C"
|
||||
{
|
||||
#include "esc.h"
|
||||
}
|
||||
extern extend32to64 longTime;
|
||||
|
||||
StepGen2::StepGen2(TIM_TypeDef *Timer, uint32_t _timerChannel, PinName _stepPin, uint8_t _dirPin, void irq(void), TIM_TypeDef *Timer2, void irq2(void))
|
||||
{
|
||||
actualPosition = 0;
|
||||
commandedPosition = 0;
|
||||
commandedStepPosition = 0;
|
||||
initialPosition = 0;
|
||||
initialStepPosition = 0;
|
||||
stepsPerMM = 0;
|
||||
enabled = 0;
|
||||
|
||||
dirPin = _dirPin;
|
||||
dirPinName = digitalPinToPinName(dirPin);
|
||||
stepPin = _stepPin;
|
||||
pulseTimerChan = _timerChannel;
|
||||
pulseTimer = new HardwareTimer(Timer);
|
||||
pulseTimer->attachInterrupt(pulseTimerChan, irq); // Capture/compare innterrupt
|
||||
pinMode(dirPin, OUTPUT);
|
||||
startTimer = new HardwareTimer(Timer2);
|
||||
startTimer->attachInterrupt(irq2);
|
||||
}
|
||||
|
||||
uint32_t StepGen2::handleStepper(uint64_t irqTime, uint16_t nLoops)
|
||||
{
|
||||
frequency = 0;
|
||||
nSteps = 0;
|
||||
dbg = 0;
|
||||
if (!enabled) // Just .... don't
|
||||
return updatePos(0);
|
||||
|
||||
commandedStepPosition = floor(commandedPosition * stepsPerMM); // Scale position to steps
|
||||
nSteps = commandedStepPosition - initialStepPosition;
|
||||
if (nSteps == 0) // No movement
|
||||
{
|
||||
return updatePos(1);
|
||||
}
|
||||
lcncCycleTime = nLoops * StepGen2::sync0CycleTime * 1.0e-9; // nLoops is there in case we missed an ethercat cycle. secs
|
||||
|
||||
if (abs(nSteps) < 0) // Some small number
|
||||
{ //
|
||||
frequency = (abs(nSteps) + 1) / lcncCycleTime; // Distribute steps inside available time
|
||||
Tpulses = abs(nSteps) / frequency; //
|
||||
Tstartf = (lcncCycleTime - Tpulses) / 2.0; //
|
||||
} //
|
||||
else // Regular step train, up or down
|
||||
{ //
|
||||
float kTRAJ = (commandedPosition - initialPosition) / lcncCycleTime; // Straight line equation. position = kTRAJ x time + mTRAJ
|
||||
float mTRAJ = initialPosition; // Operating on incoming positions (not steps)
|
||||
if (kTRAJ > 0) //
|
||||
Tstartf = (float(initialStepPosition + 1) / float(stepsPerMM) - mTRAJ) / kTRAJ; // Crossing upwards
|
||||
else //
|
||||
Tstartf = (float(initialStepPosition) / float(stepsPerMM) - mTRAJ) / kTRAJ; // Crossing downwards
|
||||
frequency = fabs(kTRAJ * stepsPerMM); //
|
||||
Tpulses = abs(nSteps) / frequency;
|
||||
}
|
||||
updatePos(5);
|
||||
|
||||
uint32_t timeSinceISR = (longTime.extendTime(micros()) - irqTime); // Diff time from ISR (usecs)
|
||||
dbg = timeSinceISR; //
|
||||
Tstartu = Tjitter + uint32_t(Tstartf * 1e6) - timeSinceISR; // Have already wasted some time since the irq.
|
||||
|
||||
if (nSteps == 0) // Can do this much earlier, but want some calculated data for debugging
|
||||
return updatePos(1);
|
||||
|
||||
timerFrequency = uint32_t(ceil(frequency));
|
||||
startTimer->setOverflow(Tstartu, MICROSEC_FORMAT); // All handled by irqs
|
||||
startTimer->refresh();
|
||||
startTimer->resume();
|
||||
return 1;
|
||||
}
|
||||
|
||||
void StepGen2::startTimerCB()
|
||||
{
|
||||
startTimer->pause(); // Once is enough.
|
||||
digitalWriteFast(dirPinName, nSteps < 0 ? HIGH : LOW); // nSteps negative => decrease, HIGH
|
||||
// There will be a short break here for t2 usecs, in the future.
|
||||
|
||||
timerEndPosition += nSteps;
|
||||
pulseTimer->setMode(pulseTimerChan, TIMER_OUTPUT_COMPARE_PWM2, stepPin);
|
||||
pulseTimer->setOverflow(timerFrequency, HERTZ_FORMAT);
|
||||
// pulseTimer->setCaptureCompare(pulseTimerChan, 50, PERCENT_COMPARE_FORMAT);
|
||||
pulseTimer->setCaptureCompare(pulseTimerChan, t3, MICROSEC_COMPARE_FORMAT);
|
||||
pulseTimer->refresh();
|
||||
pulseTimer->resume();
|
||||
}
|
||||
|
||||
void StepGen2::pulseTimerCB()
|
||||
{
|
||||
int16_t dir = digitalReadFast(dirPinName); //
|
||||
if (dir == HIGH) // The step just taken
|
||||
timerPosition--;
|
||||
else
|
||||
timerPosition++;
|
||||
int32_t diffPosition = timerEndPosition - timerPosition; // Same "polarity" as nSteps
|
||||
if (diffPosition == 0)
|
||||
pulseTimer->pause();
|
||||
else
|
||||
{
|
||||
if (diffPosition < 0 && dir == LOW) // Change direction. Should not end up here, but alas
|
||||
digitalWriteFast(dirPinName, HIGH); // Normal is to be HIGH when decreasing
|
||||
if (diffPosition > 0 && dir == HIGH) // Change direction. Should not end up here, but alas
|
||||
digitalWriteFast(dirPinName, LOW); // Normal is to be LOW when increasing
|
||||
// Normally nothing is needed
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t StepGen2::updatePos(uint32_t i)
|
||||
{ //
|
||||
initialPosition = commandedPosition; // Save the numeric position for next step
|
||||
initialStepPosition = commandedStepPosition; // also the step we are at}
|
||||
return i;
|
||||
}
|
||||
|
||||
uint32_t StepGen2::sync0CycleTime = 0;
|
||||
1195
Cards/EaserCAT-2000/Firmware/src/StepGen3.cpp
Executable file
1195
Cards/EaserCAT-2000/Firmware/src/StepGen3.cpp
Executable file
File diff suppressed because it is too large
Load Diff
391
Cards/EaserCAT-2000/Firmware/src/Stm32F4_Encoder.cpp
Executable file
391
Cards/EaserCAT-2000/Firmware/src/Stm32F4_Encoder.cpp
Executable file
@@ -0,0 +1,391 @@
|
||||
#include <Stm32F4_Encoder.h>
|
||||
|
||||
/*
|
||||
Stm32F4_Encoder.cpp
|
||||
Created on: Nov 20, 2020
|
||||
Author: GoktugH.
|
||||
*/
|
||||
// TIM2, TIM3, TIM4, TIM8
|
||||
Encoder::Encoder()
|
||||
{
|
||||
int unit;
|
||||
}
|
||||
|
||||
// void Encoder::SetCount(enum EncTimer enc, int64_t Counter)
|
||||
void Encoder::SetCount(int64_t Counter)
|
||||
{
|
||||
tim_base->CNT = Counter;
|
||||
}
|
||||
// uint16_t Encoder::GetCount(enum EncTimer enc)
|
||||
uint16_t Encoder::GetCount()
|
||||
{
|
||||
return tim_base->CNT;
|
||||
}
|
||||
|
||||
void GpioConfigPortA(GPIO_TypeDef *GPIOx)
|
||||
{
|
||||
|
||||
uint32_t pinpos = 0x00, pos = 0x00, currentpin = 0x00;
|
||||
|
||||
/* ------------------------- Configure the port pins ---------------- */
|
||||
/*-- GPIO Mode Configuration --*/
|
||||
for (pinpos = 0x00; pinpos < 0x10; pinpos++)
|
||||
{
|
||||
pos = ((uint32_t)0x01) << pinpos;
|
||||
/* Get the port pins position */
|
||||
currentpin = (GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_6 | GPIO_Pin_7) & pos;
|
||||
|
||||
if (currentpin == pos)
|
||||
{
|
||||
GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2));
|
||||
GPIOx->MODER |= (((uint32_t)GPIO_Mode_AF) << (pinpos * 2));
|
||||
|
||||
if ((GPIO_Mode_AF == GPIO_Mode_OUT) || (GPIO_Mode_AF == GPIO_Mode_AF))
|
||||
{
|
||||
/* Check Speed mode parameters */
|
||||
|
||||
/* Speed mode configuration */
|
||||
GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2));
|
||||
GPIOx->OSPEEDR |= ((uint32_t)(GPIO_Speed_50MHz) << (pinpos * 2));
|
||||
|
||||
/* Check Output mode parameters */
|
||||
|
||||
/* Output mode configuration*/
|
||||
GPIOx->OTYPER &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos));
|
||||
GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_OType_PP) << ((uint16_t)pinpos));
|
||||
}
|
||||
|
||||
/* Pull-up Pull down resistor configuration*/
|
||||
GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2));
|
||||
GPIOx->PUPDR |= (((uint32_t)GPIO_PuPd_NOPULL) << (pinpos * 2));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GpioConfigPortC(GPIO_TypeDef *GPIOx)
|
||||
{
|
||||
|
||||
uint32_t pinpos = 0x00, pos = 0x00, currentpin = 0x00;
|
||||
|
||||
/* ------------------------- Configure the port pins ---------------- */
|
||||
/*-- GPIO Mode Configuration --*/
|
||||
for (pinpos = 0x00; pinpos < 0x10; pinpos++)
|
||||
{
|
||||
pos = ((uint32_t)0x01) << pinpos;
|
||||
/* Get the port pins position */
|
||||
currentpin = (GPIO_Pin_6 | GPIO_Pin_7) & pos;
|
||||
|
||||
if (currentpin == pos)
|
||||
{
|
||||
GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2));
|
||||
GPIOx->MODER |= (((uint32_t)GPIO_Mode_AF) << (pinpos * 2));
|
||||
|
||||
if ((GPIO_Mode_AF == GPIO_Mode_OUT) || (GPIO_Mode_AF == GPIO_Mode_AF))
|
||||
{
|
||||
/* Check Speed mode parameters */
|
||||
|
||||
/* Speed mode configuration */
|
||||
GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2));
|
||||
GPIOx->OSPEEDR |= ((uint32_t)(GPIO_Speed_50MHz) << (pinpos * 2));
|
||||
|
||||
/* Check Output mode parameters */
|
||||
|
||||
/* Output mode configuration*/
|
||||
GPIOx->OTYPER &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos));
|
||||
GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_OType_PP) << ((uint16_t)pinpos));
|
||||
}
|
||||
|
||||
/* Pull-up Pull down resistor configuration*/
|
||||
GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2));
|
||||
GPIOx->PUPDR |= (((uint32_t)GPIO_PuPd_NOPULL) << (pinpos * 2));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GpioConfigPortD(GPIO_TypeDef *GPIOx)
|
||||
{
|
||||
|
||||
uint32_t pinpos = 0x00, pos = 0x00, currentpin = 0x00;
|
||||
|
||||
/* ------------------------- Configure the port pins ---------------- */
|
||||
/*-- GPIO Mode Configuration --*/
|
||||
for (pinpos = 0x00; pinpos < 0x10; pinpos++)
|
||||
{
|
||||
pos = ((uint32_t)0x01) << pinpos;
|
||||
/* Get the port pins position */
|
||||
currentpin = (GPIO_Pin_12 | GPIO_Pin_13) & pos;
|
||||
|
||||
if (currentpin == pos)
|
||||
{
|
||||
GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2));
|
||||
GPIOx->MODER |= (((uint32_t)GPIO_Mode_AF) << (pinpos * 2));
|
||||
|
||||
if ((GPIO_Mode_AF == GPIO_Mode_OUT) || (GPIO_Mode_AF == GPIO_Mode_AF))
|
||||
{
|
||||
/* Check Speed mode parameters */
|
||||
|
||||
/* Speed mode configuration */
|
||||
GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2));
|
||||
GPIOx->OSPEEDR |= ((uint32_t)(GPIO_Speed_50MHz) << (pinpos * 2));
|
||||
|
||||
/* Check Output mode parameters */
|
||||
|
||||
/* Output mode configuration*/
|
||||
GPIOx->OTYPER &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos));
|
||||
GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_OType_PP) << ((uint16_t)pinpos));
|
||||
}
|
||||
|
||||
/* Pull-up Pull down resistor configuration*/
|
||||
GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2));
|
||||
GPIOx->PUPDR |= (((uint32_t)GPIO_PuPd_NOPULL) << (pinpos * 2));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void TIM_EncoderInterConfig(TIM_TypeDef *TIMx, uint16_t TIM_EncoderMode, uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity)
|
||||
{
|
||||
|
||||
uint16_t tmpsmcr = 0;
|
||||
uint16_t tmpccmr1 = 0;
|
||||
uint16_t tmpccer = 0;
|
||||
|
||||
/* Get the TIMx SMCR register value */
|
||||
tmpsmcr = TIMx->SMCR;
|
||||
|
||||
/* Get the TIMx CCMR1 register value */
|
||||
tmpccmr1 = TIMx->CCMR1;
|
||||
|
||||
/* Get the TIMx CCER register value */
|
||||
tmpccer = TIMx->CCER;
|
||||
|
||||
/* Set the encoder Mode */
|
||||
tmpsmcr &= (uint16_t)~TIM_SMCR_SMS;
|
||||
tmpsmcr |= TIM_EncoderMode;
|
||||
|
||||
/* Select the Capture Compare 1 and the Capture Compare 2 as input */
|
||||
tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR1_CC2S);
|
||||
tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0;
|
||||
|
||||
/* Set the TI1 and the TI2 Polarities */
|
||||
tmpccer &= ((uint16_t)~TIM_CCER_CC1P) & ((uint16_t)~TIM_CCER_CC2P);
|
||||
tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4));
|
||||
|
||||
/* Write to TIMx SMCR */
|
||||
TIMx->SMCR = tmpsmcr;
|
||||
|
||||
/* Write to TIMx CCMR1 */
|
||||
TIMx->CCMR1 = tmpccmr1;
|
||||
|
||||
/* Write to TIMx CCER */
|
||||
TIMx->CCER = tmpccer;
|
||||
}
|
||||
|
||||
void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef *TIM_TimeBaseInitStruct)
|
||||
{
|
||||
/* Set the default configuration */
|
||||
TIM_TimeBaseInitStruct->TIM_Period = 0xFFFFFFFF;
|
||||
TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000;
|
||||
TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000;
|
||||
}
|
||||
|
||||
void TIM_TimeBaseInit(TIM_TypeDef *TIMx, TIM_TimeBaseInitTypeDef *TIM_TimeBaseInitStruct)
|
||||
{
|
||||
uint16_t tmpcr1 = 0;
|
||||
|
||||
tmpcr1 = TIMx->CR1;
|
||||
|
||||
if ((TIMx == TIM1) || (TIMx == TIM8) ||
|
||||
(TIMx == TIM2) || (TIMx == TIM3) ||
|
||||
(TIMx == TIM4) || (TIMx == TIM5))
|
||||
{
|
||||
/* Select the Counter Mode */
|
||||
tmpcr1 &= (uint16_t)(~(TIM_CR1_DIR | TIM_CR1_CMS));
|
||||
tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode;
|
||||
}
|
||||
|
||||
if ((TIMx != TIM6) && (TIMx != TIM7))
|
||||
{
|
||||
/* Set the clock division */
|
||||
tmpcr1 &= (uint16_t)(~TIM_CR1_CKD);
|
||||
tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision;
|
||||
}
|
||||
|
||||
TIMx->CR1 = tmpcr1;
|
||||
|
||||
/* Set the Autoreload value */
|
||||
TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period;
|
||||
|
||||
/* Set the Prescaler value */
|
||||
TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler;
|
||||
|
||||
if ((TIMx == TIM1) || (TIMx == TIM8))
|
||||
{
|
||||
/* Set the Repetition Counter value */
|
||||
TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter;
|
||||
}
|
||||
|
||||
/* Generate an update event to reload the Prescaler
|
||||
and the repetition counter(only for TIM1 and TIM8) value immediatly */
|
||||
TIMx->EGR = TIM_PSCReloadMode_Immediate;
|
||||
}
|
||||
|
||||
TIM_TimeBaseInitTypeDef TIMER_InitStructure;
|
||||
TIM_TimeBaseInitTypeDef TIMER_InitStructureE;
|
||||
TIM_TimeBaseInitTypeDef TIMER_InitStructureEE;
|
||||
TIM_TimeBaseInitTypeDef TIMER_InitStructureEEG;
|
||||
|
||||
void TIM_Cmd(TIM_TypeDef *TIMx, FunctionalState NewState)
|
||||
{
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the TIM Counter */
|
||||
TIMx->CR1 |= TIM_CR1_CEN;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the TIM Counter */
|
||||
TIMx->CR1 &= (uint16_t)~TIM_CR1_CEN;
|
||||
}
|
||||
}
|
||||
void GPIO_PinAF(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
|
||||
|
||||
{
|
||||
|
||||
uint32_t temp = 0x00;
|
||||
uint32_t temp_2 = 0x00;
|
||||
|
||||
temp = ((uint32_t)(GPIO_AF) << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4));
|
||||
GPIOx->AFR[GPIO_PinSource >> 0x03] &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4));
|
||||
temp_2 = GPIOx->AFR[GPIO_PinSource >> 0x03] | temp;
|
||||
GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2;
|
||||
}
|
||||
|
||||
void encoder_config()
|
||||
{
|
||||
RCC->AHB1ENR |= 0x1; // GPIOA
|
||||
RCC->AHB1ENR |= 0x4; // GPIOC
|
||||
RCC->AHB1ENR |= 0x8; // GPIOD
|
||||
RCC->AHB1ENR |= 0x10; // GPIOE
|
||||
|
||||
RCC->APB1ENR |= 0x20000000; // ENABLE DAC
|
||||
// RCC->APB2ENR |= 0x00000002; // APB2 TIM8
|
||||
RCC->APB1ENR |= 0x00000004; // APB1 TIM4
|
||||
RCC->APB1ENR |= 0x00000001; // APB1 TIM2
|
||||
// RCC->APB1ENR |= 0x00000002; // APB1 TIM3
|
||||
|
||||
GpioConfigPortA(GPIOA);
|
||||
// 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;
|
||||
TIM_TimeBaseInit(TIM8, &TIMER_InitStructure);
|
||||
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;
|
||||
TIM_TimeBaseInit(TIM4, &TIMER_InitStructureE);
|
||||
TIM_TimeBaseStructInit(&TIMER_InitStructureE);
|
||||
TIM_Cmd(TIM4, ENABLE);
|
||||
TIM4->CNT = 0;
|
||||
|
||||
TIM_EncoderInterConfig(TIM2, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Falling);
|
||||
TIMER_InitStructureEE.TIM_Period = 65535;
|
||||
TIMER_InitStructureEE.TIM_CounterMode = TIM_CounterMode_Up | TIM_CounterMode_Down;
|
||||
TIM_TimeBaseInit(TIM2, &TIMER_InitStructureEE);
|
||||
TIM_TimeBaseStructInit(&TIMER_InitStructureEE);
|
||||
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;
|
||||
TIM_TimeBaseInit(TIM3, &TIMER_InitStructureEEG);
|
||||
TIM_TimeBaseStructInit(&TIMER_InitStructureEEG);
|
||||
TIM_Cmd(TIM3, ENABLE);
|
||||
|
||||
TIM3->CNT = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
void encoder2_config()
|
||||
{
|
||||
#if 0
|
||||
#include "mbed.h"
|
||||
#include "stm32f4xx.h"
|
||||
#include "stm32f4xx_hal_tim_ex.h"
|
||||
|
||||
TIM_HandleTypeDef timer;
|
||||
TIM_Encoder_InitTypeDef encoder;
|
||||
|
||||
// direction to PA_9 -- step pulse to PA_8
|
||||
|
||||
int main()
|
||||
{
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStruct;
|
||||
__TIM1_CLK_ENABLE();
|
||||
__GPIOA_CLK_ENABLE();
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_9;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
timer.Instance = TIM1;
|
||||
timer.Init.Period = 0xffff;
|
||||
timer.Init.Prescaler = 0;
|
||||
timer.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
timer.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
|
||||
encoder.EncoderMode = TIM_ENCODERMODE_TI12;
|
||||
encoder.IC1Filter = 0x0f;
|
||||
encoder.IC1Polarity = TIM_INPUTCHANNELPOLARITY_RISING;
|
||||
encoder.IC1Prescaler = TIM_ICPSC_DIV4;
|
||||
encoder.IC1Selection = TIM_ICSELECTION_DIRECTTI;
|
||||
|
||||
encoder.IC2Filter = 0x0f;
|
||||
encoder.IC2Polarity = TIM_INPUTCHANNELPOLARITY_FALLING;
|
||||
encoder.IC2Prescaler = TIM_ICPSC_DIV4;
|
||||
encoder.IC2Selection = TIM_ICSELECTION_DIRECTTI;
|
||||
|
||||
HAL_TIM_Encoder_Init(&timer, &encoder);
|
||||
HAL_TIM_Encoder_Start(&timer,TIM_CHANNEL_1);
|
||||
|
||||
|
||||
TIM1->EGR = 1; // Generate an update event
|
||||
TIM1->CR1 = 1; // Enable the counter
|
||||
|
||||
|
||||
while (1) {
|
||||
int16_t count1;
|
||||
count1=TIM1->CNT;
|
||||
|
||||
printf("%d\r\n", count1);
|
||||
wait(1.0);
|
||||
|
||||
};
|
||||
}
|
||||
#endif
|
||||
}
|
||||
18
Cards/EaserCAT-2000/Firmware/src/extend32to64.cpp
Executable file
18
Cards/EaserCAT-2000/Firmware/src/extend32to64.cpp
Executable file
@@ -0,0 +1,18 @@
|
||||
#include "extend32to64.h"
|
||||
|
||||
// Extend from 32-bit to 64-bit precision
|
||||
int64_t extend32to64::extendTime(uint32_t in)
|
||||
{
|
||||
int64_t c64 = (int64_t)in - HALF_PERIOD; // remove half period to determine (+/-) sign of the wrap
|
||||
int64_t dif = (c64 - previousTimeValue); // 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 < int64_t(-HALF_PERIOD))
|
||||
mod_dif += ONE_PERIOD; // account for mod of negative number behavior in C
|
||||
|
||||
int64_t unwrapped = previousTimeValue + mod_dif;
|
||||
previousTimeValue = unwrapped; // load previous value
|
||||
|
||||
return unwrapped + HALF_PERIOD; // remove the shift we applied at the beginning, and return
|
||||
}
|
||||
355
Cards/EaserCAT-2000/Firmware/src/main.cpp
Executable file
355
Cards/EaserCAT-2000/Firmware/src/main.cpp
Executable file
@@ -0,0 +1,355 @@
|
||||
#include <Arduino.h>
|
||||
#include <stdio.h>
|
||||
extern "C"
|
||||
{
|
||||
#include "ecat_slv.h"
|
||||
#include "utypes.h"
|
||||
};
|
||||
_Objects Obj;
|
||||
|
||||
HardwareSerial Serial1(PA10, PA9);
|
||||
|
||||
volatile uint16_t ALEventIRQ; // ALEvent that caused the interrupt
|
||||
HardwareTimer *baseTimer; // The base period timer
|
||||
HardwareTimer *syncTimer; // The timer that syncs "with linuxcnc cycle"
|
||||
uint32_t sync0CycleTime; // nanosecs, often 1000000 ( 1 ms )
|
||||
|
||||
#include "MyEncoder.h"
|
||||
volatile uint16_t encCnt = 0;
|
||||
void indexPulseEncoderCB1(void);
|
||||
MyEncoder Encoder1(TIM2, PA2, indexPulseEncoderCB1);
|
||||
void indexPulseEncoderCB1(void)
|
||||
{
|
||||
encCnt++;
|
||||
Encoder1.indexPulse();
|
||||
}
|
||||
// #include <RunningAverage.h>
|
||||
// RunningAverage irqServeDelays(1000); // To get the max delay of the irq serve time over the last second
|
||||
CircularBuffer<uint16_t, 1000> irqServeDelays;
|
||||
|
||||
#include "StepGen3.h"
|
||||
StepGen3 *Step = 0;
|
||||
|
||||
#include "extend32to64.h"
|
||||
|
||||
volatile uint64_t irqTime = 0, irqCnt = 0;
|
||||
extend32to64 longTime;
|
||||
|
||||
void setFrequencyAdjustedMicrosSeconds(HardwareTimer *timer, uint32_t usecs);
|
||||
|
||||
void cb_set_outputs(void) // Master outputs gets here, slave inputs, first operation
|
||||
{
|
||||
Encoder1.setLatch(Obj.IndexLatchEnable);
|
||||
Encoder1.setScale(2000);
|
||||
}
|
||||
|
||||
volatile uint16_t basePeriodCnt;
|
||||
volatile uint64_t makePulsesCnt = 0, prevMakePulsesCnt = 0;
|
||||
volatile uint16_t deltaMakePulsesCnt;
|
||||
|
||||
volatile double posCmd1, posCmd2;
|
||||
double oldPosCmd1, oldPosCmd2;
|
||||
double deltaPosCmd1, deltaPosCmd2;
|
||||
|
||||
void syncWithLCNC()
|
||||
{
|
||||
syncTimer->pause();
|
||||
baseTimer->pause();
|
||||
deltaMakePulsesCnt = makePulsesCnt - prevMakePulsesCnt;
|
||||
prevMakePulsesCnt = makePulsesCnt;
|
||||
Step->updateStepGen(posCmd1, posCmd2, sync0CycleTime); // Update positions
|
||||
Step->makeAllPulses(); // Make first step right here
|
||||
basePeriodCnt = sync0CycleTime / BASE_PERIOD; //
|
||||
baseTimer->refresh(); //
|
||||
baseTimer->resume(); // Make the other steps in ISR
|
||||
}
|
||||
|
||||
void basePeriodCB(void)
|
||||
{
|
||||
if (--basePeriodCnt > 0) // Stop
|
||||
Step->makeAllPulses();
|
||||
else
|
||||
baseTimer->pause();
|
||||
}
|
||||
|
||||
int32_t delayT;
|
||||
uint16_t thisCycleTime; // In usecs
|
||||
int16_t maxIrqServeTime = 0;
|
||||
uint64_t oldIrqTime = 0;
|
||||
uint16_t nLoops;
|
||||
uint16_t failedSM2s = 0;
|
||||
uint16_t totalFailedSM2s = 0;
|
||||
uint16_t nLoopsAboveNorm = 0;
|
||||
|
||||
void handleStepper(void)
|
||||
{
|
||||
if (oldIrqTime != 0) // See if there is a delay in data, normally it *should* be nLoops=1, but sometimes it is more
|
||||
{
|
||||
thisCycleTime = irqTime - oldIrqTime;
|
||||
nLoops = round(float(thisCycleTime) / float(sync0CycleTime / 1000));
|
||||
nLoopsAboveNorm += nLoops - 1;
|
||||
}
|
||||
oldIrqTime = irqTime;
|
||||
|
||||
uint32_t diffT = longTime.extendTime(micros()) - irqTime; // Time from interrupt was received by isr
|
||||
irqServeDelays.push(diffT);
|
||||
if (irqServeDelays.isFull()) // Do max calcs, just waiting a second
|
||||
{
|
||||
uint16_t maxInBuffer = 0;
|
||||
using index_t = decltype(irqServeDelays)::index_t;
|
||||
for (index_t i = 0; i < irqServeDelays.size(); i++)
|
||||
{
|
||||
if (maxInBuffer < irqServeDelays[i])
|
||||
maxInBuffer = irqServeDelays[i];
|
||||
}
|
||||
if (maxIrqServeTime > maxInBuffer) // Reduce by one, slowly eating up excess time
|
||||
maxIrqServeTime--;
|
||||
if (maxIrqServeTime < maxInBuffer)
|
||||
maxIrqServeTime = maxInBuffer;
|
||||
}
|
||||
if (ALEventIRQ & ESCREG_ALEVENT_SM2)
|
||||
{ // The normal case, position update every cycle
|
||||
posCmd1 = Obj.CommandedPosition1; // The position update
|
||||
posCmd2 = Obj.CommandedPosition2;
|
||||
deltaPosCmd1 = posCmd1 - oldPosCmd1; // Needed for extrapolation in the other case
|
||||
deltaPosCmd2 = posCmd2 - oldPosCmd2;
|
||||
failedSM2s = 0;
|
||||
}
|
||||
else
|
||||
{ // Not normal, we didn't get a position update. Extrapolate from previous updates
|
||||
if (failedSM2s++ < 100) // Do max 10 such extrapolations, should be plenty
|
||||
{ //
|
||||
posCmd1 += deltaPosCmd1; // Continue with the same speed
|
||||
posCmd2 += deltaPosCmd2;
|
||||
}
|
||||
totalFailedSM2s++;
|
||||
}
|
||||
oldPosCmd1 = posCmd1;
|
||||
oldPosCmd2 = posCmd2;
|
||||
|
||||
// Obj.ActualPosition1 = Obj.CommandedPosition1;
|
||||
// Obj.ActualPosition2 = Obj.CommandedPosition2;
|
||||
|
||||
Step->stepgen_array[0].pos_scale = -Obj.StepsPerMM1;
|
||||
Step->stepgen_array[1].pos_scale = -Obj.StepsPerMM2;
|
||||
|
||||
Obj.ActualPosition1 = Step->stepgen_array[0].pos_fb;
|
||||
Obj.ActualPosition2 = Step->stepgen_array[1].pos_fb;
|
||||
|
||||
delayT = maxIrqServeTime - diffT; // Add 10 as some safety margin
|
||||
if (delayT > 0 && delayT < 900)
|
||||
{
|
||||
syncTimer->setOverflow(delayT, MICROSEC_FORMAT); // Work in flawed units, its ok
|
||||
syncTimer->refresh();
|
||||
syncTimer->resume();
|
||||
}
|
||||
else
|
||||
{
|
||||
syncWithLCNC();
|
||||
}
|
||||
}
|
||||
|
||||
float_t oldCommandedPosition = 0;
|
||||
void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
||||
{
|
||||
Obj.IndexStatus = Encoder1.indexHappened();
|
||||
Obj.EncPos = Encoder1.currentPos();
|
||||
Obj.EncFrequency = Encoder1.frequency(longTime.extendTime(micros()));
|
||||
Obj.IndexByte = Encoder1.getIndexState();
|
||||
|
||||
Obj.DiffT = nLoops;
|
||||
Obj.D1 = 1000 * deltaPosCmd2; // abs(1000 * (ap2 - Obj.CommandedPosition2)); // Step2.actPos();
|
||||
Obj.D2 = totalFailedSM2s; // Step->stepgen_array[1].pos_fb; // Step->stepgen_array[1].rawcount % INT16_MAX; // Step->stepgen_array[1].freq;
|
||||
Obj.D3 = 1000 * Obj.CommandedPosition2; // Step->stepgen_array[1].freq;
|
||||
Obj.D4 = 1000 * posCmd2; // Step->stepgen_array[1].rawcount % UINT16_MAX;
|
||||
oldCommandedPosition = Obj.CommandedPosition2;
|
||||
}
|
||||
|
||||
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 =
|
||||
{
|
||||
.user_arg = NULL,
|
||||
.use_interrupt = 1,
|
||||
.watchdog_cnt = 150,
|
||||
.set_defaults_hook = NULL,
|
||||
.pre_state_change_hook = NULL,
|
||||
.post_state_change_hook = NULL,
|
||||
.application_hook = handleStepper,
|
||||
.safeoutput_override = NULL,
|
||||
.pre_object_download_hook = NULL,
|
||||
.post_object_download_hook = NULL,
|
||||
.rxpdo_override = NULL,
|
||||
.txpdo_override = NULL,
|
||||
.esc_hw_interrupt_enable = ESC_interrupt_enable,
|
||||
.esc_hw_interrupt_disable = ESC_interrupt_disable,
|
||||
.esc_hw_eep_handler = NULL,
|
||||
.esc_check_dc_handler = dc_checker,
|
||||
};
|
||||
|
||||
void measureCrystalFrequency(void);
|
||||
|
||||
volatile byte serveIRQ = 0;
|
||||
|
||||
void setup(void)
|
||||
{
|
||||
Serial1.begin(115200);
|
||||
#if 0
|
||||
measureCrystalFrequency(); // Calibrate crystal frequency
|
||||
#endif
|
||||
Step = new StepGen3;
|
||||
|
||||
encoder_config(); // Needed by encoder, probably breaks some timers.
|
||||
ecat_slv_init(&config);
|
||||
|
||||
pinMode(PA11, OUTPUT); // Step X
|
||||
pinMode(PA12, OUTPUT); // Dir X
|
||||
pinMode(PC9, OUTPUT); // Step Z
|
||||
pinMode(PC10, OUTPUT); // Dir Z
|
||||
|
||||
baseTimer = new HardwareTimer(TIM11); // The base period timer
|
||||
setFrequencyAdjustedMicrosSeconds(baseTimer, BASE_PERIOD / 1000);
|
||||
// baseTimer->setOverflow(BASE_PERIOD / 1000, MICROSEC_FORMAT); // Or the line above, This one is uncalibrated
|
||||
baseTimer->attachInterrupt(basePeriodCB);
|
||||
|
||||
syncTimer = new HardwareTimer(TIM3); // The Linuxcnc servo period sync timer
|
||||
syncTimer->attachInterrupt(syncWithLCNC);
|
||||
}
|
||||
|
||||
void loop(void)
|
||||
{
|
||||
uint64_t dTime;
|
||||
if (serveIRQ)
|
||||
{
|
||||
DIG_process(ALEventIRQ, 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();
|
||||
}
|
||||
dTime = longTime.extendTime(micros()) - irqTime;
|
||||
if (dTime > 5000) // Don't run ecat_slv_poll when expecting to serve interrupt
|
||||
ecat_slv_poll();
|
||||
}
|
||||
|
||||
void sync0Handler(void)
|
||||
{
|
||||
ALEventIRQ = ESC_ALeventread();
|
||||
// if (ALEventIRQ & ESCREG_ALEVENT_SM2)
|
||||
{
|
||||
irqTime = longTime.extendTime(micros());
|
||||
serveIRQ = 1;
|
||||
}
|
||||
irqCnt++; // debug output
|
||||
}
|
||||
|
||||
// Enable SM2 interrupts
|
||||
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_SM2; // Only SM2
|
||||
if (mask & user_int_mask)
|
||||
{
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() & ~(ESCREG_ALEVENT_DC_SYNC0 | ESCREG_ALEVENT_SM3));
|
||||
attachInterrupt(digitalPinToInterrupt(PC3), sync0Handler, RISING);
|
||||
|
||||
// Set LAN9252 interrupt pin driver as push-pull active high
|
||||
uint32_t bits = 0x00000111;
|
||||
ESC_write(0x54, &bits, 4);
|
||||
|
||||
// Enable LAN9252 interrupt
|
||||
bits = 0x00000001;
|
||||
ESC_write(0x5c, &bits, 4);
|
||||
}
|
||||
}
|
||||
|
||||
// Disable SM2 interrupts
|
||||
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_SM2;
|
||||
|
||||
if (mask & user_int_mask)
|
||||
{
|
||||
// Disable interrupt from SYNC0
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() & ~(mask & user_int_mask));
|
||||
detachInterrupt(digitalPinToInterrupt(PC3));
|
||||
// Disable LAN9252 interrupt
|
||||
uint32_t bits = 0x00000000;
|
||||
ESC_write(0x5c, &bits, 4);
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" uint32_t ESC_SYNC0cycletime(void);
|
||||
|
||||
// Setup of DC
|
||||
uint16_t dc_checker(void)
|
||||
{
|
||||
// Indicate we run DC
|
||||
ESCvar.dcsync = 1;
|
||||
sync0CycleTime = ESC_SYNC0cycletime(); // nanosecs
|
||||
return 0;
|
||||
}
|
||||
|
||||
//
|
||||
// Code to calibrate the crystal.
|
||||
//
|
||||
|
||||
#include <HardwareTimer.h>
|
||||
HardwareTimer *timer;
|
||||
volatile uint32_t cnt;
|
||||
|
||||
void CB(void)
|
||||
{
|
||||
if (cnt-- == 0)
|
||||
{
|
||||
timer->pause();
|
||||
}
|
||||
}
|
||||
|
||||
void setFrequencyAdjustedMicrosSeconds(HardwareTimer *timer, uint32_t usecs)
|
||||
{
|
||||
const uint16_t calibrated1000 = 1042; // <- This is the factor to adjust to make 1 sec = 1 sec
|
||||
uint32_t period_cyc = (usecs * (timer->getTimerClkFreq() / 1000)) / calibrated1000; // Avoid overflow during math
|
||||
uint32_t Prescalerfactor = (period_cyc / 0x10000) + 1;
|
||||
uint32_t PeriodTicks = period_cyc / Prescalerfactor;
|
||||
timer->setPrescaleFactor(Prescalerfactor);
|
||||
timer->setOverflow(PeriodTicks, TICK_FORMAT);
|
||||
// Serial1.printf("Period_cyc=%u Prescalefactor =%u ticks = %u\n", period_cyc, Prescalerfactor, PeriodTicks);
|
||||
}
|
||||
|
||||
void measureCrystalFrequency(void)
|
||||
{
|
||||
timer = new HardwareTimer(TIM1);
|
||||
Serial1.begin(115200);
|
||||
delay(3000);
|
||||
Serial1.printf("Clock freq = %u\n", timer->getTimerClkFreq());
|
||||
setFrequencyAdjustedMicrosSeconds(timer, 1000);
|
||||
timer->refresh();
|
||||
timer->attachInterrupt(CB);
|
||||
cnt = 10000;
|
||||
|
||||
Serial1.printf("\n");
|
||||
uint32_t startT = micros();
|
||||
timer->resume();
|
||||
|
||||
while (cnt != 0)
|
||||
;
|
||||
|
||||
uint32_t endT = micros();
|
||||
uint32_t diffT = endT - startT;
|
||||
Serial1.printf("\n");
|
||||
Serial1.printf("diff = %u\n", diffT);
|
||||
|
||||
Serial1.printf("\n");
|
||||
delay(10000);
|
||||
Serial1.printf("\n");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
11
Cards/EaserCAT-2000/Firmware/test/README
Executable file
11
Cards/EaserCAT-2000/Firmware/test/README
Executable file
@@ -0,0 +1,11 @@
|
||||
|
||||
This directory is intended for PlatformIO Test Runner and project tests.
|
||||
|
||||
Unit Testing is a software testing method by which individual units of
|
||||
source code, sets of one or more MCU program modules together with associated
|
||||
control data, usage procedures, and operating procedures, are tested to
|
||||
determine whether they are fit for use. Unit testing finds problems early
|
||||
in the development cycle.
|
||||
|
||||
More information about PlatformIO Unit Testing:
|
||||
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html
|
||||
3
Cards/EaserCAT-2000/Kicad/.gitignore
vendored
Normal file
3
Cards/EaserCAT-2000/Kicad/.gitignore
vendored
Normal file
@@ -0,0 +1,3 @@
|
||||
fp-info-cache
|
||||
Ethercat-stm32-backup*
|
||||
*.lck
|
||||
53691
Cards/EaserCAT-2000/Kicad/Ethercat-stm32.kicad_pcb
Executable file
53691
Cards/EaserCAT-2000/Kicad/Ethercat-stm32.kicad_pcb
Executable file
File diff suppressed because it is too large
Load Diff
568
Cards/EaserCAT-2000/Kicad/Ethercat-stm32.kicad_pro
Executable file
568
Cards/EaserCAT-2000/Kicad/Ethercat-stm32.kicad_pro
Executable file
@@ -0,0 +1,568 @@
|
||||
{
|
||||
"board": {
|
||||
"3dviewports": [],
|
||||
"design_settings": {
|
||||
"defaults": {
|
||||
"board_outline_line_width": 0.09999999999999999,
|
||||
"copper_line_width": 0.19999999999999998,
|
||||
"copper_text_italic": false,
|
||||
"copper_text_size_h": 1.5,
|
||||
"copper_text_size_v": 1.5,
|
||||
"copper_text_thickness": 0.3,
|
||||
"copper_text_upright": false,
|
||||
"courtyard_line_width": 0.049999999999999996,
|
||||
"dimension_precision": 4,
|
||||
"dimension_units": 3,
|
||||
"dimensions": {
|
||||
"arrow_length": 1270000,
|
||||
"extension_offset": 500000,
|
||||
"keep_text_aligned": true,
|
||||
"suppress_zeroes": false,
|
||||
"text_position": 0,
|
||||
"units_format": 1
|
||||
},
|
||||
"fab_line_width": 0.09999999999999999,
|
||||
"fab_text_italic": false,
|
||||
"fab_text_size_h": 1.0,
|
||||
"fab_text_size_v": 1.0,
|
||||
"fab_text_thickness": 0.15,
|
||||
"fab_text_upright": false,
|
||||
"other_line_width": 0.15,
|
||||
"other_text_italic": false,
|
||||
"other_text_size_h": 1.0,
|
||||
"other_text_size_v": 1.0,
|
||||
"other_text_thickness": 0.15,
|
||||
"other_text_upright": false,
|
||||
"pads": {
|
||||
"drill": 0.762,
|
||||
"height": 1.524,
|
||||
"width": 1.524
|
||||
},
|
||||
"silk_line_width": 0.15,
|
||||
"silk_text_italic": false,
|
||||
"silk_text_size_h": 1.0,
|
||||
"silk_text_size_v": 1.0,
|
||||
"silk_text_thickness": 0.15,
|
||||
"silk_text_upright": false,
|
||||
"zones": {
|
||||
"min_clearance": 0.5
|
||||
}
|
||||
},
|
||||
"diff_pair_dimensions": [],
|
||||
"drc_exclusions": [],
|
||||
"meta": {
|
||||
"version": 2
|
||||
},
|
||||
"rule_severities": {
|
||||
"annular_width": "error",
|
||||
"clearance": "error",
|
||||
"connection_width": "warning",
|
||||
"copper_edge_clearance": "error",
|
||||
"copper_sliver": "warning",
|
||||
"courtyards_overlap": "error",
|
||||
"diff_pair_gap_out_of_range": "error",
|
||||
"diff_pair_uncoupled_length_too_long": "error",
|
||||
"drill_out_of_range": "error",
|
||||
"duplicate_footprints": "warning",
|
||||
"extra_footprint": "warning",
|
||||
"footprint": "error",
|
||||
"footprint_type_mismatch": "ignore",
|
||||
"hole_clearance": "error",
|
||||
"hole_near_hole": "error",
|
||||
"invalid_outline": "error",
|
||||
"isolated_copper": "warning",
|
||||
"item_on_disabled_layer": "error",
|
||||
"items_not_allowed": "error",
|
||||
"length_out_of_range": "error",
|
||||
"lib_footprint_issues": "warning",
|
||||
"lib_footprint_mismatch": "warning",
|
||||
"malformed_courtyard": "error",
|
||||
"microvia_drill_out_of_range": "error",
|
||||
"missing_courtyard": "ignore",
|
||||
"missing_footprint": "warning",
|
||||
"net_conflict": "warning",
|
||||
"npth_inside_courtyard": "ignore",
|
||||
"padstack": "warning",
|
||||
"pth_inside_courtyard": "ignore",
|
||||
"shorting_items": "error",
|
||||
"silk_edge_clearance": "warning",
|
||||
"silk_over_copper": "warning",
|
||||
"silk_overlap": "warning",
|
||||
"skew_out_of_range": "error",
|
||||
"solder_mask_bridge": "error",
|
||||
"starved_thermal": "error",
|
||||
"text_height": "warning",
|
||||
"text_thickness": "warning",
|
||||
"through_hole_pad_without_hole": "error",
|
||||
"too_many_vias": "error",
|
||||
"track_dangling": "warning",
|
||||
"track_width": "error",
|
||||
"tracks_crossing": "error",
|
||||
"unconnected_items": "error",
|
||||
"unresolved_variable": "error",
|
||||
"via_dangling": "warning",
|
||||
"zones_intersect": "error"
|
||||
},
|
||||
"rules": {
|
||||
"max_error": 0.005,
|
||||
"min_clearance": 0.0,
|
||||
"min_connection": 0.0,
|
||||
"min_copper_edge_clearance": 0.0,
|
||||
"min_hole_clearance": 0.25,
|
||||
"min_hole_to_hole": 0.25,
|
||||
"min_microvia_diameter": 0.19999999999999998,
|
||||
"min_microvia_drill": 0.09999999999999999,
|
||||
"min_resolved_spokes": 2,
|
||||
"min_silk_clearance": 0.0,
|
||||
"min_text_height": 0.7999999999999999,
|
||||
"min_text_thickness": 0.08,
|
||||
"min_through_hole_diameter": 0.3,
|
||||
"min_track_width": 0.0,
|
||||
"min_via_annular_width": 0.09999999999999999,
|
||||
"min_via_diameter": 0.5,
|
||||
"solder_mask_clearance": 0.0,
|
||||
"solder_mask_min_width": 0.0,
|
||||
"solder_mask_to_copper_clearance": 0.0,
|
||||
"use_height_for_length_calcs": true
|
||||
},
|
||||
"teardrop_options": [
|
||||
{
|
||||
"td_allow_use_two_tracks": true,
|
||||
"td_curve_segcount": 5,
|
||||
"td_on_pad_in_zone": false,
|
||||
"td_onpadsmd": true,
|
||||
"td_onroundshapesonly": false,
|
||||
"td_ontrackend": false,
|
||||
"td_onviapad": true
|
||||
}
|
||||
],
|
||||
"teardrop_parameters": [
|
||||
{
|
||||
"td_curve_segcount": 0,
|
||||
"td_height_ratio": 1.0,
|
||||
"td_length_ratio": 0.5,
|
||||
"td_maxheight": 2.0,
|
||||
"td_maxlen": 1.0,
|
||||
"td_target_name": "td_round_shape",
|
||||
"td_width_to_size_filter_ratio": 0.9
|
||||
},
|
||||
{
|
||||
"td_curve_segcount": 0,
|
||||
"td_height_ratio": 1.0,
|
||||
"td_length_ratio": 0.5,
|
||||
"td_maxheight": 2.0,
|
||||
"td_maxlen": 1.0,
|
||||
"td_target_name": "td_rect_shape",
|
||||
"td_width_to_size_filter_ratio": 0.9
|
||||
},
|
||||
{
|
||||
"td_curve_segcount": 0,
|
||||
"td_height_ratio": 1.0,
|
||||
"td_length_ratio": 0.5,
|
||||
"td_maxheight": 2.0,
|
||||
"td_maxlen": 1.0,
|
||||
"td_target_name": "td_track_end",
|
||||
"td_width_to_size_filter_ratio": 0.9
|
||||
}
|
||||
],
|
||||
"track_widths": [],
|
||||
"via_dimensions": [],
|
||||
"zones_allow_external_fillets": false
|
||||
},
|
||||
"ipc2581": {
|
||||
"dist": "",
|
||||
"distpn": "",
|
||||
"internal_id": "",
|
||||
"mfg": "",
|
||||
"mpn": ""
|
||||
},
|
||||
"layer_presets": [],
|
||||
"viewports": []
|
||||
},
|
||||
"boards": [],
|
||||
"cvpcb": {
|
||||
"equivalence_files": []
|
||||
},
|
||||
"erc": {
|
||||
"erc_exclusions": [],
|
||||
"meta": {
|
||||
"version": 0
|
||||
},
|
||||
"pin_map": [
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
1,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
1,
|
||||
2,
|
||||
1,
|
||||
1,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
0,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
1,
|
||||
2,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
1,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2
|
||||
]
|
||||
],
|
||||
"rule_severities": {
|
||||
"bus_definition_conflict": "error",
|
||||
"bus_entry_needed": "error",
|
||||
"bus_to_bus_conflict": "error",
|
||||
"bus_to_net_conflict": "error",
|
||||
"conflicting_netclasses": "error",
|
||||
"different_unit_footprint": "error",
|
||||
"different_unit_net": "error",
|
||||
"duplicate_reference": "error",
|
||||
"duplicate_sheet_names": "error",
|
||||
"endpoint_off_grid": "warning",
|
||||
"extra_units": "error",
|
||||
"global_label_dangling": "warning",
|
||||
"hier_label_mismatch": "error",
|
||||
"label_dangling": "error",
|
||||
"lib_symbol_issues": "warning",
|
||||
"missing_bidi_pin": "warning",
|
||||
"missing_input_pin": "warning",
|
||||
"missing_power_pin": "error",
|
||||
"missing_unit": "warning",
|
||||
"multiple_net_names": "warning",
|
||||
"net_not_bus_member": "warning",
|
||||
"no_connect_connected": "warning",
|
||||
"no_connect_dangling": "warning",
|
||||
"pin_not_connected": "error",
|
||||
"pin_not_driven": "error",
|
||||
"pin_to_pin": "warning",
|
||||
"power_pin_not_driven": "error",
|
||||
"similar_labels": "warning",
|
||||
"simulation_model_issue": "ignore",
|
||||
"unannotated": "error",
|
||||
"unit_value_mismatch": "error",
|
||||
"unresolved_variable": "error",
|
||||
"wire_dangling": "error"
|
||||
}
|
||||
},
|
||||
"libraries": {
|
||||
"pinned_footprint_libs": [],
|
||||
"pinned_symbol_libs": []
|
||||
},
|
||||
"meta": {
|
||||
"filename": "Ethercat-stm32.kicad_pro",
|
||||
"version": 1
|
||||
},
|
||||
"net_settings": {
|
||||
"classes": [
|
||||
{
|
||||
"bus_width": 12,
|
||||
"clearance": 0.2,
|
||||
"diff_pair_gap": 0.25,
|
||||
"diff_pair_via_gap": 0.25,
|
||||
"diff_pair_width": 0.2,
|
||||
"line_style": 0,
|
||||
"microvia_diameter": 0.3,
|
||||
"microvia_drill": 0.1,
|
||||
"name": "Default",
|
||||
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||
"track_width": 0.25,
|
||||
"via_diameter": 0.8,
|
||||
"via_drill": 0.4,
|
||||
"wire_width": 6
|
||||
}
|
||||
],
|
||||
"meta": {
|
||||
"version": 3
|
||||
},
|
||||
"net_colors": null,
|
||||
"netclass_assignments": null,
|
||||
"netclass_patterns": []
|
||||
},
|
||||
"pcbnew": {
|
||||
"last_paths": {
|
||||
"gencad": "",
|
||||
"idf": "",
|
||||
"netlist": "C:/Program Files/KiCad/7.0/",
|
||||
"plot": "",
|
||||
"pos_files": "",
|
||||
"specctra_dsn": "Ethercat-stm32.dsn",
|
||||
"step": "",
|
||||
"svg": "",
|
||||
"vrml": ""
|
||||
},
|
||||
"page_layout_descr_file": ""
|
||||
},
|
||||
"schematic": {
|
||||
"annotate_start_num": 0,
|
||||
"bom_export_filename": "",
|
||||
"bom_fmt_presets": [],
|
||||
"bom_fmt_settings": {
|
||||
"field_delimiter": ",",
|
||||
"keep_line_breaks": false,
|
||||
"keep_tabs": false,
|
||||
"name": "CSV",
|
||||
"ref_delimiter": ",",
|
||||
"ref_range_delimiter": "",
|
||||
"string_delimiter": "\""
|
||||
},
|
||||
"bom_presets": [],
|
||||
"bom_settings": {
|
||||
"exclude_dnp": false,
|
||||
"fields_ordered": [
|
||||
{
|
||||
"group_by": false,
|
||||
"label": "Reference",
|
||||
"name": "Reference",
|
||||
"show": true
|
||||
},
|
||||
{
|
||||
"group_by": true,
|
||||
"label": "Value",
|
||||
"name": "Value",
|
||||
"show": true
|
||||
},
|
||||
{
|
||||
"group_by": false,
|
||||
"label": "Datasheet",
|
||||
"name": "Datasheet",
|
||||
"show": true
|
||||
},
|
||||
{
|
||||
"group_by": false,
|
||||
"label": "Footprint",
|
||||
"name": "Footprint",
|
||||
"show": true
|
||||
},
|
||||
{
|
||||
"group_by": false,
|
||||
"label": "Qty",
|
||||
"name": "${QUANTITY}",
|
||||
"show": true
|
||||
},
|
||||
{
|
||||
"group_by": true,
|
||||
"label": "DNP",
|
||||
"name": "${DNP}",
|
||||
"show": true
|
||||
}
|
||||
],
|
||||
"filter_string": "",
|
||||
"group_symbols": true,
|
||||
"name": "Grouped By Value",
|
||||
"sort_asc": true,
|
||||
"sort_field": "Reference"
|
||||
},
|
||||
"connection_grid_size": 50.0,
|
||||
"drawing": {
|
||||
"dashed_lines_dash_length_ratio": 12.0,
|
||||
"dashed_lines_gap_length_ratio": 3.0,
|
||||
"default_line_thickness": 6.0,
|
||||
"default_text_size": 50.0,
|
||||
"field_names": [],
|
||||
"intersheets_ref_own_page": false,
|
||||
"intersheets_ref_prefix": "",
|
||||
"intersheets_ref_short": false,
|
||||
"intersheets_ref_show": false,
|
||||
"intersheets_ref_suffix": "",
|
||||
"junction_size_choice": 3,
|
||||
"label_size_ratio": 0.375,
|
||||
"operating_point_overlay_i_precision": 3,
|
||||
"operating_point_overlay_i_range": "~A",
|
||||
"operating_point_overlay_v_precision": 3,
|
||||
"operating_point_overlay_v_range": "~V",
|
||||
"overbar_offset_ratio": 1.23,
|
||||
"pin_symbol_size": 25.0,
|
||||
"text_offset_ratio": 0.15
|
||||
},
|
||||
"legacy_lib_dir": "",
|
||||
"legacy_lib_list": [],
|
||||
"meta": {
|
||||
"version": 1
|
||||
},
|
||||
"net_format_name": "",
|
||||
"page_layout_descr_file": "",
|
||||
"plot_directory": "",
|
||||
"spice_current_sheet_as_root": false,
|
||||
"spice_external_command": "spice \"%I\"",
|
||||
"spice_model_current_sheet_as_root": true,
|
||||
"spice_save_all_currents": false,
|
||||
"spice_save_all_dissipations": false,
|
||||
"spice_save_all_voltages": false,
|
||||
"subpart_first_id": 65,
|
||||
"subpart_id_separator": 0
|
||||
},
|
||||
"sheets": [
|
||||
[
|
||||
"5597aedc-b607-407f-bbfd-31b3b298ecb1",
|
||||
""
|
||||
],
|
||||
[
|
||||
"a120273a-c1ae-42b3-935d-01f789f654a3",
|
||||
"LAN9252"
|
||||
],
|
||||
[
|
||||
"650f1ee4-2ce7-4e9d-a70d-f9d8defa5d03",
|
||||
"LAN9252_diverse"
|
||||
],
|
||||
[
|
||||
"d564400f-40ba-4aca-9c2a-14ec52a8353b",
|
||||
"STM32F4"
|
||||
],
|
||||
[
|
||||
"0a376a6c-0f15-42f8-81f6-3a55619be267",
|
||||
"Peripherals"
|
||||
]
|
||||
],
|
||||
"text_variables": {}
|
||||
}
|
||||
87
Cards/EaserCAT-2000/Kicad/Ethercat-stm32.kicad_sch
Executable file
87
Cards/EaserCAT-2000/Kicad/Ethercat-stm32.kicad_sch
Executable file
@@ -0,0 +1,87 @@
|
||||
(kicad_sch (version 20230121) (generator eeschema)
|
||||
|
||||
(uuid 5597aedc-b607-407f-bbfd-31b3b298ecb1)
|
||||
|
||||
(paper "A3")
|
||||
|
||||
(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)
|
||||
(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)
|
||||
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||
)
|
||||
(property "Sheetfile" "peripherals.kicad_sch" (at 144.78 241.8846 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left top))
|
||||
)
|
||||
(instances
|
||||
(project "Ethercat-stm32"
|
||||
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "5"))
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
(sheet (at 46.99 224.79) (size 82.55 17.78) (fields_autoplaced)
|
||||
(stroke (width 0.1524) (type solid))
|
||||
(fill (color 0 0 0 0.0000))
|
||||
(uuid 650f1ee4-2ce7-4e9d-a70d-f9d8defa5d03)
|
||||
(property "Sheetname" "LAN9252_diverse" (at 46.99 224.0784 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||
)
|
||||
(property "Sheetfile" "LAN9252_diverse.kicad_sch" (at 46.99 243.1546 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left top))
|
||||
)
|
||||
(instances
|
||||
(project "Ethercat-stm32"
|
||||
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "3"))
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
(sheet (at 46.99 200.66) (size 82.55 17.78) (fields_autoplaced)
|
||||
(stroke (width 0.1524) (type solid))
|
||||
(fill (color 0 0 0 0.0000))
|
||||
(uuid a120273a-c1ae-42b3-935d-01f789f654a3)
|
||||
(property "Sheetname" "LAN9252" (at 46.99 199.9484 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||
)
|
||||
(property "Sheetfile" "LAN9252.kicad_sch" (at 46.99 219.0246 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left top))
|
||||
)
|
||||
(instances
|
||||
(project "Ethercat-stm32"
|
||||
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "2"))
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
(sheet (at 142.24 200.66) (size 74.93 17.78) (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)
|
||||
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||
)
|
||||
(property "Sheetfile" "STM32F4.kicad_sch" (at 142.24 219.0246 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left top))
|
||||
)
|
||||
(instances
|
||||
(project "Ethercat-stm32"
|
||||
(path "/5597aedc-b607-407f-bbfd-31b3b298ecb1" (page "4"))
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
(sheet_instances
|
||||
(path "/" (page "1"))
|
||||
)
|
||||
)
|
||||
@@ -0,0 +1,32 @@
|
||||
(footprint "2.8 TFT 320x240 led with sd and touch" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(attr smd)
|
||||
(fp_text reference "REF**" (at -33.782 -7.112 unlocked) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 1dd33759-143b-476c-bb42-c5e5d445a2fc)
|
||||
)
|
||||
(fp_text value "2.8 TFT 320x240 led with sd and touch" (at -36.83 -0.254 90 unlocked) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 1ce2bf2b-b61f-46da-a1cb-06e193ac5296)
|
||||
)
|
||||
(fp_rect (start -43 25) (end 43 -25)
|
||||
(stroke (width 0.12) (type solid)) (fill none) (layer "F.SilkS") (tstamp 9717e78c-245e-4b0a-ba7e-ef5374b0c38c))
|
||||
(pad "1" thru_hole roundrect (at 40.005 3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 21623806-8193-49aa-8e86-f5d741ee3217))
|
||||
(pad "2" thru_hole roundrect (at 40.005 1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 1c8efd92-4e91-4579-bd5c-5fab3c9a7156))
|
||||
(pad "3" thru_hole roundrect (at 40.005 -1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp c0b8101a-448b-46a1-9a8a-2ff22c1b14db))
|
||||
(pad "4" thru_hole roundrect (at 40.005 -3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp a34698d6-085b-485a-ba4e-0184bb2cbfd8))
|
||||
(pad "5" thru_hole roundrect (at -40.3 16.51 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp d099de14-88e2-441e-a73e-ff95baeb8e26))
|
||||
(pad "6" thru_hole roundrect (at -40.3 13.97 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 59a1ecf0-8d7b-4db7-8aa7-b858a90fc7be))
|
||||
(pad "7" thru_hole roundrect (at -40.3 11.43 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp b96d741a-8459-4bdc-b8c3-996255ed9d94))
|
||||
(pad "8" thru_hole roundrect (at -40.3 8.89 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 378396b7-816f-412c-b398-2bfbec7f6a55))
|
||||
(pad "9" thru_hole roundrect (at -40.3 6.35 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 3f510b37-3d66-4b1f-a522-569a3c2d8bbf))
|
||||
(pad "10" thru_hole roundrect (at -40.3 3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 434996e1-61bd-42ff-a716-8e2eded0b81d))
|
||||
(pad "11" thru_hole roundrect (at -40.3 1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp d04da8c4-1375-40f5-862d-89a40323615e))
|
||||
(pad "12" thru_hole roundrect (at -40.3 -1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp d3eb6fac-45c7-4fd1-9912-2d8c789ffa62))
|
||||
(pad "13" thru_hole roundrect (at -40.3 -3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 925b72f2-8f72-452d-a630-3febc08cc9ad))
|
||||
(pad "14" thru_hole roundrect (at -40.3 -6.35 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp b4fcf448-08be-496d-8886-fa111b5b3ed1))
|
||||
(pad "15" thru_hole roundrect (at -40.3 -8.89 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 71333f91-0375-4115-aff4-5c1287b2ffc3))
|
||||
(pad "16" thru_hole roundrect (at -40.3 -11.43 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 1da1d33c-0ecb-4e9c-810a-201946bf2333))
|
||||
(pad "17" thru_hole roundrect (at -40.3 -13.97 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp da71bc08-e42f-44ea-865c-6032dc757532))
|
||||
(pad "18" thru_hole roundrect (at -40.3 -16.51 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp e630b3ad-972b-48f8-8387-439339d1a82b))
|
||||
)
|
||||
@@ -0,0 +1,36 @@
|
||||
(footprint "4.0 TFT 480x320 led with sd and touch" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(attr through_hole)
|
||||
(fp_text reference "REF**" (at 6.858 -7.112 unlocked) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 1dd33759-143b-476c-bb42-c5e5d445a2fc)
|
||||
)
|
||||
(fp_text value "4.0 TFT 480x320 led with sd and touch" (at 3.47 -0.254 90 unlocked) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 1ce2bf2b-b61f-46da-a1cb-06e193ac5296)
|
||||
)
|
||||
(fp_rect (start -1.93 30.9) (end 106.07 -30.9)
|
||||
(stroke (width 0.12) (type solid)) (fill none) (layer "F.SilkS") (tstamp 9717e78c-245e-4b0a-ba7e-ef5374b0c38c))
|
||||
(pad "" np_thru_hole circle (at 1.07 -27.5) (size 6 6) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp 7ce980db-52dc-41e1-bac4-30a0cf9df4f2))
|
||||
(pad "" np_thru_hole circle (at 1.07 27.5) (size 6 6) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp d2f64eb5-177b-453b-a52e-31c9cd53aa66))
|
||||
(pad "" np_thru_hole circle (at 103.07 -27.5) (size 6 6) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp 9edc280a-c2af-4851-92a3-2973bd93b7ea))
|
||||
(pad "" np_thru_hole circle (at 103.07 27.5) (size 6 6) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp f03fba2d-995e-47a0-b9be-5909be892403))
|
||||
(pad "1" thru_hole roundrect (at 104.14 3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 21623806-8193-49aa-8e86-f5d741ee3217))
|
||||
(pad "2" thru_hole roundrect (at 104.14 1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 1c8efd92-4e91-4579-bd5c-5fab3c9a7156))
|
||||
(pad "3" thru_hole roundrect (at 104.14 -1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp c0b8101a-448b-46a1-9a8a-2ff22c1b14db))
|
||||
(pad "4" thru_hole roundrect (at 104.14 -3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp a34698d6-085b-485a-ba4e-0184bb2cbfd8))
|
||||
(pad "5" thru_hole roundrect (at 0 16.51 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp d099de14-88e2-441e-a73e-ff95baeb8e26))
|
||||
(pad "6" thru_hole roundrect (at 0 13.97 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 59a1ecf0-8d7b-4db7-8aa7-b858a90fc7be))
|
||||
(pad "7" thru_hole roundrect (at 0 11.43 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp b96d741a-8459-4bdc-b8c3-996255ed9d94))
|
||||
(pad "8" thru_hole roundrect (at 0 8.89 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 378396b7-816f-412c-b398-2bfbec7f6a55))
|
||||
(pad "9" thru_hole roundrect (at 0 6.35 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 3f510b37-3d66-4b1f-a522-569a3c2d8bbf))
|
||||
(pad "10" thru_hole roundrect (at 0 3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 434996e1-61bd-42ff-a716-8e2eded0b81d))
|
||||
(pad "11" thru_hole roundrect (at 0 1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp d04da8c4-1375-40f5-862d-89a40323615e))
|
||||
(pad "12" thru_hole roundrect (at 0 -1.27 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp d3eb6fac-45c7-4fd1-9912-2d8c789ffa62))
|
||||
(pad "13" thru_hole roundrect (at 0 -3.81 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 925b72f2-8f72-452d-a630-3febc08cc9ad))
|
||||
(pad "14" thru_hole roundrect (at 0 -6.35 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp b4fcf448-08be-496d-8886-fa111b5b3ed1))
|
||||
(pad "15" thru_hole roundrect (at 0 -8.89 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 71333f91-0375-4115-aff4-5c1287b2ffc3))
|
||||
(pad "16" thru_hole roundrect (at 0 -11.43 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp 1da1d33c-0ecb-4e9c-810a-201946bf2333))
|
||||
(pad "17" thru_hole roundrect (at 0 -13.97 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp da71bc08-e42f-44ea-865c-6032dc757532))
|
||||
(pad "18" thru_hole roundrect (at 0 -16.51 180) (size 2.286 1.524) (drill 0.9) (layers "*.Cu" "*.Mask") (roundrect_rratio 0.25) (tstamp e630b3ad-972b-48f8-8387-439339d1a82b))
|
||||
)
|
||||
@@ -0,0 +1,48 @@
|
||||
(footprint "IC_DRV8825_STEPPER_MOTOR_DRIVER_CARRIER" (version 20211014) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(tedit 6381DD42)
|
||||
(attr through_hole)
|
||||
(fp_text reference "REF**" (at -4.445 -12.065) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 1f808c90-825e-49d0-9480-2865cbd239e3)
|
||||
)
|
||||
(fp_text value "IC_DRV8825_STEPPER_MOTOR_DRIVER_CARRIER" (at 17.145 12.065) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp cd8735a2-64b2-46f7-86e5-f65aa6773d1a)
|
||||
)
|
||||
(fp_line (start 7.62 10.16) (end -7.62 10.16) (layer "F.SilkS") (width 0.127) (tstamp 184ea5e5-773a-4470-a1d9-ada8f7c72915))
|
||||
(fp_line (start 7.62 -10.16) (end 7.62 10.16) (layer "F.SilkS") (width 0.127) (tstamp 332001f5-cc71-4238-ac59-603f5e908f28))
|
||||
(fp_line (start -7.62 -10.16) (end 7.62 -10.16) (layer "F.SilkS") (width 0.127) (tstamp 55d53cb2-4740-441d-b360-53850205a522))
|
||||
(fp_line (start -7.62 10.16) (end -7.62 -10.16) (layer "F.SilkS") (width 0.127) (tstamp eb50be0a-af3d-4f72-8f32-b836afc4ea23))
|
||||
(fp_circle (center -8.6 -9) (end -8.5 -9) (layer "F.SilkS") (width 0.2) (fill none) (tstamp c3e53920-591b-41f7-bfa4-cdec252f192d))
|
||||
(fp_line (start 7.87 10.41) (end -7.87 10.41) (layer "F.CrtYd") (width 0.05) (tstamp 9d0dccba-7ac6-439e-bee8-29aefc9066a6))
|
||||
(fp_line (start -7.87 10.41) (end -7.87 -10.41) (layer "F.CrtYd") (width 0.05) (tstamp a58804ce-8cb0-4f6a-a098-d45aeb1aae2d))
|
||||
(fp_line (start 7.87 -10.41) (end 7.87 10.41) (layer "F.CrtYd") (width 0.05) (tstamp df63f6d8-a5ee-4781-9ec1-cc05348d1b96))
|
||||
(fp_line (start -7.87 -10.41) (end 7.87 -10.41) (layer "F.CrtYd") (width 0.05) (tstamp faf89614-78d8-4859-84c0-3ebe11c19d95))
|
||||
(fp_line (start -7.62 -10.16) (end 7.62 -10.16) (layer "F.Fab") (width 0.127) (tstamp 5ded9bb8-1156-457b-84b6-685326575cf1))
|
||||
(fp_line (start 7.62 -10.16) (end 7.62 10.16) (layer "F.Fab") (width 0.127) (tstamp 940db903-16a4-48e2-a98f-adad90558e9e))
|
||||
(fp_line (start 7.62 10.16) (end -7.62 10.16) (layer "F.Fab") (width 0.127) (tstamp a2ec6ef3-fc2f-46bb-b912-4a1b212ee2aa))
|
||||
(fp_line (start -7.62 10.16) (end -7.62 -10.16) (layer "F.Fab") (width 0.127) (tstamp b51a4bcf-71d4-420a-bfc9-af8e91ffce12))
|
||||
(fp_circle (center -8.6 -9) (end -8.5 -9) (layer "F.Fab") (width 0.2) (fill none) (tstamp c5b0755b-ae47-484b-a9d8-a14bc3fe4d6a))
|
||||
(pad "1" thru_hole rect (at -6.35 -8.89) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 741b3aed-a21f-49e6-afae-979a391e69e3))
|
||||
(pad "2" thru_hole circle (at -6.35 -6.35) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp e08eefbd-e4db-4df7-81f8-1db4f4624b8e))
|
||||
(pad "3" thru_hole circle (at -6.35 -3.81) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp fa23c747-4f5a-467c-b9ee-d1568722f9f4))
|
||||
(pad "4" thru_hole circle (at -6.35 -1.27) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 1526f4b4-4f3a-4309-88e3-e357e5e4fd01))
|
||||
(pad "5" thru_hole circle (at -6.35 1.27) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 346d4de3-c86e-4f9a-b0cd-327abb4e6e16))
|
||||
(pad "6" thru_hole circle (at -6.35 3.81) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 2b0dcfb1-04fb-4736-9932-8b443dc4b4db))
|
||||
(pad "7" thru_hole circle (at -6.35 6.35) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp f5651210-70bd-4ef4-b435-4f5b604ad5ea))
|
||||
(pad "8" thru_hole circle (at -6.35 8.89) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 4c930822-2577-4b8f-880c-ba5110fe90ca))
|
||||
(pad "9" thru_hole circle (at 6.35 8.89) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 58a376a7-9b6c-4a01-8858-f7f3b141df35))
|
||||
(pad "10" thru_hole circle (at 6.35 6.35) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 826cd63c-449b-4341-9d3a-e4f9d7be3522))
|
||||
(pad "11" thru_hole circle (at 6.35 3.81) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 3ecd8ab0-f3ff-4b33-b61a-ac8f6d635b8d))
|
||||
(pad "12" thru_hole circle (at 6.35 1.27) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp d98ae056-8cce-485d-8161-65c8fa9131da))
|
||||
(pad "13" thru_hole circle (at 6.35 -1.27) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp 7b3e4290-3208-4aa1-a099-022dbb423783))
|
||||
(pad "14" thru_hole circle (at 6.35 -3.81) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp a1c91abb-0590-4d22-9c4d-0cc9face79ef))
|
||||
(pad "15" thru_hole circle (at 6.35 -6.35) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp bcbd6a36-e817-4130-a8e3-a17958b1b374))
|
||||
(pad "16" thru_hole circle (at 6.35 -8.89) (size 1.65 1.65) (drill 1.1) (layers *.Cu *.Mask) (tstamp fa5466b9-c748-4ab2-8ed8-0ca9c70ab11e))
|
||||
(model "C:/Users/Hakan/Downloads/DRV8825 STEPPER MOTOR DRIVER CARRIER--3DModel-STEP-1.STEP"
|
||||
(offset (xyz 0 0 0))
|
||||
(scale (xyz 1 1 1))
|
||||
(rotate (xyz -90 0 0))
|
||||
)
|
||||
)
|
||||
@@ -0,0 +1,29 @@
|
||||
(footprint "L298N Motor driver module-utan motorpads" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(attr through_hole)
|
||||
(fp_text reference "REF**" (at 0 -0.5 unlocked) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 09a028f6-0462-4b35-a49b-ef2c13c355bf)
|
||||
)
|
||||
(fp_text value "L298N Motor driver module-utan motorpads" (at 0 1 unlocked) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 14df8c27-1aca-4de8-bd30-28d03a31e6f6)
|
||||
)
|
||||
(fp_line (start -12.192 19.7) (end 9.398 19.7)
|
||||
(stroke (width 0.12) (type default)) (layer "F.SilkS") (tstamp 317d2810-d3c2-49db-938a-bafe7f4e1e31))
|
||||
(fp_rect (start -21.7 -21.9) (end 21.7 21.9)
|
||||
(stroke (width 0.12) (type default)) (fill none) (layer "F.SilkS") (tstamp 5b17b7f5-435b-4a28-afb4-86ded0e884be))
|
||||
(pad "" np_thru_hole circle (at -18.5 -18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp c04b2057-c14b-4dd5-b142-15b98e9d5668))
|
||||
(pad "" np_thru_hole circle (at -18.5 18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp 7a2864d1-8946-4dc9-93a0-02a917a24fd8))
|
||||
(pad "" np_thru_hole circle (at 18.5 -18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp 269d31b6-76fe-44b5-8014-0153a125cf89))
|
||||
(pad "" np_thru_hole circle (at 18.5 18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp c86e2980-43bd-4dde-a031-8739fee66cba))
|
||||
(pad "1" thru_hole oval (at 2 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 2a20db31-01a1-4353-ae5f-88685f485774))
|
||||
(pad "2" thru_hole oval (at 4.54 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 00389037-846c-4418-9b22-7fd733ca52aa))
|
||||
(pad "3" thru_hole oval (at 7.08 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 08d18f74-257d-41fb-b81c-4b1a4997e10a))
|
||||
(pad "4" thru_hole oval (at 9.62 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp d53e5f93-12ba-4536-a4db-2ce58ccb8456))
|
||||
(pad "5" thru_hole oval (at 12.16 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 6b708c4d-114c-4ca0-87da-43019ce568bd))
|
||||
(pad "6" thru_hole oval (at 14.7 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 5d21a68b-46af-4933-ac21-2a94a7818f09))
|
||||
(pad "7" thru_hole oval (at -12.9 18.2) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp 22dc6290-4fa9-4254-9657-42161eb64109))
|
||||
(pad "8" thru_hole oval (at -7.9 18.2) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp fb5ddbfb-2f7d-4a7b-8c41-0e9c79aa84cc))
|
||||
(pad "9" thru_hole oval (at -2.9 18.2) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp cdffeec5-53fa-4dc9-a305-b74eb46b6bfe))
|
||||
)
|
||||
@@ -0,0 +1,33 @@
|
||||
(footprint "L298N Motor driver module" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(attr through_hole)
|
||||
(fp_text reference "REF**" (at 0 -0.5 unlocked) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 09a028f6-0462-4b35-a49b-ef2c13c355bf)
|
||||
)
|
||||
(fp_text value "L298N Motor driver module" (at 0 1 unlocked) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 14df8c27-1aca-4de8-bd30-28d03a31e6f6)
|
||||
)
|
||||
(fp_line (start -12.192 19.7) (end 9.398 19.7)
|
||||
(stroke (width 0.12) (type default)) (layer "F.SilkS") (tstamp 317d2810-d3c2-49db-938a-bafe7f4e1e31))
|
||||
(fp_rect (start -21.7 -21.9) (end 21.7 21.9)
|
||||
(stroke (width 0.12) (type default)) (fill none) (layer "F.SilkS") (tstamp 5b17b7f5-435b-4a28-afb4-86ded0e884be))
|
||||
(pad "" np_thru_hole circle (at -18.5 -18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp c04b2057-c14b-4dd5-b142-15b98e9d5668))
|
||||
(pad "" np_thru_hole circle (at -18.5 18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp 7a2864d1-8946-4dc9-93a0-02a917a24fd8))
|
||||
(pad "" np_thru_hole circle (at 18.5 -18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp 269d31b6-76fe-44b5-8014-0153a125cf89))
|
||||
(pad "" np_thru_hole circle (at 18.5 18.5) (size 3.5 3.5) (drill 3.5) (layers "F&B.Cu" "*.Mask") (tstamp c86e2980-43bd-4dde-a031-8739fee66cba))
|
||||
(pad "1" thru_hole oval (at 2 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 2a20db31-01a1-4353-ae5f-88685f485774))
|
||||
(pad "2" thru_hole oval (at 4.54 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 00389037-846c-4418-9b22-7fd733ca52aa))
|
||||
(pad "3" thru_hole oval (at 7.08 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 08d18f74-257d-41fb-b81c-4b1a4997e10a))
|
||||
(pad "4" thru_hole oval (at 9.62 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp d53e5f93-12ba-4536-a4db-2ce58ccb8456))
|
||||
(pad "5" thru_hole oval (at 12.16 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 6b708c4d-114c-4ca0-87da-43019ce568bd))
|
||||
(pad "6" thru_hole oval (at 14.7 19.7) (size 2 3) (drill 1) (layers "*.Cu" "*.Mask") (tstamp 5d21a68b-46af-4933-ac21-2a94a7818f09))
|
||||
(pad "7" thru_hole oval (at -12.9 18.2) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp 22dc6290-4fa9-4254-9657-42161eb64109))
|
||||
(pad "8" thru_hole oval (at -7.9 18.2) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp fb5ddbfb-2f7d-4a7b-8c41-0e9c79aa84cc))
|
||||
(pad "9" thru_hole oval (at -2.9 18.2) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp cdffeec5-53fa-4dc9-a305-b74eb46b6bfe))
|
||||
(pad "10" thru_hole oval (at -18 4.3 90) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp 0e3fa457-3725-462a-a14a-790e4c546848))
|
||||
(pad "11" thru_hole oval (at -18 9.3 90) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp ad687e58-7c86-4b4e-991b-893276f1f94c))
|
||||
(pad "12" thru_hole oval (at 18 9.3 90) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp 6302ccd5-1c76-4372-a74c-9fedcff4b8cd))
|
||||
(pad "13" thru_hole oval (at 18 4.3 90) (size 4 7) (drill 1.2) (layers "*.Cu" "*.Mask") (tstamp 9557f817-b189-4de2-b586-7853253c921f))
|
||||
)
|
||||
@@ -0,0 +1,348 @@
|
||||
(footprint "LQFP-80-1EP_10x10mm_P0.4mm_EP5.3x4.5mm_ThermalVias" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(descr "LQFP, 80 Pin (https://www.renesas.com/eu/en/package-image/pdf/outdrawing/q80.10x10.pdf), generated with kicad-footprint-generator ipc_gullwing_generator.py")
|
||||
(tags "LQFP QFP")
|
||||
(attr smd)
|
||||
(fp_text reference "REF**" (at 0 -7.35) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 70a26ab6-df9c-48f2-b232-ba5a4878094a)
|
||||
)
|
||||
(fp_text value "LQFP-80-1EP_10x10mm_P0.4mm_EP5.3x4.5mm_ThermalVias" (at 0 7.35) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 56c71606-43cb-468f-a489-b58f27e62838)
|
||||
)
|
||||
(fp_text user "${REFERENCE}" (at 0 0) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp c4eb89c8-c35e-439b-9b14-00202743cb5d)
|
||||
)
|
||||
(fp_line (start -5.11 -5.11) (end -5.11 -4.185)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp c5bddc3b-f651-475f-983e-cf26dcd39f29))
|
||||
(fp_line (start -5.11 -4.185) (end -6.4 -4.185)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp dadd5c9b-2a27-4b9e-a444-e08638750ba6))
|
||||
(fp_line (start -5.11 5.11) (end -5.11 4.185)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp f5def86f-240a-467c-8c02-0f072b5b84d7))
|
||||
(fp_line (start -4.185 -5.11) (end -5.11 -5.11)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 530dac9e-65e4-48f9-a600-3bbd1e830082))
|
||||
(fp_line (start -4.185 5.11) (end -5.11 5.11)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 7621f715-b087-44f1-8143-e6e5c792b5f4))
|
||||
(fp_line (start 4.185 -5.11) (end 5.11 -5.11)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 3679784e-2dcd-491e-8a80-f42a72cadd52))
|
||||
(fp_line (start 4.185 5.11) (end 5.11 5.11)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 943ff432-66db-4385-97ca-4d25dd102247))
|
||||
(fp_line (start 5.11 -5.11) (end 5.11 -4.185)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 3317151a-3858-4575-8c5c-394a9ed2e4d3))
|
||||
(fp_line (start 5.11 5.11) (end 5.11 4.185)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp c1bce80f-e6a5-4cc5-940a-ae00f257044d))
|
||||
(fp_line (start -6.65 -4.18) (end -6.65 0)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp da9a1a45-ac9e-41ea-bd71-4e69a36ecfc9))
|
||||
(fp_line (start -6.65 4.18) (end -6.65 0)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 051c90c9-9e89-49eb-9ca7-bcb39cb1a823))
|
||||
(fp_line (start -5.25 -5.25) (end -5.25 -4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 29a0c261-d919-4091-adb0-248e8090cde4))
|
||||
(fp_line (start -5.25 -4.18) (end -6.65 -4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp d063dbd7-7a5d-4f1a-aeed-d918ab802785))
|
||||
(fp_line (start -5.25 4.18) (end -6.65 4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 3ee90fd5-7212-4e30-8044-e032ddbda20e))
|
||||
(fp_line (start -5.25 5.25) (end -5.25 4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 9ef09f70-188d-4b81-9741-49766493be45))
|
||||
(fp_line (start -4.18 -6.65) (end -4.18 -5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 4a909761-7e01-4bef-a53d-25fc094e00d2))
|
||||
(fp_line (start -4.18 -5.25) (end -5.25 -5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 3b0255f2-4927-4627-9924-9584744fc2a2))
|
||||
(fp_line (start -4.18 5.25) (end -5.25 5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 3482fba9-bad5-4c49-8c24-f0181769fb20))
|
||||
(fp_line (start -4.18 6.65) (end -4.18 5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp c5509683-4355-40bd-bbde-e7eb51c8f247))
|
||||
(fp_line (start 0 -6.65) (end -4.18 -6.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 5714a1dc-f2b7-4ff2-b089-7521d2416a6f))
|
||||
(fp_line (start 0 -6.65) (end 4.18 -6.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 8acd3e0e-36a7-41ae-99df-1c5f22d1ec62))
|
||||
(fp_line (start 0 6.65) (end -4.18 6.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp f40345b6-b387-4fd0-aa68-f1d362375732))
|
||||
(fp_line (start 0 6.65) (end 4.18 6.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp e708afeb-860e-4202-b808-c9d599294938))
|
||||
(fp_line (start 4.18 -6.65) (end 4.18 -5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 8ebbfe90-811e-480f-9089-55aa4ea65885))
|
||||
(fp_line (start 4.18 -5.25) (end 5.25 -5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 9071e95a-8022-44b0-8abe-ef7b0ee1020c))
|
||||
(fp_line (start 4.18 5.25) (end 5.25 5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp cf570861-0bc3-4701-9148-3284e7c36c37))
|
||||
(fp_line (start 4.18 6.65) (end 4.18 5.25)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp a29515fd-97b0-4960-9058-63c30163e785))
|
||||
(fp_line (start 5.25 -5.25) (end 5.25 -4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 6e1b7053-41ca-4470-8a3b-d4fcc9ebaf85))
|
||||
(fp_line (start 5.25 -4.18) (end 6.65 -4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp a37dada8-0704-417d-beaf-9928452138d6))
|
||||
(fp_line (start 5.25 4.18) (end 6.65 4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp b6a81440-240d-46e2-b5c6-60d154000d9e))
|
||||
(fp_line (start 5.25 5.25) (end 5.25 4.18)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 6f1c3838-3a73-42f7-911c-d9dba0d09bc0))
|
||||
(fp_line (start 6.65 -4.18) (end 6.65 0)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 4985a328-96f8-4248-bbb9-19b68bbcea52))
|
||||
(fp_line (start 6.65 4.18) (end 6.65 0)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 4d6df114-c8a5-439b-9bc8-72b0c0d0a875))
|
||||
(fp_line (start -5 -4) (end -4 -5)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp c60a5f83-09e1-4784-9ca1-a45fd876984c))
|
||||
(fp_line (start -5 5) (end -5 -4)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 5f0a98af-340b-4806-a4a9-354e3ddc6b64))
|
||||
(fp_line (start -4 -5) (end 5 -5)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 3fdeb27d-a382-4fc8-a55b-6a7393c81183))
|
||||
(fp_line (start 5 -5) (end 5 5)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp cb92a039-abdd-4888-a265-be65549f967d))
|
||||
(fp_line (start 5 5) (end -5 5)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 724131b3-f967-4db3-9ebe-79c738e1642c))
|
||||
(pad "" smd custom (at -2.225 -2.025) (size 0.251864 0.251864) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.251946 -0.0907)
|
||||
(xy 0.251946 -0.0907)
|
||||
(xy 0.251946 -0.013058)
|
||||
(xy 0.148187 0.0907)
|
||||
(xy -0.251946 0.0907)
|
||||
)
|
||||
(width 0.181401) (fill yes))
|
||||
) (tstamp 28f4ea71-2775-4c4f-9ce4-5fe517418270))
|
||||
(pad "" smd roundrect (at -2.225 -1.2) (size 0.685292 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp ace3dc98-8d6d-4849-95da-6221efe251a5))
|
||||
(pad "" smd roundrect (at -2.225 0) (size 0.685292 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 457afe70-9334-41d5-b1a7-42603d03c053))
|
||||
(pad "" smd roundrect (at -2.225 1.2) (size 0.685292 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 016c8c32-3ffe-41e2-bee0-9d54aae88d95))
|
||||
(pad "" smd custom (at -2.225 2.025) (size 0.251864 0.251864) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.251946 -0.0907)
|
||||
(xy 0.148187 -0.0907)
|
||||
(xy 0.251946 0.013058)
|
||||
(xy 0.251946 0.0907)
|
||||
(xy -0.251946 0.0907)
|
||||
)
|
||||
(width 0.181401) (fill yes))
|
||||
) (tstamp 8297f017-cc08-41b4-9e72-cac57b6af107))
|
||||
(pad "" smd custom (at -1.2 -2.025) (size 0.275842 0.275842) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.396776 -0.094442)
|
||||
(xy 0.396776 -0.094442)
|
||||
(xy 0.396776 0.022402)
|
||||
(xy 0.324737 0.094442)
|
||||
(xy -0.324737 0.094442)
|
||||
(xy -0.396776 0.022402)
|
||||
)
|
||||
(width 0.173919) (fill yes))
|
||||
) (tstamp 98104fdc-d8a9-4b30-bc46-07b1452b5e7b))
|
||||
(pad "" smd roundrect (at -1.2 -1.2) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 56615431-ec6b-49bf-b6c7-8e06a826515e))
|
||||
(pad "" smd roundrect (at -1.2 0) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp eca585ef-f6d3-44a2-9b23-06c0f135db6a))
|
||||
(pad "" smd roundrect (at -1.2 1.2) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 1f5212d2-d855-4380-81b9-7da89c06b550))
|
||||
(pad "" smd custom (at -1.2 2.025) (size 0.275842 0.275842) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.396776 -0.022402)
|
||||
(xy -0.324737 -0.094442)
|
||||
(xy 0.324737 -0.094442)
|
||||
(xy 0.396776 -0.022402)
|
||||
(xy 0.396776 0.094442)
|
||||
(xy -0.396776 0.094442)
|
||||
)
|
||||
(width 0.173919) (fill yes))
|
||||
) (tstamp 4d107af8-6e67-485f-97e4-a79041dfe91b))
|
||||
(pad "" smd custom (at 0 -2.025) (size 0.275842 0.275842) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.396776 -0.094442)
|
||||
(xy 0.396776 -0.094442)
|
||||
(xy 0.396776 0.022402)
|
||||
(xy 0.324737 0.094442)
|
||||
(xy -0.324737 0.094442)
|
||||
(xy -0.396776 0.022402)
|
||||
)
|
||||
(width 0.173919) (fill yes))
|
||||
) (tstamp 69ce57af-8692-4681-851f-05bc6b7dcd2d))
|
||||
(pad "" smd roundrect (at 0 -1.2) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 695d8e54-c6f8-4dfe-988d-304fb510d9b3))
|
||||
(pad "" smd roundrect (at 0 0) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 9dc5aade-238d-41b5-a8bd-17246da04521))
|
||||
(pad "" smd roundrect (at 0 1.2) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 68228e66-bac4-4d77-9622-0ebf44e75e11))
|
||||
(pad "" smd custom (at 0 2.025) (size 0.275842 0.275842) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.396776 -0.022402)
|
||||
(xy -0.324737 -0.094442)
|
||||
(xy 0.324737 -0.094442)
|
||||
(xy 0.396776 -0.022402)
|
||||
(xy 0.396776 0.094442)
|
||||
(xy -0.396776 0.094442)
|
||||
)
|
||||
(width 0.173919) (fill yes))
|
||||
) (tstamp 29ba71eb-7459-4020-bf47-c0e12aaf082e))
|
||||
(pad "" smd custom (at 1.2 -2.025) (size 0.275842 0.275842) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.396776 -0.094442)
|
||||
(xy 0.396776 -0.094442)
|
||||
(xy 0.396776 0.022402)
|
||||
(xy 0.324737 0.094442)
|
||||
(xy -0.324737 0.094442)
|
||||
(xy -0.396776 0.022402)
|
||||
)
|
||||
(width 0.173919) (fill yes))
|
||||
) (tstamp 5606937d-2462-41df-ae65-5390836b3089))
|
||||
(pad "" smd roundrect (at 1.2 -1.2) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp d95bc55d-5437-4ce2-a6a7-2f6f9bd08c83))
|
||||
(pad "" smd roundrect (at 1.2 0) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 528e6ae8-c7f4-4de4-8a42-c1153f9c72ca))
|
||||
(pad "" smd roundrect (at 1.2 1.2) (size 0.967471 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp d957b47d-59f6-4d60-b26c-b5bcb6627e0c))
|
||||
(pad "" smd custom (at 1.2 2.025) (size 0.275842 0.275842) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.396776 -0.022402)
|
||||
(xy -0.324737 -0.094442)
|
||||
(xy 0.324737 -0.094442)
|
||||
(xy 0.396776 -0.022402)
|
||||
(xy 0.396776 0.094442)
|
||||
(xy -0.396776 0.094442)
|
||||
)
|
||||
(width 0.173919) (fill yes))
|
||||
) (tstamp 1940cced-0695-4c6b-95a8-ed760b617735))
|
||||
(pad "" smd custom (at 2.225 -2.025) (size 0.251864 0.251864) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.251946 -0.0907)
|
||||
(xy 0.251946 -0.0907)
|
||||
(xy 0.251946 0.0907)
|
||||
(xy -0.148187 0.0907)
|
||||
(xy -0.251946 -0.013058)
|
||||
)
|
||||
(width 0.181401) (fill yes))
|
||||
) (tstamp fe6b212c-b08d-40e8-b6af-119b0a54a6f8))
|
||||
(pad "" smd roundrect (at 2.225 -1.2) (size 0.685292 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 29ae4d63-60a3-400a-9119-0444f5c74a7d))
|
||||
(pad "" smd roundrect (at 2.225 0) (size 0.685292 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 3b4198a9-29e7-4b87-ab6b-39a740dc63ea))
|
||||
(pad "" smd roundrect (at 2.225 1.2) (size 0.685292 0.967471) (layers "F.Paste") (roundrect_rratio 0.25) (tstamp 95f63383-7bcd-4986-a9d4-5411fc4cc19b))
|
||||
(pad "" smd custom (at 2.225 2.025) (size 0.251864 0.251864) (layers "F.Paste")
|
||||
(options (clearance outline) (anchor circle))
|
||||
(primitives
|
||||
(gr_poly
|
||||
(pts
|
||||
(xy -0.251946 0.013058)
|
||||
(xy -0.148187 -0.0907)
|
||||
(xy 0.251946 -0.0907)
|
||||
(xy 0.251946 0.0907)
|
||||
(xy -0.251946 0.0907)
|
||||
)
|
||||
(width 0.181401) (fill yes))
|
||||
) (tstamp 5851fa62-7fbc-4c3e-b562-32571c57b543))
|
||||
(pad "1" smd roundrect (at -5.6625 -3.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 4daef23d-07c8-4f34-8723-ed9bc3d6b6cb))
|
||||
(pad "2" smd roundrect (at -5.6625 -3.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 80bbd5c1-90c3-4e16-84cb-d1a9ad4f4555))
|
||||
(pad "3" smd roundrect (at -5.6625 -3) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 57798149-8b9a-42cd-a306-84d63971dbfd))
|
||||
(pad "4" smd roundrect (at -5.6625 -2.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 71c128b4-c833-4d94-a2ee-bc4af75063ce))
|
||||
(pad "5" smd roundrect (at -5.6625 -2.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp e2e6943e-5dd0-47ee-9ccf-d93c05d6aa7d))
|
||||
(pad "6" smd roundrect (at -5.6625 -1.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 681064bb-a98c-4135-a898-1667adbad002))
|
||||
(pad "7" smd roundrect (at -5.6625 -1.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 61d7c1c5-09a6-4353-80e6-349f7b9d1c44))
|
||||
(pad "8" smd roundrect (at -5.6625 -1) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp a40afa06-82eb-4b41-8b78-afcd4b56635f))
|
||||
(pad "9" smd roundrect (at -5.6625 -0.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp bbe7b114-0763-4f51-9471-ee9f1ddddb2d))
|
||||
(pad "10" smd roundrect (at -5.6625 -0.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp bb46ccb4-88df-4333-82a5-9639d064c1a7))
|
||||
(pad "11" smd roundrect (at -5.6625 0.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 1f61fe27-8c24-48bb-9ec9-f5fa56292bda))
|
||||
(pad "12" smd roundrect (at -5.6625 0.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp cf3c9f3a-b1d8-4ce2-a95d-aba48d872ab4))
|
||||
(pad "13" smd roundrect (at -5.6625 1) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 798cbbb5-1c07-4b16-81c5-e3d269aa517c))
|
||||
(pad "14" smd roundrect (at -5.6625 1.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 25796559-fe4a-4b6e-88fb-aab86db9b3d5))
|
||||
(pad "15" smd roundrect (at -5.6625 1.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp c8e0607f-0619-497f-aac3-2c542027833b))
|
||||
(pad "16" smd roundrect (at -5.6625 2.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 505371d5-69e1-4023-a2b3-9078c042c98a))
|
||||
(pad "17" smd roundrect (at -5.6625 2.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 8320eb5d-5dee-4299-b385-226c77bd4226))
|
||||
(pad "18" smd roundrect (at -5.6625 3) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 28d36ebb-6a23-474f-b96b-0ab32b065c7a))
|
||||
(pad "19" smd roundrect (at -5.6625 3.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp d61558ae-2451-42fe-a996-6e0d836f682f))
|
||||
(pad "20" smd roundrect (at -5.6625 3.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 2ef10c3c-1b85-4037-8003-17be6f26d23f))
|
||||
(pad "21" smd roundrect (at -3.8 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 94cae820-b620-4a09-a1e9-8e2476592263))
|
||||
(pad "22" smd roundrect (at -3.4 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 1cd4d34c-e3f5-413a-aae5-f4089b83270a))
|
||||
(pad "23" smd roundrect (at -3 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp cc110e54-3685-4781-b4eb-35134891a364))
|
||||
(pad "24" smd roundrect (at -2.6 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 589ed67a-fcfc-42c3-9a97-d82870d65f96))
|
||||
(pad "25" smd roundrect (at -2.2 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp cb26aabe-ef10-4d14-a7de-83a599d1cd24))
|
||||
(pad "26" smd roundrect (at -1.8 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 806dbab8-f1ed-4d80-bbaa-f9e2087abd20))
|
||||
(pad "27" smd roundrect (at -1.4 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 1cc486d5-ab04-4f7c-a154-5b58bbecde54))
|
||||
(pad "28" smd roundrect (at -1 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp c66c7a13-3792-4c28-9d48-c10990aa30cb))
|
||||
(pad "29" smd roundrect (at -0.6 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 2b623c24-987e-4f8f-804c-29f4a63dc949))
|
||||
(pad "30" smd roundrect (at -0.2 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp e2746c2b-6047-412a-b9f0-aac5f4817b1b))
|
||||
(pad "31" smd roundrect (at 0.2 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp a363212b-60c8-4d69-a56b-078490918f7f))
|
||||
(pad "32" smd roundrect (at 0.6 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp cd117bd9-1811-440a-a334-753a9914a021))
|
||||
(pad "33" smd roundrect (at 1 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp f79260c8-8985-4e34-b936-b31b559f4784))
|
||||
(pad "34" smd roundrect (at 1.4 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 2c6f0908-3752-4f4e-8e4e-71db83bcc7a1))
|
||||
(pad "35" smd roundrect (at 1.8 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp b743a367-cb36-410c-80f8-f09e10b366ef))
|
||||
(pad "36" smd roundrect (at 2.2 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 27e31d4b-d83e-4150-8a9f-3473455e2447))
|
||||
(pad "37" smd roundrect (at 2.6 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp d829991f-31cf-48e9-ac59-c0db20d007cb))
|
||||
(pad "38" smd roundrect (at 3 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 4d35a71c-1c0a-4db4-a544-d0970f9bc662))
|
||||
(pad "39" smd roundrect (at 3.4 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 33fae0a6-c7e8-4bc2-a2ec-9960a3f24fea))
|
||||
(pad "40" smd roundrect (at 3.8 5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 6714c4a3-e4fe-488d-a47c-0fb19a41c6e6))
|
||||
(pad "41" smd roundrect (at 5.6625 3.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp c91bdcda-0ef9-4442-8028-f8a016a4eda0))
|
||||
(pad "42" smd roundrect (at 5.6625 3.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp cdf5baa1-903b-41c8-a8fc-da83e43ba080))
|
||||
(pad "43" smd roundrect (at 5.6625 3) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp fe8e28cf-2551-4e27-ab22-2a4ef391cc43))
|
||||
(pad "44" smd roundrect (at 5.6625 2.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 3457736e-76df-4073-aa88-d2d0b90f6279))
|
||||
(pad "45" smd roundrect (at 5.6625 2.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 202baced-75c6-43f6-9c65-e0e33beedfbb))
|
||||
(pad "46" smd roundrect (at 5.6625 1.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 93553dd1-e0c9-49de-af0c-42a0849eee29))
|
||||
(pad "47" smd roundrect (at 5.6625 1.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp b25f7e27-2b15-4933-9905-4bdf1dd499c7))
|
||||
(pad "48" smd roundrect (at 5.6625 1) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 8cbb89ee-3844-4a26-88ae-c4345619c983))
|
||||
(pad "49" smd roundrect (at 5.6625 0.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp a533518f-f81b-481e-ad7b-4d5e9198a1f7))
|
||||
(pad "50" smd roundrect (at 5.6625 0.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 3a2a942e-c501-4fd4-84ea-3ad96ff1a192))
|
||||
(pad "51" smd roundrect (at 5.6625 -0.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 79f0f9b9-9b21-45f3-97e2-88ba82ce088c))
|
||||
(pad "52" smd roundrect (at 5.6625 -0.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp c4aa2af9-475d-4b77-ba9c-90f14ca002ce))
|
||||
(pad "53" smd roundrect (at 5.6625 -1) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 96e062a8-bb55-423a-9a24-47af09eb9c9e))
|
||||
(pad "54" smd roundrect (at 5.6625 -1.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp f9a9aabe-e5f2-42fc-9d57-c3e2a45a9768))
|
||||
(pad "55" smd roundrect (at 5.6625 -1.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp b05c78a8-6fd1-46d2-a9f0-39acd1c3760b))
|
||||
(pad "56" smd roundrect (at 5.6625 -2.2) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 6a0eaa31-4f55-4617-8f34-6a1acdd3140e))
|
||||
(pad "57" smd roundrect (at 5.6625 -2.6) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 088cb985-3a4f-4c5b-9fa5-65d48ad13894))
|
||||
(pad "58" smd roundrect (at 5.6625 -3) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 5682c911-0567-497c-92ed-dd7984108790))
|
||||
(pad "59" smd roundrect (at 5.6625 -3.4) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 4bac6f90-0038-422e-a1eb-10dfcb1f7dd7))
|
||||
(pad "60" smd roundrect (at 5.6625 -3.8) (size 1.475 0.25) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 0b95bd24-1012-4fe1-801b-d26fcd007595))
|
||||
(pad "61" smd roundrect (at 3.8 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 282de30a-8759-4271-ba7b-3ebbf5196414))
|
||||
(pad "62" smd roundrect (at 3.4 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 0f23526c-60d9-4637-aedf-656bf5417285))
|
||||
(pad "63" smd roundrect (at 3 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 863d77fb-3c5f-45c9-b14c-3810b3f25173))
|
||||
(pad "64" smd roundrect (at 2.6 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 0c69ca09-47d5-4a65-af2e-bdb0338ae166))
|
||||
(pad "65" smd roundrect (at 2.2 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 9de94c1c-dcee-4f27-88b6-beddb05a688b))
|
||||
(pad "66" smd roundrect (at 1.8 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 5766892b-b632-4f08-a7d8-8c08c196450c))
|
||||
(pad "67" smd roundrect (at 1.4 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp fb2f46f5-c78f-4fbd-ba08-8a4100c976d8))
|
||||
(pad "68" smd roundrect (at 1 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 6d6e1fad-c06e-4786-a691-fba5e9dd0e1b))
|
||||
(pad "69" smd roundrect (at 0.6 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 42103648-634c-419f-9fbc-4ba66b82d1aa))
|
||||
(pad "70" smd roundrect (at 0.2 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 1eaf98ee-0640-45c9-b717-2450f475a292))
|
||||
(pad "71" smd roundrect (at -0.2 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 27bfab82-b658-43fa-8d50-59ee0ca72d97))
|
||||
(pad "72" smd roundrect (at -0.6 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 60e5fc74-08a3-4db8-a1c0-4684abffcb6a))
|
||||
(pad "73" smd roundrect (at -1 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 22608ae5-d499-4454-b51d-86f40e1f9679))
|
||||
(pad "74" smd roundrect (at -1.4 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp ac334e14-408a-44ca-a5f3-9ac479bf2303))
|
||||
(pad "75" smd roundrect (at -1.8 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp eb85667d-1d76-4a1a-b218-6420eed784e8))
|
||||
(pad "76" smd roundrect (at -2.2 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 4e722732-36fb-479b-816a-a6981bfd2e2c))
|
||||
(pad "77" smd roundrect (at -2.6 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp d14f7c99-5641-42a7-9325-1fc1bdebad7d))
|
||||
(pad "78" smd roundrect (at -3 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 08220d57-c9b6-4a80-b56b-f9d237a90e79))
|
||||
(pad "79" smd roundrect (at -3.4 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 9d5bd4e3-9c57-429e-8f79-5eb9908f5665))
|
||||
(pad "80" smd roundrect (at -3.8 -5.6625) (size 0.25 1.475) (layers "F.Cu" "F.Paste" "F.Mask") (roundrect_rratio 0.25) (tstamp 56578a29-4295-4269-b1c7-4244a7f89431))
|
||||
(pad "81" thru_hole circle (at -1.8 -1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 16391819-43ac-4734-80c1-34ad12a20b03))
|
||||
(pad "81" thru_hole circle (at -1.8 -0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp c79c41d4-2bbc-4f52-a74b-31a4fba09e9b))
|
||||
(pad "81" thru_hole circle (at -1.8 0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 46d71156-7c0a-47c6-999d-2d75a92a9dcd))
|
||||
(pad "81" thru_hole circle (at -1.8 1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 12a77539-6cda-47cc-962e-6d19266036b7))
|
||||
(pad "81" thru_hole circle (at -0.6 -1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp adb21cd2-d504-44d7-99f1-8a56890c2bed))
|
||||
(pad "81" thru_hole circle (at -0.6 -0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 0bbaa0b7-6acc-46ea-9259-124b37923068))
|
||||
(pad "81" thru_hole circle (at -0.6 0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 3af3c50a-a553-41cb-aaad-4b5d4451be2c))
|
||||
(pad "81" thru_hole circle (at -0.6 1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp c286aaae-6526-436f-930d-3b059458a276))
|
||||
(pad "81" smd rect (at 0 0) (size 4.1 4.1) (layers "B.Cu") (tstamp 3524f943-29c4-43e0-92bc-5a9a84114d38))
|
||||
(pad "81" smd rect (at 0 0) (size 5.3 4.5) (layers "F.Cu" "F.Mask") (tstamp 88727049-5477-40c7-8453-c60008c63992))
|
||||
(pad "81" thru_hole circle (at 0.6 -1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 7be4eceb-8fd4-44a3-ac4c-9e24c2e9defd))
|
||||
(pad "81" thru_hole circle (at 0.6 -0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp b2019f80-ee10-4345-9965-c0bac17c6275))
|
||||
(pad "81" thru_hole circle (at 0.6 0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp da8885f6-e2d7-4797-9607-cfb52f650bf0))
|
||||
(pad "81" thru_hole circle (at 0.6 1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp aa3a8115-8e44-4ad1-bd65-ccd7f22502df))
|
||||
(pad "81" thru_hole circle (at 1.8 -1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 6706993c-a834-462c-8357-a40f1869517b))
|
||||
(pad "81" thru_hole circle (at 1.8 -0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 726bba8c-e324-4c4f-afdf-f6697cd388e4))
|
||||
(pad "81" thru_hole circle (at 1.8 0.6) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 88fe9863-0350-4442-905f-e914481006f5))
|
||||
(pad "81" thru_hole circle (at 1.8 1.8) (size 0.5 0.5) (drill 0.2) (layers "*.Cu") (tstamp 118dd107-8d39-4899-a0da-068651ad52b7))
|
||||
(model "${KICAD7_3DMODEL_DIR}/Package_QFP.3dshapes/LQFP-80-1EP_10x10mm_P0.4mm_EP5.3x4.5mm.wrl"
|
||||
(offset (xyz 0 0 0))
|
||||
(scale (xyz 1 1 1))
|
||||
(rotate (xyz 0 0 0))
|
||||
)
|
||||
)
|
||||
121
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/MODULE_ESP32_DEVKIT_V1.kicad_mod
Executable file
121
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/MODULE_ESP32_DEVKIT_V1.kicad_mod
Executable file
@@ -0,0 +1,121 @@
|
||||
|
||||
(footprint MODULE_ESP32_DEVKIT_V1 (layer F.Cu) (tedit 6381D09B)
|
||||
(descr "")
|
||||
(fp_text reference REF** (at -11.355 -27.36 0) (layer F.SilkS)
|
||||
(effects (font (size 1.0 1.0) (thickness 0.15)))
|
||||
)
|
||||
(fp_text value MODULE_ESP32_DEVKIT_V1 (at -0.56 27.36 0) (layer F.Fab)
|
||||
(effects (font (size 1.0 1.0) (thickness 0.15)))
|
||||
)
|
||||
(pad 1 thru_hole rect (at -12.7 -15.515) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 2 thru_hole circle (at -12.7 -12.975) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 3 thru_hole circle (at -12.7 -10.435) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 4 thru_hole circle (at -12.7 -7.895) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 5 thru_hole circle (at -12.7 -5.355) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 6 thru_hole circle (at -12.7 -2.815) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 7 thru_hole circle (at -12.7 -0.275) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 8 thru_hole circle (at -12.7 2.265) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 9 thru_hole circle (at -12.7 4.805) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 10 thru_hole circle (at -12.7 7.345) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 11 thru_hole circle (at -12.7 9.885) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 12 thru_hole circle (at -12.7 12.425) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 13 thru_hole circle (at -12.7 14.965) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 14 thru_hole circle (at -12.7 17.505) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 15 thru_hole circle (at -12.7 20.045) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 30 thru_hole circle (at 12.7 -15.515) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 29 thru_hole circle (at 12.7 -12.975) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 28 thru_hole circle (at 12.7 -10.435) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 27 thru_hole circle (at 12.7 -7.895) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 26 thru_hole circle (at 12.7 -5.355) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 25 thru_hole circle (at 12.7 -2.815) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 24 thru_hole circle (at 12.7 -0.275) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 23 thru_hole circle (at 12.7 2.265) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 22 thru_hole circle (at 12.7 4.805) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 21 thru_hole circle (at 12.7 7.345) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 20 thru_hole circle (at 12.7 9.885) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 19 thru_hole circle (at 12.7 12.425) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 18 thru_hole circle (at 12.7 14.965) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 17 thru_hole circle (at 12.7 17.505) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad 16 thru_hole circle (at 12.7 20.045) (size 2.0 2.0) (drill 1.02) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at -12.28 23.475) (size 3.0 3.0) (drill 3.0) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at 12.23 23.475) (size 3.0 3.0) (drill 3.0) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at 12.23 -23.475) (size 3.0 3.0) (drill 3.0) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at -12.28 -23.475) (size 3.0 3.0) (drill 3.0) (layers *.Cu *.Mask))
|
||||
(fp_line (start -14.28 -25.475) (end -3.211 -25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -3.211 -25.475) (end 3.5 -25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 3.5 -25.475) (end 14.23 -25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 14.23 -25.475) (end 14.23 25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start 14.23 25.475) (end -14.28 25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.28 25.475) (end -14.28 -25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -14.28 -25.475) (end 14.23 -25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.28 25.475) (end -14.28 -25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_circle (center -14.85 -15.515) (end -14.75 -15.515) (layer F.SilkS) (width 0.2))
|
||||
(fp_circle (center -14.85 -15.515) (end -14.75 -15.515) (layer F.Fab) (width 0.2))
|
||||
(fp_line (start 14.23 -25.475) (end 14.23 25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -14.28 25.475) (end -8.91 25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -8.91 25.475) (end 8.78 25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 8.78 25.475) (end 14.23 25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -8.91 25.475) (end -8.91 18.985) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -8.91 18.985) (end -8.91 6.355) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -8.91 6.355) (end 8.78 6.355) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 8.78 6.355) (end 8.78 18.985) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 8.78 18.985) (end 8.78 25.475) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -8.91 18.985) (end 8.78 18.985) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 3.5 -25.475) (end 3.5 -21.585) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 3.5 -21.585) (end -3.211 -21.585) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -3.211 -21.585) (end -3.211 -25.475) (layer F.Fab) (width 0.127))
|
||||
(zone (net 0) (net_name "") (layer F.Cu) (hatch full 0.508)
|
||||
(connect_pads (clearance 0))
|
||||
(min_thickness 0.01)
|
||||
(keepout (tracks not_allowed) (vias not_allowed) (pads not_allowed ) (copperpour not_allowed) (footprints allowed))
|
||||
(fill (thermal_gap 0.508) (thermal_bridge_width 0.508))
|
||||
(polygon
|
||||
(pts
|
||||
(xy -8.91 18.985)
|
||||
(xy 8.78 18.985)
|
||||
(xy 8.78 25.475)
|
||||
(xy -8.91 25.475)
|
||||
)
|
||||
)
|
||||
)
|
||||
(zone (net 0) (net_name "") (layers *.Cu) (hatch full 0.508)
|
||||
(connect_pads (clearance 0))
|
||||
(min_thickness 0.01)
|
||||
(keepout (tracks allowed) (vias not_allowed) (pads allowed ) (copperpour allowed) (footprints allowed))
|
||||
(fill (thermal_gap 0.508) (thermal_bridge_width 0.508))
|
||||
(polygon
|
||||
(pts
|
||||
(xy -8.91 18.985)
|
||||
(xy 8.78 18.985)
|
||||
(xy 8.78 25.475)
|
||||
(xy -8.91 25.475)
|
||||
)
|
||||
)
|
||||
)
|
||||
(zone (net 0) (net_name "") (layer B.Cu) (hatch full 0.508)
|
||||
(connect_pads (clearance 0))
|
||||
(min_thickness 0.01)
|
||||
(keepout (tracks not_allowed) (vias not_allowed) (pads not_allowed ) (copperpour not_allowed) (footprints allowed))
|
||||
(fill (thermal_gap 0.508) (thermal_bridge_width 0.508))
|
||||
(polygon
|
||||
(pts
|
||||
(xy -8.91 18.985)
|
||||
(xy 8.78 18.985)
|
||||
(xy 8.78 25.475)
|
||||
(xy -8.91 25.475)
|
||||
)
|
||||
)
|
||||
)
|
||||
(fp_line (start -14.28 -25.475) (end -3.211 -25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -3.211 -25.475) (end 3.5 -25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start 3.5 -25.475) (end 14.23 -25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.28 25.475) (end -14.28 -25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start 14.23 -25.475) (end 14.23 25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.28 25.475) (end -8.91 25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -8.91 25.475) (end 8.78 25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start 8.78 25.475) (end 14.23 25.475) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.53 -25.725) (end -14.53 25.725) (layer F.CrtYd) (width 0.05))
|
||||
(fp_line (start -14.53 25.725) (end 14.48 25.725) (layer F.CrtYd) (width 0.05))
|
||||
(fp_line (start 14.48 25.725) (end 14.48 -25.725) (layer F.CrtYd) (width 0.05))
|
||||
(fp_line (start 14.48 -25.725) (end -14.53 -25.725) (layer F.CrtYd) (width 0.05))
|
||||
)
|
||||
@@ -0,0 +1,64 @@
|
||||
|
||||
(footprint MODULE_ESP32_NODEMCU (layer F.Cu) (tedit 6381D25E)
|
||||
(descr "")
|
||||
(fp_text reference REF** (at -11.075 -29.385 0) (layer F.SilkS)
|
||||
(effects (font (size 1.0 1.0) (thickness 0.15)))
|
||||
)
|
||||
(fp_text value MODULE_ESP32_NODEMCU (at -1.55 29.385 0) (layer F.Fab)
|
||||
(effects (font (size 1.0 1.0) (thickness 0.15)))
|
||||
)
|
||||
(pad J5_19 thru_hole circle (at -13.0 -22.86) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_18 thru_hole circle (at -13.0 -20.32) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_1 thru_hole rect (at -13.0 22.86) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_17 thru_hole circle (at -13.0 -17.78) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_16 thru_hole circle (at -13.0 -15.24) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_15 thru_hole circle (at -13.0 -12.7) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_14 thru_hole circle (at -13.0 -10.16) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_13 thru_hole circle (at -13.0 -7.62) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_12 thru_hole circle (at -13.0 -5.08) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_11 thru_hole circle (at -13.0 -2.54) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_10 thru_hole circle (at -13.0 0.0) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_9 thru_hole circle (at -13.0 2.54) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_8 thru_hole circle (at -13.0 5.08) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_7 thru_hole circle (at -13.0 7.62) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_6 thru_hole circle (at -13.0 10.16) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_5 thru_hole circle (at -13.0 12.7) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_4 thru_hole circle (at -13.0 15.24) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_3 thru_hole circle (at -13.0 17.78) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J5_2 thru_hole circle (at -13.0 20.32) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_19 thru_hole circle (at 13.0 22.86) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_18 thru_hole circle (at 13.0 20.32) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_17 thru_hole circle (at 13.0 17.78) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_16 thru_hole circle (at 13.0 15.24) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_15 thru_hole circle (at 13.0 12.7) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_14 thru_hole circle (at 13.0 10.16) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_13 thru_hole circle (at 13.0 7.62) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_12 thru_hole circle (at 13.0 5.08) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_11 thru_hole circle (at 13.0 2.54) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_10 thru_hole circle (at 13.0 0.0) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_9 thru_hole circle (at 13.0 -2.54) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_8 thru_hole circle (at 13.0 -5.08) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_7 thru_hole circle (at 13.0 -7.62) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_6 thru_hole circle (at 13.0 -10.16) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_5 thru_hole circle (at 13.0 -12.7) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_4 thru_hole circle (at 13.0 -15.24) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_3 thru_hole circle (at 13.0 -17.78) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_2 thru_hole circle (at 13.0 -20.32) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad J4_1 thru_hole rect (at 13.0 -22.86) (size 1.35 1.35) (drill 0.9) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at -12.5 26.0) (size 2.25 2.25) (drill 2.25) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at 12.5 26.0) (size 2.25 2.25) (drill 2.25) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at -12.5 -26.0) (size 2.25 2.25) (drill 2.25) (layers *.Cu *.Mask))
|
||||
(pad None np_thru_hole circle (at 12.5 -26.0) (size 2.25 2.25) (drill 2.25) (layers *.Cu *.Mask))
|
||||
(fp_line (start -14.0 27.5) (end -14.0 -27.5) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -14.0 -27.5) (end 14.0 -27.5) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 14.0 -27.5) (end 14.0 27.5) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start 14.0 27.5) (end -14.0 27.5) (layer F.Fab) (width 0.127))
|
||||
(fp_line (start -14.0 -27.5) (end -14.0 27.5) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.0 -27.5) (end 14.0 -27.5) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start 14.0 -27.5) (end 14.0 27.5) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.0 27.5) (end 14.0 27.5) (layer F.SilkS) (width 0.127))
|
||||
(fp_line (start -14.25 -27.75) (end -14.25 27.75) (layer F.CrtYd) (width 0.05))
|
||||
(fp_line (start -14.25 27.75) (end 14.25 27.75) (layer F.CrtYd) (width 0.05))
|
||||
(fp_line (start 14.25 27.75) (end 14.25 -27.75) (layer F.CrtYd) (width 0.05))
|
||||
(fp_line (start 14.25 -27.75) (end -14.25 -27.75) (layer F.CrtYd) (width 0.05))
|
||||
)
|
||||
19
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/PWM_module_ebay.kicad_mod
Executable file
19
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/PWM_module_ebay.kicad_mod
Executable file
@@ -0,0 +1,19 @@
|
||||
(footprint "PWM_module_ebay" (version 20211014) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(tedit 0)
|
||||
(attr smd)
|
||||
(fp_text reference "REF**" (at 0 -0.5 unlocked) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp c8121568-d3f5-48c8-9ecf-a54c1a1074ad)
|
||||
)
|
||||
(fp_text value "PWM_module_ebay" (at 0 1 unlocked) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp dd8648e9-e72b-41af-ac5a-778a58f169b2)
|
||||
)
|
||||
(fp_rect (start -2 -8.5) (end 31.5 8.5) (layer "F.SilkS") (width 0.12) (fill none) (tstamp 544f39f6-64e8-4f0a-a78a-5e28b7872f5b))
|
||||
(pad "1" thru_hole roundrect (at 0 -1.27) (size 2.286 1.524) (drill 0.9) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp 6b50b86c-f9d8-4912-a87b-9d561db19997))
|
||||
(pad "2" thru_hole roundrect (at 0 1.27) (size 2.286 1.524) (drill 0.9) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp 5f68daa8-c144-4203-bee1-0e7dc9fd2d2a))
|
||||
(pad "3" thru_hole roundrect (at 27.94 -3.5) (size 2.286 1.524) (drill 0.9) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp 109eb1d6-b156-437a-a163-7bcc6259259e))
|
||||
(pad "4" thru_hole roundrect (at 27.94 0) (size 2.286 1.524) (drill 0.9) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp aae80b99-f5f7-4cee-b9d6-1e8589696882))
|
||||
(pad "5" thru_hole roundrect (at 27.94 3.5) (size 2.286 1.524) (drill 0.9) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp 39d93395-0259-4e7b-9e15-e09f030e816a))
|
||||
)
|
||||
103
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/PulseJack JB0011D01BNL.kicad_mod
Executable file
103
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/PulseJack JB0011D01BNL.kicad_mod
Executable file
@@ -0,0 +1,103 @@
|
||||
(footprint "PulseJack JB0011D01BNL" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(descr "1 Port RJ45 Magjack Connector Through Hole 10/100 Base-T, AutoMDIX, https://www.amphenol-cs.com/media/wysiwyg/files/drawing/rjmg1bd3b8k1anr.pdf")
|
||||
(tags "RJ45 Magjack")
|
||||
(attr through_hole)
|
||||
(fp_text reference "REF**" (at -4.445 5.49 180) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp e2f1695c-beea-4fcf-8b80-b8ca5ba8d340)
|
||||
)
|
||||
(fp_text value "PulseJack JB0011D01BNL" (at -4.445 -18.23 180) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp ba8f000b-59da-4929-ac44-88846ac40828)
|
||||
)
|
||||
(fp_text user "${REFERENCE}" (at -4.445 -6.37 180) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 9ca336cd-ca2e-4358-bf36-988a1e93b470)
|
||||
)
|
||||
(fp_line (start -12.42 -17.33) (end 3.53 -17.33)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 6cc8c013-9c97-410e-8b52-798376aa06f9))
|
||||
(fp_line (start -12.42 -4.89) (end -12.42 -17.33)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp dfe51a95-bf40-4283-8584-c3bd5cc9df9e))
|
||||
(fp_line (start -12.42 4.59) (end -12.42 -1.69)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 8246d8f2-1c6f-4b33-8d25-c618de02407e))
|
||||
(fp_line (start 3.53 -17.33) (end 3.53 -4.89)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp f47c6b12-f626-45aa-9068-5767b95e0936))
|
||||
(fp_line (start 3.53 -1.69) (end 3.53 4.59)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 0777e883-a211-4ec6-83de-d3a434fd515e))
|
||||
(fp_line (start 3.53 4.59) (end -12.42 4.59)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 02396337-73e6-497a-8f0c-d054d6d0c6db))
|
||||
(fp_line (start 3.73 1) (end 3.73 -1)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 0c9cfb1c-8626-45ba-b8d0-0fa1d897dde5))
|
||||
(fp_line (start -14.02 -4.04) (end -12.82 -5.24)
|
||||
(stroke (width 0.05) (type default)) (layer "F.CrtYd") (tstamp 13cdb4cc-fea5-44e3-93ef-ac453a62464a))
|
||||
(fp_line (start -14.02 -2.54) (end -14.02 -4.04)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp a85fb57b-5bbf-4280-850d-8afa2455d39a))
|
||||
(fp_line (start -12.82 -5.24) (end -12.82 -17.73)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp e2c5f1ff-8df1-4236-b76c-300e04f8790c))
|
||||
(fp_line (start -12.82 -1.34) (end -14.02 -2.54)
|
||||
(stroke (width 0.05) (type default)) (layer "F.CrtYd") (tstamp ce6674fd-2fbe-4f69-89a7-10eb73acbd10))
|
||||
(fp_line (start -12.82 4.99) (end -12.82 -1.34)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 60a05c14-e1f9-4ada-a1af-593963ac1586))
|
||||
(fp_line (start -12.82 4.99) (end 3.93 4.99)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 4fdd4f36-1a01-4604-96b0-b2181006ea98))
|
||||
(fp_line (start 3.93 -17.73) (end -12.82 -17.73)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp bfd74dac-89ff-4170-b66a-da6e02ab8a10))
|
||||
(fp_line (start 3.93 -5.24) (end 3.93 -17.73)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp a7ea8871-0814-496d-bea8-76acf87a9f1d))
|
||||
(fp_line (start 3.93 -1.34) (end 5.13 -2.54)
|
||||
(stroke (width 0.05) (type default)) (layer "F.CrtYd") (tstamp ce9b9799-5a6e-4d3c-ad71-51ecb5f3226b))
|
||||
(fp_line (start 3.93 4.99) (end 3.93 -1.34)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp a7ea8871-0814-496d-bea8-76acf87a9f1d))
|
||||
(fp_line (start 5.13 -4.04) (end 3.93 -5.24)
|
||||
(stroke (width 0.05) (type default)) (layer "F.CrtYd") (tstamp 35eb9022-e801-4ec2-b75e-575993ae22a7))
|
||||
(fp_line (start 5.13 -2.54) (end 5.13 -4.04)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 42f37172-575a-4e35-ab04-4207d00c9215))
|
||||
(fp_line (start -12.32 -17.23) (end 3.43 -17.23)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 3bcf90ed-72cf-43f6-9200-1af27dc71125))
|
||||
(fp_line (start -12.32 4.49) (end -12.32 -17.23)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 0e51847c-5550-4434-a920-3207f3b327a4))
|
||||
(fp_line (start 0 3.49) (end -1 4.49)
|
||||
(stroke (width 0.1) (type default)) (layer "F.Fab") (tstamp 2203cc90-7f47-4295-8157-870276d4dc86))
|
||||
(fp_line (start 0 3.49) (end 1 4.49)
|
||||
(stroke (width 0.1) (type default)) (layer "F.Fab") (tstamp aa2be614-88ae-4474-8f42-6dcd6743c3ee))
|
||||
(fp_line (start 3.43 -17.23) (end 3.43 4.49)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 6433be6c-4de7-4dae-a169-d00a015d196a))
|
||||
(fp_line (start 3.43 4.49) (end -12.32 4.49)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 98f93373-5da4-47b9-a4ca-c4dc9246ed79))
|
||||
(pad "" np_thru_hole circle (at -10.16 -6.35 180) (size 3.25 3.25) (drill 3.25) (layers "F&B.Cu" "*.Mask") (tstamp f48b1e8e-4538-458d-a65c-3138e85ea983))
|
||||
(pad "" np_thru_hole circle (at 1.27 -6.35 180) (size 3.25 3.25) (drill 3.25) (layers "F&B.Cu" "*.Mask") (tstamp 185b9caa-e029-4e3c-ac0d-88faa14dbe70))
|
||||
(pad "1" thru_hole rect (at 0 0 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp e7b20907-2bab-4e95-a575-a415b5c81d21))
|
||||
(pad "2" thru_hole circle (at -1.27 2.54 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp 795bd836-c6e1-4e60-8c0e-c390a64de36d))
|
||||
(pad "3" thru_hole circle (at -2.54 0 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp e8ffc943-c00a-44ac-890a-53d47631b4ca))
|
||||
(pad "4" thru_hole circle (at -3.81 2.54 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp 07a28928-313b-4940-b033-f561fb74708a))
|
||||
(pad "5" thru_hole circle (at -5.08 0 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp f45e2541-d577-4c9c-b663-888b4be2cd9d))
|
||||
(pad "6" thru_hole circle (at -6.35 2.54 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp c75da34c-c8bd-4693-b686-9e59682fd0df))
|
||||
(pad "7" thru_hole circle (at -7.62 0 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp d93d30c2-35fb-434c-a82d-d583066fc83d))
|
||||
(pad "8" thru_hole circle (at -8.89 2.54 180) (size 1.9 1.9) (drill 0.9) (layers "*.Cu" "*.Mask") (tstamp df23d44a-7a80-4775-875f-744a84f07092))
|
||||
(pad "9" thru_hole circle (at 1.8796 -11.2522 180) (size 1.89 1.89) (drill 0.89) (layers "*.Cu" "*.Mask") (tstamp 31281c12-ca20-4a5f-84f9-96702a50100e))
|
||||
(pad "10" thru_hole circle (at -0.6604 -9.7282 180) (size 1.89 1.89) (drill 0.89) (layers "*.Cu" "*.Mask") (tstamp 1481ff80-5f30-4ef2-91da-ead74ebeaa80))
|
||||
(pad "11" thru_hole circle (at -8.2296 -11.2522 180) (size 1.89 1.89) (drill 0.89) (layers "*.Cu" "*.Mask") (tstamp 9804c560-faa5-4df3-9d54-539192cf2965))
|
||||
(pad "12" thru_hole circle (at -10.7696 -9.7282 180) (size 1.89 1.89) (drill 0.89) (layers "*.Cu" "*.Mask") (tstamp f7a2d297-559e-45fa-9e90-075150e8a9fa))
|
||||
(pad "SH" thru_hole circle (at -12.319 -3.302 180) (size 2.6 2.6) (drill 1.6) (layers "*.Cu" "*.Mask") (tstamp 3a4032e9-a391-42a8-8d46-37a6a669af39))
|
||||
(pad "SH" thru_hole circle (at 3.429 -3.302 180) (size 2.6 2.6) (drill 1.6) (layers "*.Cu" "*.Mask") (tstamp 9c410289-a5f6-43a2-b6d5-e00c7525c3d4))
|
||||
(zone (net 0) (net_name "") (layers "F&B.Cu" "F.SilkS") (tstamp 8504694f-c10f-4788-9961-ef566cd97e6b) (name "No trace zone") (hatch edge 0.5)
|
||||
(connect_pads (clearance 0))
|
||||
(min_thickness 0.25) (filled_areas_thickness no)
|
||||
(keepout (tracks not_allowed) (vias not_allowed) (pads not_allowed) (copperpour allowed) (footprints allowed))
|
||||
(fill (thermal_gap 0.5) (thermal_bridge_width 0.5))
|
||||
(polygon
|
||||
(pts
|
||||
(xy 3.683 -13.97)
|
||||
(xy -12.573 -13.97)
|
||||
(xy -12.573 -17.526)
|
||||
(xy 3.683 -17.526)
|
||||
)
|
||||
)
|
||||
)
|
||||
(model "${KICAD7_3DMODEL_DIR}/Connector_RJ.3dshapes/RJ45-01-J0011D01BNL.STEP"
|
||||
(offset (xyz -4.4 6.6 0))
|
||||
(scale (xyz 1 1 1))
|
||||
(rotate (xyz -90 0 180))
|
||||
)
|
||||
)
|
||||
19
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/Step-down_converter.kicad_mod
Executable file
19
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/Step-down_converter.kicad_mod
Executable file
@@ -0,0 +1,19 @@
|
||||
(footprint "Step-down_converter" (version 20211014) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(tedit 0)
|
||||
(attr smd)
|
||||
(fp_text reference "REF**" (at 1 -2 unlocked) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 02961187-d897-402a-8be0-280efa86136e)
|
||||
)
|
||||
(fp_text value "Step-down_converter" (at 1 0 unlocked) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 86ce3e0b-05da-49e1-bbdd-4b8a82d57320)
|
||||
)
|
||||
(fp_rect (start 9.398 -6.35) (end -8.382 5.334) (layer "F.SilkS") (width 0.12) (fill none) (tstamp a74d3364-cf5e-4ce8-81ee-30303d1a2fff))
|
||||
(fp_rect (start -8.382 -6.35) (end 9.398 5.334) (layer "F.CrtYd") (width 0.12) (fill none) (tstamp 2dc45bff-1695-4e57-9525-90c2d17683f1))
|
||||
(pad "IN+" thru_hole rect (at -7 4) (size 2 2) (drill 1) (layers *.Cu *.Mask) (tstamp f9cef32a-df9e-484b-9b98-5c39bed8e59f))
|
||||
(pad "IN-" thru_hole rect (at -7 -5) (size 2 2) (drill 1) (layers *.Cu *.Mask) (tstamp b207658a-2d2d-4567-aa6a-a6939ed82d9a))
|
||||
(pad "OUT+" thru_hole rect (at 8 4) (size 2 2) (drill 1) (layers *.Cu *.Mask) (tstamp 57a92d72-08d9-4070-ae87-6de89c192f43))
|
||||
(pad "OUT-" thru_hole rect (at 8 -5) (size 2 2) (drill 1) (layers *.Cu *.Mask) (tstamp b3710e17-dffb-4214-b6d9-79b3e34fd05c))
|
||||
)
|
||||
91
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/USB_Micro-Hakan.kicad_mod
Executable file
91
Cards/EaserCAT-2000/Kicad/HakansLibrary.pretty/USB_Micro-Hakan.kicad_mod
Executable file
@@ -0,0 +1,91 @@
|
||||
(footprint "USB_Micro-Hakan" (version 20221018) (generator pcbnew)
|
||||
(layer "F.Cu")
|
||||
(descr "Micro USB AB receptable, right-angle inverted (https://www.molex.com/pdm_docs/sd/475900001_sd.pdf)")
|
||||
(tags "Micro AB USB SMD")
|
||||
(attr smd)
|
||||
(fp_text reference "REF**" (at 0 -4.8 -180) (layer "F.SilkS")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 934339ec-1cb6-463e-8be7-53de8c8333c7)
|
||||
)
|
||||
(fp_text value "USB_Micro-Hakan" (at 0 3.5) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp cbe7cf3e-519b-4cc6-bb14-9eb244b4d642)
|
||||
)
|
||||
(fp_text user "PCB Edge" (at 0 1.45) (layer "Dwgs.User")
|
||||
(effects (font (size 0.4 0.4) (thickness 0.04)))
|
||||
(tstamp bab58309-66f6-4101-abc0-1146c4c6eb53)
|
||||
)
|
||||
(fp_text user "${REFERENCE}" (at 0 -1.5) (layer "F.Fab")
|
||||
(effects (font (size 1 1) (thickness 0.15)))
|
||||
(tstamp 9a98430f-5a6a-4beb-9df6-2ff5de8ad42d)
|
||||
)
|
||||
(fp_line (start -3.87 -3.27) (end -3.87 -1.2)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 2d37630d-fc20-46e3-9f0a-37884fe92080))
|
||||
(fp_line (start -3.87 -3.27) (end -3 -3.27)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 7a091366-bda5-4ae9-b8bb-05ca09dde226))
|
||||
(fp_line (start -3.87 1.2) (end -3.87 1.45)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 0d46e52b-92f1-4829-89fc-4aaac518b86c))
|
||||
(fp_line (start 1 -3.8) (end 1.6 -3.8)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 2da27fd0-40d0-4d12-8acb-9b0c4746f591))
|
||||
(fp_line (start 1.3 -3.5) (end 1 -3.8)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp ec3cbbc1-7abb-4a2b-9614-d47a3494480c))
|
||||
(fp_line (start 1.3 -3.5) (end 1.6 -3.8)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 35601a70-353f-406d-bbd0-8caf92f19c0b))
|
||||
(fp_line (start 3 -3.27) (end 3.87 -3.27)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 40a7b295-350d-4143-baec-c6f8ff9d76d2))
|
||||
(fp_line (start 3.87 -3.27) (end 3.87 -1.2)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 74dfe2ea-e3fd-4caa-b764-c1de0b7a69ff))
|
||||
(fp_line (start 3.87 1.2) (end 3.87 1.45)
|
||||
(stroke (width 0.12) (type solid)) (layer "F.SilkS") (tstamp 8ec0b9c7-7985-473b-bcc5-ddfb4408d2c9))
|
||||
(fp_line (start -3.75 1.45) (end -2.8 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 024d267c-18aa-4abd-a1d0-c92a6e485600))
|
||||
(fp_line (start -2.8 -0.125) (end -2.8 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 401e311c-0ca8-4584-8ff2-3f4f6b51d241))
|
||||
(fp_line (start -1.95 -0.125) (end -1.95 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 73d911a7-90a3-4d1d-a029-378744021085))
|
||||
(fp_line (start -1.95 1.45) (end 1.95 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp ee5977e1-c184-40f7-a823-45eb668167aa))
|
||||
(fp_line (start 1.95 -0.125) (end 1.95 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 74b35cff-17e2-4b36-add6-6ec4112541a5))
|
||||
(fp_line (start 2.8 -0.125) (end 2.8 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 869611ae-d851-4622-abc5-aad71c6b09f1))
|
||||
(fp_line (start 2.8 1.45) (end 3.75 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 50bc56b1-3a29-4e1f-8652-d659f7d57da0))
|
||||
(fp_arc (start -2.8 -0.125) (mid -2.375 -0.55) (end -1.95 -0.125)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 7f5410bb-983e-4e57-b73a-0eb543c44190))
|
||||
(fp_arc (start 1.95 -0.125) (mid 2.375 -0.55) (end 2.8 -0.125)
|
||||
(stroke (width 0.1) (type solid)) (layer "Edge.Cuts") (tstamp 110f4d1a-d4c5-4e63-a5a9-f29f4fdc854e))
|
||||
(fp_line (start -5.18 -4.13) (end -5.18 2.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 002ef12b-00f9-48b1-a279-9f817643f514))
|
||||
(fp_line (start -5.18 -4.13) (end 5.18 -4.13)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 5e020143-41e5-42c6-808c-eb743d1d2f89))
|
||||
(fp_line (start -5.18 2.65) (end 5.18 2.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 0a5b36ae-286f-405c-9ec9-aabba86c2fd8))
|
||||
(fp_line (start 5.18 -4.13) (end 5.18 2.65)
|
||||
(stroke (width 0.05) (type solid)) (layer "F.CrtYd") (tstamp 7b6c0121-e313-40f8-9310-831434e7c888))
|
||||
(fp_line (start -3.75 -3.15) (end -3.75 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 0fb604fc-b92e-45b6-8bda-e4899a9d5c8b))
|
||||
(fp_line (start -3.75 -3.15) (end 3.75 -3.15)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp b12cf5c4-387b-4583-ac97-4f26bfd82512))
|
||||
(fp_line (start -3.75 1.45) (end 3.75 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp 736ab801-951d-47eb-856b-bbd96669fe85))
|
||||
(fp_line (start -3.75 2.15) (end 3.75 2.15)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp c70f2741-31b9-423c-a2a3-1fcfab4a62e2))
|
||||
(fp_line (start 3.75 -3.15) (end 3.75 1.45)
|
||||
(stroke (width 0.1) (type solid)) (layer "F.Fab") (tstamp a10d755e-b990-4a0f-8473-2fa6c925a77c))
|
||||
(pad "" smd rect (at -3.5 0) (size 0.3 0.85) (layers "F.Paste") (tstamp f6d16555-361c-45c0-b638-e30497582a0c))
|
||||
(pad "" smd rect (at 3.5 0) (size 0.3 0.85) (layers "F.Paste") (tstamp 098f3983-cc81-4561-b6b3-5fbeddabea75))
|
||||
(pad "1" smd rect (at 1.3 -2.675) (size 0.4 1.35) (layers "F.Cu" "F.Paste" "F.Mask") (tstamp f18640f9-bb70-4637-8b80-13ef4e4668f7))
|
||||
(pad "2" smd rect (at 0.65 -2.675) (size 0.4 1.35) (layers "F.Cu" "F.Paste" "F.Mask") (tstamp 14681c88-b094-46f2-ba05-0a108b5873e0))
|
||||
(pad "3" smd rect (at 0 -2.675) (size 0.4 1.35) (layers "F.Cu" "F.Paste" "F.Mask") (tstamp b99f8391-4192-462d-b63f-3c48dbc61c83))
|
||||
(pad "4" smd rect (at -0.65 -2.675) (size 0.4 1.35) (layers "F.Cu" "F.Paste" "F.Mask") (tstamp 80b1b826-b2d9-4a3f-a60f-983859b1fe2d))
|
||||
(pad "5" smd rect (at -1.3 -2.675) (size 0.4 1.35) (layers "F.Cu" "F.Paste" "F.Mask") (tstamp 7a5037d8-1adf-4802-9521-386cc4a58105))
|
||||
(pad "6" smd rect (at -3.7375 0) (size 0.875 1.9) (layers "F.Cu" "F.Mask") (tstamp 1e7c2782-72c9-4974-bc76-c1345656f1ec))
|
||||
(pad "6" smd rect (at 0 0) (size 2.9 1.9) (layers "F.Cu" "F.Paste" "F.Mask") (tstamp bbaf77de-f7e5-4a41-9e1b-9dddcbff5b82))
|
||||
(pad "6" smd rect (at 3.7375 0) (size 0.875 1.9) (layers "F.Cu" "F.Mask") (tstamp b23bb249-4cd3-40fc-8105-d0d7b8908f58))
|
||||
(model "${KICAD6_3DMODEL_DIR}/Connector_USB.3dshapes/USB_Micro-AB_Molex_47590-0001.wrl"
|
||||
(offset (xyz 0 0 0))
|
||||
(scale (xyz 1 1 1))
|
||||
(rotate (xyz 0 0 0))
|
||||
)
|
||||
)
|
||||
2230
Cards/EaserCAT-2000/Kicad/LAN9252.kicad_sch
Executable file
2230
Cards/EaserCAT-2000/Kicad/LAN9252.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
4830
Cards/EaserCAT-2000/Kicad/LAN9252_diverse.kicad_sch
Executable file
4830
Cards/EaserCAT-2000/Kicad/LAN9252_diverse.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
4914
Cards/EaserCAT-2000/Kicad/STM32F4.kicad_sch
Executable file
4914
Cards/EaserCAT-2000/Kicad/STM32F4.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
2187
Cards/EaserCAT-2000/Kicad/Symbols/HakansLibrary.kicad_sym
Executable file
2187
Cards/EaserCAT-2000/Kicad/Symbols/HakansLibrary.kicad_sym
Executable file
File diff suppressed because it is too large
Load Diff
321
Cards/EaserCAT-2000/Kicad/Symbols/LAN9252_PT.kicad_sym
Executable file
321
Cards/EaserCAT-2000/Kicad/Symbols/LAN9252_PT.kicad_sym
Executable file
@@ -0,0 +1,321 @@
|
||||
(kicad_symbol_lib (version 20220914) (generator kicad_symbol_editor)
|
||||
(symbol "LAN9252_PT" (pin_names (offset 1.016)) (in_bom yes) (on_board yes)
|
||||
(property "Reference" "U" (at -60.96 59.69 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||
)
|
||||
(property "Value" "LAN9252_PT" (at -29.21 -60.96 0)
|
||||
(effects (font (size 1.27 1.27)) (justify left bottom))
|
||||
)
|
||||
(property "Footprint" "LAN9252_PT:QFP50P1200X1200X120-65N" (at -5.08 6.35 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Datasheet" "" (at 0 0 0)
|
||||
(effects (font (size 1.27 1.27)) hide)
|
||||
)
|
||||
(property "MF" "Microchip" (at -1.27 -13.97 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "MAXIMUM_PACKAGE_HEIGHT" "1.2 mm" (at 0 -2.54 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Package" "TQFP-64 Microchip" (at -1.27 -11.43 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Price" "" (at 0 0 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Check_prices" "" (at 0 0 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "STANDARD" "IPC 7351B" (at -1.27 -5.08 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "PARTREV" "04-08-15" (at -1.27 -13.97 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "SnapEDA_Link" "" (at 0 0 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "MP" "LAN9252/PT" (at -2.54 3.81 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Purchase-URL" "" (at 0 0 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Description" "\nEthernet Controller 10/100 Base-FX/T/TX PHY SPI Interface 64-TQFP-EP (10x10)\n" (at -1.27 10.16 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "Availability" "" (at 0 -2.54 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(property "MANUFACTURER" "Microchip Technology" (at -1.27 -8.89 0)
|
||||
(effects (font (size 1.27 1.27)) (justify bottom) hide)
|
||||
)
|
||||
(symbol "LAN9252_PT_0_0"
|
||||
(rectangle (start -29.21 58.42) (end 60.96 -59.69)
|
||||
(stroke (width 0.254) (type default))
|
||||
(fill (type background))
|
||||
)
|
||||
(pin input line (at -34.29 -2.54 0) (length 5.08)
|
||||
(name "OSCI" (effects (font (size 1.016 1.016))))
|
||||
(number "1" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at -34.29 12.7 0) (length 5.08)
|
||||
(name "FXSDB/FXLOSB/~{FXSDENB}" (effects (font (size 1.016 1.016))))
|
||||
(number "10" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at -34.29 30.48 0) (length 5.08)
|
||||
(name "~{RST}" (effects (font (size 1.016 1.016))))
|
||||
(number "11" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -10.16 180) (length 5.08)
|
||||
(name "D2/AD2/SOF/SIO2" (effects (font (size 1.016 1.016))))
|
||||
(number "12" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -7.62 180) (length 5.08)
|
||||
(name "D1/AD1/EOF/SO/SIO1" (effects (font (size 1.016 1.016))))
|
||||
(number "13" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 59.69 180) (length 5.08)
|
||||
(name "VDDIO" (effects (font (size 1.016 1.016))))
|
||||
(number "14" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -40.64 180) (length 5.08)
|
||||
(name "D14/AD14/DIGIO8/GPI8/GPO8/MII_TXD3/~{TX_SHIFT1}" (effects (font (size 1.016 1.016))))
|
||||
(number "15" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -38.1 180) (length 5.08)
|
||||
(name "D13/AD13/DIGIO7/GPI7/GPO7/MII_TXD2/~{TX_SHIFT0}" (effects (font (size 1.016 1.016))))
|
||||
(number "16" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -5.08 180) (length 5.08)
|
||||
(name "D0/AD0/WD_STATE/SI/SIO0" (effects (font (size 1.016 1.016))))
|
||||
(number "17" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -25.4 0) (length 5.08)
|
||||
(name "SYNC1/LATCH1" (effects (font (size 1.016 1.016))))
|
||||
(number "18" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -27.94 180) (length 5.08)
|
||||
(name "D9/AD9/LATCH_IN/SCK" (effects (font (size 1.016 1.016))))
|
||||
(number "19" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin output line (at -34.29 -5.08 0) (length 5.08)
|
||||
(name "OSCO" (effects (font (size 1.016 1.016))))
|
||||
(number "2" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 60.96 180) (length 5.08)
|
||||
(name "VDDIO" (effects (font (size 1.016 1.016))))
|
||||
(number "20" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -35.56 180) (length 5.08)
|
||||
(name "D12/AD12/DIGIO6/GPI6/GPO6/MII_TXD1" (effects (font (size 1.016 1.016))))
|
||||
(number "21" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -33.02 180) (length 5.08)
|
||||
(name "D11/AD11/DIGIO5/GPI5/GPO5/MII_TXD0" (effects (font (size 1.016 1.016))))
|
||||
(number "22" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -30.48 180) (length 5.08)
|
||||
(name "D10/AD10/DIGIO4/GPI4/GPO4/MII_TXEN" (effects (font (size 1.016 1.016))))
|
||||
(number "23" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 55.88 180) (length 5.08)
|
||||
(name "VDDCR" (effects (font (size 1.016 1.016))))
|
||||
(number "24" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -35.56 0) (length 5.08)
|
||||
(name "A1/ALELO/OE_EXT/MII_CLK25" (effects (font (size 1.016 1.016))))
|
||||
(number "25" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -40.64 0) (length 5.08)
|
||||
(name "A3/DIGIO11/GPI11/GPO11/MII_RXDV" (effects (font (size 1.016 1.016))))
|
||||
(number "26" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -43.18 0) (length 5.08)
|
||||
(name "A4/DIGIO12/GPI12/GPO12/MII_RXD0" (effects (font (size 1.016 1.016))))
|
||||
(number "27" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -30.48 0) (length 5.08)
|
||||
(name "CS/DIGIO13/GPI13/GPO13/MII_RXD1" (effects (font (size 1.016 1.016))))
|
||||
(number "28" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -38.1 0) (length 5.08)
|
||||
(name "A2/ALEHI/DIGIO10/GPI10/GPO10/LINKACTLED2/~{MII_LINKPOL}" (effects (font (size 1.016 1.016))))
|
||||
(number "29" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 48.26 180) (length 5.08)
|
||||
(name "OSCVDD12" (effects (font (size 1.016 1.016))))
|
||||
(number "3" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 2.54 180) (length 5.08)
|
||||
(name "WR/ENB/DIGIO14/GPI14/GPO14/MII_RXD2" (effects (font (size 1.016 1.016))))
|
||||
(number "30" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 0 180) (length 5.08)
|
||||
(name "RD/RD_WR/DIGIO15/GPI15/GPO15/MII_RXD3" (effects (font (size 1.016 1.016))))
|
||||
(number "31" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 62.23 180) (length 5.08)
|
||||
(name "VDDIO" (effects (font (size 1.016 1.016))))
|
||||
(number "32" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -43.18 180) (length 5.08)
|
||||
(name "A0/D15/AD15/DIGIO9/GPI9/GPO9/MII_RXER" (effects (font (size 1.016 1.016))))
|
||||
(number "33" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -22.86 0) (length 5.08)
|
||||
(name "SYNC0/LATCH0" (effects (font (size 1.016 1.016))))
|
||||
(number "34" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -12.7 180) (length 5.08)
|
||||
(name "D3/AD3/WD_TRIG/SIO3" (effects (font (size 1.016 1.016))))
|
||||
(number "35" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -20.32 180) (length 5.08)
|
||||
(name "D6/AD6/DIGIO0/GPI0/GPO0/MII_RXCLK" (effects (font (size 1.016 1.016))))
|
||||
(number "36" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 63.5 180) (length 5.08)
|
||||
(name "VDDIO" (effects (font (size 1.016 1.016))))
|
||||
(number "37" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 54.61 180) (length 5.08)
|
||||
(name "VDDCR" (effects (font (size 1.016 1.016))))
|
||||
(number "38" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -22.86 180) (length 5.08)
|
||||
(name "D7/AD7/DIGIO1/GPI1/GPO1/MII_MDC" (effects (font (size 1.016 1.016))))
|
||||
(number "39" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 -55.88 180) (length 5.08)
|
||||
(name "OSCVSS" (effects (font (size 1.016 1.016))))
|
||||
(number "4" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -25.4 180) (length 5.08)
|
||||
(name "D8/AD8/DIGIO2/GPI2/GPO2/MII_MDIO" (effects (font (size 1.016 1.016))))
|
||||
(number "40" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at 66.04 -48.26 180) (length 5.08)
|
||||
(name "TESTMODE" (effects (font (size 1.016 1.016))))
|
||||
(number "41" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 5.08 0) (length 5.08)
|
||||
(name "EESDA/TMS" (effects (font (size 1.016 1.016))))
|
||||
(number "42" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin output clock (at -34.29 2.54 0) (length 5.08)
|
||||
(name "EESCL/TCK" (effects (font (size 1.016 1.016))))
|
||||
(number "43" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin output line (at 66.04 30.48 180) (length 5.08)
|
||||
(name "IRQ" (effects (font (size 1.016 1.016))))
|
||||
(number "44" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at -34.29 -17.78 0) (length 5.08)
|
||||
(name "RUNLED/~{E2PSIZE}" (effects (font (size 1.016 1.016))))
|
||||
(number "45" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at -34.29 -12.7 0) (length 5.08)
|
||||
(name "LINKACTLED1/TDI/~{CHIP_MODE1}" (effects (font (size 1.016 1.016))))
|
||||
(number "46" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 58.42 180) (length 5.08)
|
||||
(name "VDDIO" (effects (font (size 1.016 1.016))))
|
||||
(number "47" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin output line (at -34.29 -10.16 0) (length 5.08)
|
||||
(name "LINKACTLED0/TDO/~{CHIP_MODE0}" (effects (font (size 1.016 1.016))))
|
||||
(number "48" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -15.24 180) (length 5.08)
|
||||
(name "D4/AD4/DIGIO3/GPI3/GPO3/MII_LINK" (effects (font (size 1.016 1.016))))
|
||||
(number "49" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 50.8 180) (length 5.08)
|
||||
(name "VDD33" (effects (font (size 1.016 1.016))))
|
||||
(number "5" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 -17.78 180) (length 5.08)
|
||||
(name "D5/AD5/OUTVALID/SCS#" (effects (font (size 1.016 1.016))))
|
||||
(number "50" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 38.1 180) (length 5.08)
|
||||
(name "VDD33TXRX1" (effects (font (size 1.016 1.016))))
|
||||
(number "51" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 22.86 180) (length 5.08)
|
||||
(name "TXNA" (effects (font (size 1.016 1.016))))
|
||||
(number "52" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 25.4 180) (length 5.08)
|
||||
(name "TXPA" (effects (font (size 1.016 1.016))))
|
||||
(number "53" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 17.78 180) (length 5.08)
|
||||
(name "RXNA" (effects (font (size 1.016 1.016))))
|
||||
(number "54" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 20.32 180) (length 5.08)
|
||||
(name "RXPA" (effects (font (size 1.016 1.016))))
|
||||
(number "55" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 45.72 180) (length 5.08)
|
||||
(name "VDD12TX1" (effects (font (size 1.016 1.016))))
|
||||
(number "56" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin passive line (at -34.29 -48.26 0) (length 5.08)
|
||||
(name "RBIAS" (effects (font (size 1.016 1.016))))
|
||||
(number "57" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 40.64 180) (length 5.08)
|
||||
(name "VDD33BIAS" (effects (font (size 1.016 1.016))))
|
||||
(number "58" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 43.18 180) (length 5.08)
|
||||
(name "VDD12TX2" (effects (font (size 1.016 1.016))))
|
||||
(number "59" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 53.34 180) (length 5.08)
|
||||
(name "VDDCR" (effects (font (size 1.016 1.016))))
|
||||
(number "6" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 10.16 180) (length 5.08)
|
||||
(name "RXPB" (effects (font (size 1.016 1.016))))
|
||||
(number "60" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 7.62 180) (length 5.08)
|
||||
(name "RXNB" (effects (font (size 1.016 1.016))))
|
||||
(number "61" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 15.24 180) (length 5.08)
|
||||
(name "TXPB" (effects (font (size 1.016 1.016))))
|
||||
(number "62" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin bidirectional line (at 66.04 12.7 180) (length 5.08)
|
||||
(name "TXNB" (effects (font (size 1.016 1.016))))
|
||||
(number "63" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 35.56 180) (length 5.08)
|
||||
(name "VDD33TXRX2" (effects (font (size 1.016 1.016))))
|
||||
(number "64" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin power_in line (at 66.04 -53.34 180) (length 5.08)
|
||||
(name "VSS" (effects (font (size 1.016 1.016))))
|
||||
(number "65" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at -34.29 25.4 0) (length 5.08)
|
||||
(name "REG_EN" (effects (font (size 1.016 1.016))))
|
||||
(number "7" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at -34.29 17.78 0) (length 5.08)
|
||||
(name "~{FXLOSEN}" (effects (font (size 1.016 1.016))))
|
||||
(number "8" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
(pin input line (at -34.29 15.24 0) (length 5.08)
|
||||
(name "FXSDA/FXLOSA/~{FXSDENA}" (effects (font (size 1.016 1.016))))
|
||||
(number "9" (effects (font (size 1.016 1.016))))
|
||||
)
|
||||
)
|
||||
)
|
||||
)
|
||||
1928
Cards/EaserCAT-2000/Kicad/peripherals.kicad_sch
Executable file
1928
Cards/EaserCAT-2000/Kicad/peripherals.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
BIN
Cards/EaserCAT-2000/linuxcnc/Performance.ods
Executable file
BIN
Cards/EaserCAT-2000/linuxcnc/Performance.ods
Executable file
Binary file not shown.
102
Cards/EaserCAT-2000/linuxcnc/lcec-64bitfloatadded.patch
Normal file
102
Cards/EaserCAT-2000/linuxcnc/lcec-64bitfloatadded.patch
Normal file
@@ -0,0 +1,102 @@
|
||||
diff --git a/src/lcec_conf.c b/src/lcec_conf.c
|
||||
index b0e9ad1..6cc7f8a 100644
|
||||
--- a/src/lcec_conf.c
|
||||
+++ b/src/lcec_conf.c
|
||||
@@ -1267,6 +1267,11 @@ static void parsePdoEntryAttrs(LCEC_CONF_XML_INST_T *inst, int next, const char
|
||||
p->halType = HAL_FLOAT;
|
||||
continue;
|
||||
}
|
||||
+ if (strcasecmp(val, "float-double") == 0) {
|
||||
+ p->subType = lcecPdoEntTypeFloatDouble;
|
||||
+ p->halType = HAL_FLOAT;
|
||||
+ continue;
|
||||
+ }
|
||||
fprintf(stderr, "%s: ERROR: Invalid pdoEntry halType %s\n", modname, val);
|
||||
XML_StopParser(inst->parser, 0);
|
||||
return;
|
||||
@@ -1410,6 +1415,11 @@ static void parseComplexEntryAttrs(LCEC_CONF_XML_INST_T *inst, int next, const c
|
||||
p->halType = HAL_FLOAT;
|
||||
continue;
|
||||
}
|
||||
+ if (strcasecmp(val, "float-double") == 0) {
|
||||
+ p->subType = lcecPdoEntTypeFloatDouble;
|
||||
+ p->halType = HAL_FLOAT;
|
||||
+ continue;
|
||||
+ }
|
||||
fprintf(stderr, "%s: ERROR: Invalid complexEntry halType %s\n", modname, val);
|
||||
XML_StopParser(inst->parser, 0);
|
||||
return;
|
||||
diff --git a/src/lcec_conf.h b/src/lcec_conf.h
|
||||
index 5d9943c..261c965 100644
|
||||
--- a/src/lcec_conf.h
|
||||
+++ b/src/lcec_conf.h
|
||||
@@ -55,6 +55,7 @@ typedef enum {
|
||||
lcecPdoEntTypeSimple,
|
||||
lcecPdoEntTypeFloatSigned,
|
||||
lcecPdoEntTypeFloatUnsigned,
|
||||
+ lcecPdoEntTypeFloatDouble,
|
||||
lcecPdoEntTypeComplex,
|
||||
lcecPdoEntTypeFloatIeee
|
||||
} LCEC_PDOENT_TYPE_T;
|
||||
diff --git a/src/lcec_generic.c b/src/lcec_generic.c
|
||||
index dfddf73..41a13a9 100644
|
||||
--- a/src/lcec_generic.c
|
||||
+++ b/src/lcec_generic.c
|
||||
@@ -26,6 +26,7 @@ hal_s32_t lcec_generic_read_s32(uint8_t *pd, lcec_generic_pin_t *hal_data);
|
||||
hal_u32_t lcec_generic_read_u32(uint8_t *pd, lcec_generic_pin_t *hal_data);
|
||||
void lcec_generic_write_s32(uint8_t *pd, lcec_generic_pin_t *hal_data, hal_s32_t sval);
|
||||
void lcec_generic_write_u32(uint8_t *pd, lcec_generic_pin_t *hal_data, hal_u32_t uval);
|
||||
+void lcec_generic_write_f64(uint8_t *pd, lcec_generic_pin_t *hal_data, hal_float_t fval);
|
||||
|
||||
int lcec_generic_init(int comp_id, struct lcec_slave *slave, ec_pdo_entry_reg_t *pdo_entry_regs) {
|
||||
lcec_master_t *master = slave->master;
|
||||
@@ -78,7 +79,7 @@ int lcec_generic_init(int comp_id, struct lcec_slave *slave, ec_pdo_entry_reg_t
|
||||
|
||||
case HAL_FLOAT:
|
||||
// check data size
|
||||
- if (hal_data->bitLength > 32) {
|
||||
+ if (hal_data->bitLength > 64) {
|
||||
rtapi_print_msg(RTAPI_MSG_WARN, LCEC_MSG_PFX "unable to export pin %s.%s.%s.%s: invalid process data bitlen!\n", LCEC_MODULE_NAME, master->name, slave->name, hal_data->name);
|
||||
continue;
|
||||
}
|
||||
@@ -133,6 +134,8 @@ void lcec_generic_read(struct lcec_slave *slave, long period) {
|
||||
fval = lcec_generic_read_u32(pd, hal_data);
|
||||
} else if(hal_data->subType == lcecPdoEntTypeFloatIeee){
|
||||
fval = EC_READ_REAL(&pd[hal_data->pdo_os]);
|
||||
+ } else if(hal_data->subType == lcecPdoEntTypeFloatDouble){
|
||||
+ fval = EC_READ_LREAL(&pd[hal_data->pdo_os]);
|
||||
} else {
|
||||
fval = lcec_generic_read_s32(pd, hal_data);
|
||||
}
|
||||
@@ -185,6 +188,8 @@ void lcec_generic_write(struct lcec_slave *slave, long period) {
|
||||
|
||||
if (hal_data->subType == lcecPdoEntTypeFloatUnsigned) {
|
||||
lcec_generic_write_u32(pd, hal_data, (hal_u32_t) fval);
|
||||
+ } else if (hal_data->subType == lcecPdoEntTypeFloatDouble) {
|
||||
+ lcec_generic_write_f64(pd, hal_data, fval);
|
||||
} else {
|
||||
lcec_generic_write_s32(pd, hal_data, (hal_s32_t) fval);
|
||||
}
|
||||
@@ -300,3 +305,22 @@ void lcec_generic_write_u32(uint8_t *pd, lcec_generic_pin_t *hal_data, hal_u32_t
|
||||
}
|
||||
}
|
||||
|
||||
+void lcec_generic_write_f64(uint8_t *pd, lcec_generic_pin_t *hal_data, hal_float_t fval) {
|
||||
+ int i, offset;
|
||||
+
|
||||
+ if (hal_data->pdo_bp == 0 && hal_data->bitOffset == 0) {
|
||||
+ EC_WRITE_LREAL(&pd[hal_data->pdo_os], fval);
|
||||
+ return;
|
||||
+ }
|
||||
+ union {
|
||||
+ double d;
|
||||
+ uint64_t u;
|
||||
+ } v;
|
||||
+ v.d = fval; // Make an equivalent long int for bit operations (don't work on doubles)
|
||||
+ offset = ((hal_data->pdo_os << 3) | (hal_data->pdo_bp & 0x07)) + hal_data->bitOffset;
|
||||
+ for (i=0; i < hal_data->bitLength; i++, offset++) {
|
||||
+ EC_WRITE_BIT(&pd[offset >> 3], offset & 0x07,v.u & 1);
|
||||
+ v.u >>= 1;
|
||||
+ }
|
||||
+}
|
||||
+
|
||||
21
Cards/EaserCAT-2000/linuxcnc/metalmusings_encoder.comp
Normal file
21
Cards/EaserCAT-2000/linuxcnc/metalmusings_encoder.comp
Normal file
@@ -0,0 +1,21 @@
|
||||
component metalmusings_encoder;
|
||||
pin io bit index-c-enable;
|
||||
pin in u32 index-status;
|
||||
pin out u32 index-latch-enable;
|
||||
|
||||
function _;
|
||||
license "GPL";
|
||||
;;
|
||||
|
||||
//main function
|
||||
FUNCTION(_) {
|
||||
index_latch_enable = index_c_enable;
|
||||
if (index_latch_enable) {
|
||||
if (index_status) {
|
||||
index_c_enable = 0;
|
||||
}
|
||||
// else wait for index-status
|
||||
} else {
|
||||
index_c_enable = index_status;
|
||||
}
|
||||
}
|
||||
1
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/.gitignore
vendored
Executable file
1
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/.gitignore
vendored
Executable file
@@ -0,0 +1 @@
|
||||
*~
|
||||
3057
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/LatheMacro.svg
Executable file
3057
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/LatheMacro.svg
Executable file
File diff suppressed because one or more lines are too long
|
After Width: | Height: | Size: 4.8 MiB |
72
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/README
Executable file
72
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/README
Executable file
@@ -0,0 +1,72 @@
|
||||
This folder contains a number of simulated lathe configs.
|
||||
|
||||
the "lathemacro" config offers a number of simple macros to perform
|
||||
the most common lathe operations.
|
||||
|
||||
The GUI that controls the macros can be viewed by clicking the "Cycles"
|
||||
tab top left of the graphical preview window.
|
||||
|
||||
There are two load-time options to control the tab behaviour:
|
||||
1) norun will hide the action button, use this if you want to use only
|
||||
a physical button (connected to gladevcp.cycle-start) to start the macros
|
||||
(Strongly recommended, especially with Touchy)
|
||||
2) notouch will allow keyboard editing of the spinboxes. Otherwise the
|
||||
custom numeric keyboard will be shown.
|
||||
|
||||
An example loadrt line, as used here in the Gmoccapy demo is:
|
||||
|
||||
[DISPLAY]
|
||||
EMBED_TAB_COMMAND = halcmd loadusr -Wn gladevcp gladevcp -c gladevcp -U notouch=1 -U norun=0 -u lathehandler.py -x {XID} lathemacro.ui
|
||||
|
||||
The window will resize slowly if you grab the corner and move the mouse
|
||||
inside the window. It's not as bad as it was, but still needs work.
|
||||
You may need to click the unmaximise button in the toolbar to get a
|
||||
window border to be able to use the resize handles.
|
||||
|
||||
Notes on the keyboard:
|
||||
As well as the obvious functions and unit conversions, it can be used to
|
||||
enter fractions. For example if you type 1.1/2 it will automatically
|
||||
update to display 1.5000 and 16.17/64 will show 16.2656.
|
||||
This can be used in a limited way to halve the onscreen value eg for
|
||||
entering radius instead of diameter.
|
||||
However it only works for whole numbers: 100/2 will become 50 but
|
||||
3.14149/2 is interpreted as 3 and 14 thousand halves so won't work.
|
||||
|
||||
Notes on adding your own cycles:
|
||||
Create a new G-code subroutine in the same format as the existing ones.
|
||||
In Glade add a new tab to the 'tabs1' notebook and give it a name matching
|
||||
the new cycle.
|
||||
Edit the action button (inside an eventbox) to call the new G-code sub.
|
||||
Rename the action button to match the tab name and append '.action' eg
|
||||
MyCycle.action
|
||||
|
||||
Create new artwork. I used Fusion360, the models are here:
|
||||
https://a360.co/3uFPZNv
|
||||
and the drawings are here:
|
||||
https://a360.co/3uFPZNv
|
||||
Esport the drawing page as PDF and import into the lathemacro.svg file in
|
||||
Inkscape. You will need to resize. Add your own arrows and annotations.
|
||||
|
||||
Save the new layer in a layer named "layerN" (lower case) where N is the
|
||||
tab number, starting at zero. You will need to invoke the XML editor for
|
||||
this (Shift-Cmd-X on Mac)
|
||||
|
||||
The entry boxes are positioned relative to a 1500 x 1000 image; the
|
||||
original size of the SVG. So you can hover your mouse over the image in
|
||||
Inkscape to determine the coordinates.
|
||||
In the in the case of on-drawing controls the coordinates are entered as
|
||||
an XML comment in the Tooltip for the control in x,y format (The surface speed,
|
||||
tool and coolant do not need this, they are in a fixed table)
|
||||
|
||||
An example:
|
||||
|
||||
<!--300,711->Peck distance
|
||||
|
||||
Make sure the comment has "use markup" selected for the tooltip.
|
||||
Also ensure that the control has the "show_keyb" function allocated for
|
||||
the Widget->button_press event. If you copy-paste a tab and copy-paste
|
||||
extra controls this should be automatic.
|
||||
_All_ your new spinboxes will need their own new Adjustment, or they will
|
||||
change value when you alter the original spinbox that they are a copy of.
|
||||
|
||||
|
||||
Binary file not shown.
32
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/autosave.halscope
Executable file
32
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/autosave.halscope
Executable file
@@ -0,0 +1,32 @@
|
||||
THREAD servo-thread
|
||||
MAXCHAN 8
|
||||
HMULT 1
|
||||
HZOOM 5
|
||||
HPOS 6,169492e-01
|
||||
CHAN 1
|
||||
PIN lcec.0.0.commanded-position
|
||||
VSCALE -4
|
||||
VPOS 0,550725
|
||||
VOFF 3,580000e+01
|
||||
CHAN 2
|
||||
PIN lcec.0.0.DiffT
|
||||
VSCALE 8
|
||||
VPOS 0,382609
|
||||
VOFF 3,588000e+05
|
||||
CHAN 4
|
||||
PIN lcec.0.0.index-byte
|
||||
VSCALE 5
|
||||
VPOS 0,547826
|
||||
VOFF 2,550000e+03
|
||||
CHAN 5
|
||||
PIN lcec.0.0.index-status
|
||||
VSCALE 5
|
||||
VPOS 0,546377
|
||||
VOFF 1,400000e+04
|
||||
CHAN 3
|
||||
PIN lcec.0.0.actual-position
|
||||
VSCALE -4
|
||||
VPOS 0,549342
|
||||
VOFF 3,580000e+01
|
||||
TMODE 0
|
||||
RMODE 0
|
||||
64
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/boring.ngc
Executable file
64
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/boring.ngc
Executable file
@@ -0,0 +1,64 @@
|
||||
;boring
|
||||
|
||||
O<boring> sub
|
||||
|
||||
G8 ; Radius mode (easier maths)
|
||||
G18 ; XZ Plane
|
||||
G21 ; Metric Units
|
||||
G90 ; Absolute Distance
|
||||
G91.1 ; but not for arcs
|
||||
|
||||
M6 T#8 G43
|
||||
|
||||
#1 = [#1 / 2] ; because of radius mode
|
||||
|
||||
#14 = [#<_x>] (starting X)
|
||||
#13 = #<_z> (starting Z)
|
||||
|
||||
#20 = [#6 * SIN[#7]]
|
||||
#21 = [-#6 * COS[#7]]
|
||||
#22 = [#6 / COS[#7]]
|
||||
#23 = [#5 + #6 - #20]
|
||||
#24 = [[#23 - #13] * TAN[#7]]
|
||||
|
||||
|
||||
G96 D2500 S#2 ; Constant Surface Speed Mode
|
||||
m3 ;Start Spindle
|
||||
g95 F#4 ; Feed-Per-Rev Mode
|
||||
|
||||
O90 IF [#9 GT 0.5]
|
||||
M8
|
||||
O90 ENDIF
|
||||
|
||||
g4p1 ; Wait to reach speed
|
||||
|
||||
(debug, Turning finish dia #1 start dia #14 start length #13 finish length #5 coolant #9)
|
||||
O100 WHILE [#14 LT [#1 - #3]]
|
||||
g0 X #14
|
||||
#14=[#14 + #3]
|
||||
G1 X #14
|
||||
G1 Z #23 X[#14 + #24]
|
||||
O101 IF [#6 GT 0]
|
||||
G3 Z#5 X[#14 + #24 + #21] I#21 K#20
|
||||
G1 X[#14 + #24 + #21 - #3]
|
||||
O101 ELSE
|
||||
G1 X[#14 + #24 - [#3 * 1.5]]
|
||||
O101 ENDIF
|
||||
G0 Z[#13]
|
||||
O100 ENDWHILE
|
||||
|
||||
G0 x#1
|
||||
G1 Z #23 X[#1 + #24]
|
||||
O102 IF [#6 GT 0]
|
||||
G3 Z#5 X[#1 + #24 + #21] I#21 K#20
|
||||
G1 X[#1 + #24 + #21 - #3]
|
||||
O102 ELSE
|
||||
G1 X[#1 + #24 - #3]
|
||||
O102 ENDIF
|
||||
G0 Z #13
|
||||
G0 X #1 ; For touch-off
|
||||
M5 M9
|
||||
G7
|
||||
O<boring> endsub
|
||||
|
||||
M2
|
||||
77
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/chamfer.ngc
Executable file
77
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/chamfer.ngc
Executable file
@@ -0,0 +1,77 @@
|
||||
;chamfer
|
||||
|
||||
O<chamfer> sub
|
||||
|
||||
G8 ; Lathe radius Mode
|
||||
G18 ; XZ Plane
|
||||
G21 ; Metric Units
|
||||
G90 ; Absolute Distance
|
||||
|
||||
|
||||
M6 T#6 G43
|
||||
|
||||
#1 = [#1 / 2] ; because of radius mode
|
||||
|
||||
#14 = [#<_x>] (starting X)
|
||||
#13 = [#<_z>] (starting Z)
|
||||
|
||||
G96 D1500 S#2 ; Constant Surface Speed Mode
|
||||
M3
|
||||
g95 F0.1 ; Feed-Per-Rev Mode
|
||||
|
||||
O90 IF [#12 GT 0.5]
|
||||
M8
|
||||
O90 ENDIF
|
||||
|
||||
#20 = 0
|
||||
O101 if [#9 GT 0.5] ; front outside
|
||||
o100 while [[#20 + #3] lt #8]
|
||||
#20 = [#20 + #3]
|
||||
g0 x[#1 - #20] z#13
|
||||
g1 z#5
|
||||
g1 x#1 z[#5 - #20]
|
||||
g1 x #14
|
||||
g0 z#13
|
||||
o100 endwhile
|
||||
g0 x#14 z#13
|
||||
g0 x[#1 - #8]
|
||||
g1 z#5
|
||||
g1 x#1 z[#5 - #8]
|
||||
g1 x #14
|
||||
g0 z#13
|
||||
O101 elseif [#10 GT 0.5] ; front inside
|
||||
o102 while [[#20 + #3] lt #8]
|
||||
#20 = [#20 + #3]
|
||||
g0 x[#1 + #20] z#13
|
||||
g1 z#5
|
||||
g1 x#1 z[#5 - #20]
|
||||
g1 x #14
|
||||
g0 z#13
|
||||
o102 endwhile
|
||||
g0 x#14 z#13
|
||||
g0 x[#1 + #8]
|
||||
g1 z#5
|
||||
g1 x#1 z[#5 - #8]
|
||||
g1 x #14
|
||||
g0 z#13
|
||||
O101 elseif [#11 GT 0.5] ; back outside
|
||||
o103 while [[#20 + #3] lt #8]
|
||||
#20 = [#20 + #3]
|
||||
g0 x[#1 - #20] z#13
|
||||
g1 z#5
|
||||
g1 x#1 z[#5 + #20]
|
||||
g1 x #14
|
||||
g0 z#13
|
||||
o103 endwhile
|
||||
g0 x#14 z#13
|
||||
g0 x[#1 - #8]
|
||||
g1 z#5
|
||||
g1 x#1 z[#5 + #8]
|
||||
g1 x #14
|
||||
g0 z#13
|
||||
O101 endif
|
||||
M5 M9
|
||||
G7
|
||||
O<chamfer> endsub
|
||||
m2
|
||||
%
|
||||
35
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/core_sim_lathe.hal
Executable file
35
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/core_sim_lathe.hal
Executable file
@@ -0,0 +1,35 @@
|
||||
# core HAL config file for simulation
|
||||
|
||||
# first load all the RT modules that will be needed
|
||||
# kinematics
|
||||
loadrt [KINS]KINEMATICS
|
||||
# motion controller, get name and thread periods from ini file
|
||||
loadrt [EMCMOT]EMCMOT base_period_nsec=[EMCMOT]BASE_PERIOD servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
|
||||
loadusr -W lcec_conf ethercat-conf.xml
|
||||
loadrt lcec
|
||||
addf lcec.read-all servo-thread
|
||||
# add motion controller functions to servo thread
|
||||
addf motion-command-handler servo-thread
|
||||
addf motion-controller servo-thread
|
||||
|
||||
# create HAL signals for position commands from motion module
|
||||
# loop position commands back to motion module feedback
|
||||
net Xpos joint.0.motor-pos-cmd => joint.0.motor-pos-fb
|
||||
net Zpos joint.1.motor-pos-cmd => joint.1.motor-pos-fb
|
||||
net Xpos lcec.0.0.commanded-position
|
||||
net myXvel lcec.0.0.commanded-velocity joint.0.vel-cmd
|
||||
|
||||
# estop loopback
|
||||
net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in
|
||||
|
||||
# create signals for tool loading loopback
|
||||
net tool-prep-loop iocontrol.0.tool-prepare iocontrol.0.tool-prepared
|
||||
net tool-change-loop iocontrol.0.tool-change iocontrol.0.tool-changed
|
||||
|
||||
net spindle-fwd spindle.0.forward
|
||||
net spindle-rev spindle.0.reverse
|
||||
#net spindle-speed spindle.0.speed-out
|
||||
|
||||
net lube iocontrol.0.lube
|
||||
net flood iocontrol.0.coolant-flood
|
||||
net mist iocontrol.0.coolant-mist
|
||||
59
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/core_sim_lathe_C.hal
Executable file
59
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/core_sim_lathe_C.hal
Executable file
@@ -0,0 +1,59 @@
|
||||
# core HAL config file for simulation
|
||||
|
||||
# first load all the RT modules that will be needed
|
||||
# kinematics
|
||||
loadrt [KINS]KINEMATICS
|
||||
# motion controller, get name and thread periods from ini file
|
||||
loadrt [EMCMOT]EMCMOT base_period_nsec=[EMCMOT]BASE_PERIOD servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
|
||||
# load 6 differentiators (for velocity and accel signals
|
||||
loadrt ddt names=ddt_x,ddt_xv,ddt_y,ddt_yv,ddt_z,ddt_zv
|
||||
# load additional blocks
|
||||
loadrt hypot names=vel_xy,vel_xyz
|
||||
|
||||
# add motion controller functions to servo thread
|
||||
addf motion-command-handler servo-thread
|
||||
addf motion-controller servo-thread
|
||||
# link the differentiator functions into the code
|
||||
addf ddt_x servo-thread
|
||||
addf ddt_xv servo-thread
|
||||
addf ddt_y servo-thread
|
||||
addf ddt_yv servo-thread
|
||||
addf ddt_z servo-thread
|
||||
addf ddt_zv servo-thread
|
||||
addf vel_xy servo-thread
|
||||
addf vel_xyz servo-thread
|
||||
|
||||
# create HAL signals for position commands from motion module
|
||||
# loop position commands back to motion module feedback
|
||||
net Xpos joint.0.motor-pos-cmd => joint.0.motor-pos-fb ddt_x.in
|
||||
net Zpos joint.1.motor-pos-cmd => joint.1.motor-pos-fb ddt_z.in
|
||||
net Cpos joint.2.motor-pos-cmd => joint.2.motor-pos-fb
|
||||
|
||||
|
||||
# send the position commands thru differentiators to
|
||||
# generate velocity and accel signals
|
||||
net Xvel ddt_x.out => ddt_xv.in vel_xy.in0
|
||||
net Xacc <= ddt_xv.out
|
||||
net Yvel ddt_y.out => ddt_yv.in vel_xy.in1
|
||||
net Yacc <= ddt_yv.out
|
||||
net Zvel ddt_z.out => ddt_zv.in vel_xyz.in0
|
||||
net Zacc <= ddt_zv.out
|
||||
|
||||
# Cartesian 2- and 3-axis velocities
|
||||
net XYvel vel_xy.out => vel_xyz.in1
|
||||
net XYZvel <= vel_xyz.out
|
||||
|
||||
# estop loopback
|
||||
net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in
|
||||
|
||||
# create signals for tool loading loopback
|
||||
net tool-prep-loop iocontrol.0.tool-prepare iocontrol.0.tool-prepared
|
||||
net tool-change-loop iocontrol.0.tool-change iocontrol.0.tool-changed
|
||||
|
||||
net spindle-fwd spindle.0.forward
|
||||
net spindle-rev spindle.0.reverse
|
||||
#net spindle-speed spindle.0.speed-out
|
||||
|
||||
net lube iocontrol.0.lube
|
||||
net flood iocontrol.0.coolant-flood
|
||||
net mist iocontrol.0.coolant-mist
|
||||
@@ -0,0 +1,59 @@
|
||||
# core HAL config file for simulation
|
||||
|
||||
# first load all the RT modules that will be needed
|
||||
# kinematics
|
||||
loadrt [KINS]KINEMATICS
|
||||
# motion controller, get name and thread periods from ini file
|
||||
loadrt [EMCMOT]EMCMOT base_period_nsec=[EMCMOT]BASE_PERIOD servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
|
||||
# load 6 differentiators (for velocity and accel signals
|
||||
loadrt ddt names=ddt_x,ddt_xv,ddt_y,ddt_yv,ddt_z,ddt_zv
|
||||
# load additional blocks
|
||||
loadrt hypot names=vel_xy,vel_xyz
|
||||
|
||||
# add motion controller functions to servo thread
|
||||
addf motion-command-handler servo-thread
|
||||
addf motion-controller servo-thread
|
||||
# link the differentiator functions into the code
|
||||
addf ddt_x servo-thread
|
||||
addf ddt_xv servo-thread
|
||||
addf ddt_y servo-thread
|
||||
addf ddt_yv servo-thread
|
||||
addf ddt_z servo-thread
|
||||
addf ddt_zv servo-thread
|
||||
addf vel_xy servo-thread
|
||||
addf vel_xyz servo-thread
|
||||
|
||||
# create HAL signals for position commands from motion module
|
||||
# loop position commands back to motion module feedback
|
||||
net Xpos joint.0.motor-pos-cmd => joint.0.motor-pos-fb ddt_x.in
|
||||
net Zpos joint.1.motor-pos-cmd => joint.1.motor-pos-fb ddt_z.in
|
||||
net Cpos joint.2.motor-pos-cmd => joint.2.motor-pos-fb
|
||||
net Wpos joint.3.motor-pos-cmd => joint.3.motor-pos-fb
|
||||
|
||||
# send the position commands thru differentiators to
|
||||
# generate velocity and accel signals
|
||||
net Xvel ddt_x.out => ddt_xv.in vel_xy.in0
|
||||
net Xacc <= ddt_xv.out
|
||||
net Yvel ddt_y.out => ddt_yv.in vel_xy.in1
|
||||
net Yacc <= ddt_yv.out
|
||||
net Zvel ddt_z.out => ddt_zv.in vel_xyz.in0
|
||||
net Zacc <= ddt_zv.out
|
||||
|
||||
# Cartesian 2- and 3-axis velocities
|
||||
net XYvel vel_xy.out => vel_xyz.in1
|
||||
net XYZvel <= vel_xyz.out
|
||||
|
||||
# estop loopback
|
||||
net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in
|
||||
|
||||
# create signals for tool loading loopback
|
||||
net tool-prep-loop iocontrol.0.tool-prepare iocontrol.0.tool-prepared
|
||||
net tool-change-loop iocontrol.0.tool-change iocontrol.0.tool-changed
|
||||
|
||||
net spindle-fwd spindle.0.forward
|
||||
net spindle-rev spindle.0.reverse
|
||||
#net spindle-speed spindle.0.speed-out
|
||||
|
||||
net lube iocontrol.0.lube
|
||||
net flood iocontrol.0.coolant-flood
|
||||
net mist iocontrol.0.coolant-mist
|
||||
51
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/custom.hal
Executable file
51
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/custom.hal
Executable file
@@ -0,0 +1,51 @@
|
||||
# Include your custom HAL commands here
|
||||
|
||||
# Load the Huanyang VFD user component
|
||||
loadusr -Wn spindle-vfd hy_vfd -n spindle-vfd -d /dev/hy_vfd -r 19200 -p none -s 1 -b 8
|
||||
|
||||
# motion.spindle-speed-in needs rev per second
|
||||
loadrt scale names=scale.0,scale.1,scale.2
|
||||
# scale.0 gearbox via M101-M106, M101 being lowest gear.
|
||||
# scale.1 Inverted gear ratio
|
||||
# scale.2 motion.spindle-speed.in in rev/sec
|
||||
loadrt limit2 names=spindlemax
|
||||
loadrt mult2 names=mult2.1
|
||||
addf scale.0 servo-thread
|
||||
addf scale.1 servo-thread
|
||||
addf scale.2 servo-thread
|
||||
addf mult2.1 servo-thread
|
||||
addf spindlemax servo-thread
|
||||
setp scale.0.gain 0.8846 # Start with fourth gear
|
||||
setp scale.1.gain 1.13045
|
||||
setp scale.2.gain 0.0166666667
|
||||
setp mult2.1.in1 25.0
|
||||
unlinkp spindle.0.forward
|
||||
unlinkp spindle.0.reverse
|
||||
unlinkp spindle.0.on
|
||||
#unlinkp motion.spindle-at-speed
|
||||
net spindle-fwd spindle.0.forward => spindle-vfd.spindle-forward
|
||||
net spindle-reverse spindle.0.reverse => spindle-vfd.spindle-reverse
|
||||
net spindle-on spindle.0.on => spindle-vfd.spindle-on
|
||||
net spindle-at-speed <= spindle-vfd.spindle-at-speed
|
||||
#net spindle-enable => spindle-vfd.enable
|
||||
setp spindle-vfd.enable 1
|
||||
|
||||
# Prepare max limit rpm for spindle
|
||||
net spindle-max-freq spindle-vfd.max-freq => mult2.1.in0
|
||||
net spindle-max-rpm mult2.1.out => spindlemax.max # Max limit for motor rpm, like 67*25 = 1675
|
||||
|
||||
# Give speed to vfd, limited to max possible
|
||||
unlinkp spindle.0.speed-out-abs
|
||||
net spindle-speed-scale spindle.0.speed-out-abs => scale.1.in # Spindle rpm => Motor rpm
|
||||
net spindle-speed-cmd-unlimited scale.1.out => spindlemax.in # Limit spindle rpm
|
||||
net spindle-speed-cmd-limited spindlemax.out => spindle-vfd.speed-command # Feed to vfd
|
||||
|
||||
# Convert actual feed from rpm to rps, consider gear in use.
|
||||
unlinkp spindle.0.speed-in
|
||||
net spindle-speed-scale2 spindle-vfd.spindle-speed-fb => scale.2.in # Motor rpm => Motor rps
|
||||
net spindle-speed-gears scale.2.out => scale.0.in # Motor rps => spindle rps
|
||||
net spindle-speed-in scale.0.out => spindle.0.speed-in
|
||||
|
||||
# Gamepad
|
||||
loadusr -W hal_input -KRAL F310
|
||||
# Resten är i custom_postgui.hal
|
||||
74
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/custom_postgui.hal
Executable file
74
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/custom_postgui.hal
Executable file
@@ -0,0 +1,74 @@
|
||||
# Include your custom_postgui HAL commands here
|
||||
# This file will not be overwritten when you run PNCconf again
|
||||
|
||||
loadrt or2 count=2
|
||||
loadrt mux4 count=1
|
||||
loadrt and2 count=4
|
||||
loadrt oneshot count=1
|
||||
|
||||
addf or2.0 servo-thread
|
||||
addf or2.1 servo-thread
|
||||
addf mux4.0 servo-thread
|
||||
addf and2.0 servo-thread
|
||||
addf and2.1 servo-thread
|
||||
addf and2.2 servo-thread
|
||||
addf and2.3 servo-thread
|
||||
addf oneshot.0 servo-thread
|
||||
|
||||
setp mux4.0.in0 0
|
||||
setp mux4.0.in1 25
|
||||
setp mux4.0.in2 50
|
||||
setp mux4.0.in3 1000
|
||||
|
||||
net remote-speed-slow or2.0.in0 <= input.0.btn-x
|
||||
net remote-speed-medium or2.1.in0 <= input.0.btn-a
|
||||
net remote-speed-fast or2.0.in1 <= input.0.btn-b
|
||||
net remote-speed-fast or2.1.in1 <= input.0.btn-b
|
||||
|
||||
net joy-speed-1 mux4.0.sel0 <= or2.0.out
|
||||
net joy-speed-2 mux4.0.sel1 <= or2.1.out
|
||||
net jog-speed <= mux4.0.out
|
||||
|
||||
net jog-x-analog <= input.0.abs-y-position
|
||||
net jog-z-analog <= input.0.abs-x-position
|
||||
|
||||
# Spindle start+manual and stop
|
||||
|
||||
net manual-mode-spindle-lock and2.3.in0 halui.mode.manual <= input.0.btn-mode
|
||||
net spindle-safe-start and2.3.in1 <= input.0.btn-tr
|
||||
net spindle-manual-cw <= and2.3.out
|
||||
net spindle-manual-stop <= input.0.btn-tl
|
||||
|
||||
# E-stop
|
||||
|
||||
net estop halui.estop.activate <= input.0.btn-y
|
||||
|
||||
# net manual-mode halui.mode.manual <= input.0.btn-mode
|
||||
|
||||
# Start/pause/resume stop
|
||||
|
||||
setp oneshot.0.width 0.0011
|
||||
setp oneshot.0.retriggerable 0
|
||||
setp oneshot.0.rising 1
|
||||
setp oneshot.0.falling 0
|
||||
|
||||
net program-is-idle halui.program.is-idle => and2.0.in0
|
||||
net program-is-running halui.program.is-running => and2.1.in0
|
||||
net program-is-paused halui.program.is-paused => and2.2.in0
|
||||
net button-edge-trig input.0.btn-start => oneshot.0.in
|
||||
net button-start oneshot.0.out => and2.0.in1 and2.1.in1 and2.2.in1
|
||||
|
||||
net program-start and2.0.out => halui.program.run halui.mode.auto
|
||||
net program-pause and2.1.out => halui.program.pause
|
||||
net program-resume and2.2.out => halui.program.resume
|
||||
net program-stop input.0.btn-select => halui.program.stop
|
||||
|
||||
net spindle-at-speed gmoccapy.spindle_at_speed_led
|
||||
net spindle-vel-fb-rpm => gmoccapy.spindle_feedback_bar
|
||||
|
||||
net tool-change gmoccapy.toolchange-change <= iocontrol.0.tool-change
|
||||
net tool-changed gmoccapy.toolchange-changed <= iocontrol.0.tool-changed
|
||||
net tool-prep-number gmoccapy.toolchange-number <= iocontrol.0.tool-prep-number
|
||||
net tool-prep-loop iocontrol.0.tool-prepare <= iocontrol.0.tool-prepared
|
||||
net tooloffset-x gmoccapy.tooloffset-x <= motion.tooloffset.x
|
||||
net tooloffset-z gmoccapy.tooloffset-z <= motion.tooloffset.z
|
||||
49
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/drilling.ngc
Executable file
49
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/drilling.ngc
Executable file
@@ -0,0 +1,49 @@
|
||||
;drilling
|
||||
|
||||
; Use T = 0 for tailstock drilling, then this just sets speed
|
||||
|
||||
O<drilling> SUB
|
||||
|
||||
G18 ; XZ Plane
|
||||
G21 ; Metric Units
|
||||
G90 ; Absolute Distance
|
||||
G91.1 ; but not for arcs
|
||||
|
||||
#10 = [#2 * 1000 / [ #1 * 3.141592]]
|
||||
(debug, #10)
|
||||
O90 IF [#7 GT 0.5]
|
||||
M8
|
||||
O90 ENDIF
|
||||
|
||||
O100 IF [#6 LT 0.5]
|
||||
G97 M3 S#10
|
||||
O<drilling> RETURN
|
||||
O100 ENDIF
|
||||
|
||||
M6 T#6 G43
|
||||
G0 X0
|
||||
|
||||
O83 IF [#5 GT 0] ; Pecking
|
||||
G17
|
||||
G95 F#3 ; Feed-Per-Rev Mode
|
||||
G97 M3 S#10
|
||||
G98
|
||||
G83 R#<_z> Q#5 Z#4
|
||||
M5 M9 G18
|
||||
O<drilling> RETURN
|
||||
O83 ENDIF
|
||||
|
||||
O82 IF [1]; not pecking
|
||||
G17
|
||||
G95 F#3 ; Feed-Per-Rev Mode
|
||||
G97 M3 S#10
|
||||
G98
|
||||
G82 R#<_z> P0.5 Z#4
|
||||
M5 M9 G18
|
||||
O82 ENDIF
|
||||
|
||||
O<drilling> ENDSUB
|
||||
|
||||
O<drilling> call [10] [100] [0.03] [0] [2] [0] [1]
|
||||
|
||||
M2
|
||||
1
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/ethercat_end.hal
Executable file
1
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/ethercat_end.hal
Executable file
@@ -0,0 +1 @@
|
||||
addf lcec.write-all servo-thread
|
||||
45
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/facing.ngc
Executable file
45
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/facing.ngc
Executable file
@@ -0,0 +1,45 @@
|
||||
;Facing
|
||||
O<facing> sub
|
||||
|
||||
G7 ; Lathe Diameter Mode
|
||||
G18 ; XZ Plane
|
||||
G21 ; Metric Units
|
||||
G90 ; Absolute Distance
|
||||
|
||||
M6 T#7 G43
|
||||
|
||||
O90 IF [#8 GT 0.5]
|
||||
M8
|
||||
O90 ENDIF
|
||||
|
||||
O10 IF [#6 NE 0]
|
||||
(MSG, Angled facing isn't supported yet)
|
||||
O10 ENDIF
|
||||
|
||||
#14 = [#<_x> * 2] (starting X)
|
||||
#13 = #<_z> (starting Z)
|
||||
|
||||
G96 D2500 S#2 ; Constant Surface Speed Mode
|
||||
M3
|
||||
g95 F#4 ; Feed-Per-Rev Mode
|
||||
|
||||
g4p1 ; Wait to reach speed
|
||||
|
||||
O200 WHILE [#13 GT #5 + #3]
|
||||
|
||||
#13=[#13-#3]
|
||||
G1 Z#13
|
||||
G1 X#1
|
||||
G0 Z[#13+#3]
|
||||
G0 X#14
|
||||
G0 Z#13
|
||||
O200 ENDWHILE
|
||||
|
||||
G1 Z#5
|
||||
G1 X#1
|
||||
G0 Z[#13+#3]
|
||||
G0 X[#14+#3]
|
||||
G0 Z#5 ; For touch-off
|
||||
M5 M9
|
||||
O<facing> endsub
|
||||
M2
|
||||
81
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/gmoccapy_lathe.pref
Executable file
81
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/gmoccapy_lathe.pref
Executable file
@@ -0,0 +1,81 @@
|
||||
[DEFAULT]
|
||||
dro_size = 28
|
||||
abs_color = #0000FF
|
||||
rel_color = #000000
|
||||
dtg_color = #FFFF00
|
||||
homed_color = #00FF00
|
||||
unhomed_color = #FF0000
|
||||
spindle_bar_min = 0.0
|
||||
spindle_bar_max = 6000.0
|
||||
unlock_code = 123
|
||||
view = y
|
||||
blockheight = 0.0
|
||||
spindle_start_rpm = 300.0
|
||||
scale_jog_vel = 140.4
|
||||
scale_spindle_override = 1
|
||||
scale_feed_override = 1
|
||||
scale_rapid_override = 1
|
||||
hide_turtle_jog_button = False
|
||||
turtle_jog_factor = 20
|
||||
open_file =
|
||||
screen1 = window
|
||||
x_pos = 40
|
||||
y_pos = 30
|
||||
width = 979
|
||||
height = 750
|
||||
gtk_theme = Follow System Theme
|
||||
audio_alert = /usr/share/sounds/freedesktop/stereo/dialog-warning.oga
|
||||
audio_error = /usr/share/sounds/freedesktop/stereo/dialog-error.oga
|
||||
grid_size = 1.0
|
||||
mouse_btn_mode = 4
|
||||
hide_cursor = False
|
||||
system_name_tool = Tool
|
||||
system_name_g5x = G5x
|
||||
system_name_rot = Rot
|
||||
system_name_g92 = G92
|
||||
system_name_g54 = G54
|
||||
system_name_g55 = G55
|
||||
system_name_g56 = G56
|
||||
system_name_g57 = G57
|
||||
system_name_g58 = G58
|
||||
system_name_g59 = G59
|
||||
system_name_g59.1 = G59.1
|
||||
system_name_g59.2 = G59.2
|
||||
system_name_g59.3 = G59.3
|
||||
jump_to_dir = /home/emcmesa
|
||||
show_keyboard_on_offset = False
|
||||
show_keyboard_on_tooledit = False
|
||||
show_keyboard_on_edit = False
|
||||
show_keyboard_on_mdi = False
|
||||
show_keyboard_on_file_selection = False
|
||||
x_pos_popup = 45.0
|
||||
y_pos_popup = 55
|
||||
width_popup = 250.0
|
||||
max_messages = 10
|
||||
message_font = sans 10
|
||||
use_frames = True
|
||||
reload_tool = True
|
||||
blockdel = False
|
||||
opstop = False
|
||||
enable_dro = False
|
||||
show_offsets = False
|
||||
show_dtg = False
|
||||
view_tool_path = True
|
||||
view_dimension = True
|
||||
run_from_line = no_run
|
||||
unlock_way = no
|
||||
show_preview_on_offset = False
|
||||
use_keyboard_shortcuts = True
|
||||
dro_digits = 3
|
||||
toggle_readout = True
|
||||
tool_in_spindle = 3
|
||||
diameter offset_axis_x = 0
|
||||
offset_axis_x = 0.0
|
||||
offset_axis_z = 0.0
|
||||
offset_axis_r = 50.0
|
||||
radius offset_axis_x = 0
|
||||
use_toolmeasurement = False
|
||||
kbd_height = 250
|
||||
icon_theme = None
|
||||
hide_tooltips = False
|
||||
|
||||
@@ -0,0 +1,72 @@
|
||||
[DEFAULT]
|
||||
dro_size = 28
|
||||
abs_color = #0000FF
|
||||
rel_color = #000000
|
||||
dtg_color = #FFFF00
|
||||
homed_color = #00FF00
|
||||
unhomed_color = #FF0000
|
||||
spindle_bar_min = 0.0
|
||||
spindle_bar_max = 6000.0
|
||||
unlock_code = 123
|
||||
view = y
|
||||
blockheight = 0.0
|
||||
spindle_start_rpm = 300.0
|
||||
scale_jog_vel = 140.4
|
||||
scale_spindle_override = 1
|
||||
scale_feed_override = 1
|
||||
scale_rapid_override = 1
|
||||
hide_turtle_jog_button = False
|
||||
turtle_jog_factor = 20
|
||||
open_file =
|
||||
screen1 = window
|
||||
x_pos = 40
|
||||
y_pos = 30
|
||||
width = 979
|
||||
height = 750
|
||||
gtk_theme = Follow System Theme
|
||||
audio_alert = /usr/share/sounds/freedesktop/stereo/dialog-warning.oga
|
||||
audio_error = /usr/share/sounds/freedesktop/stereo/dialog-error.oga
|
||||
grid_size = 1.0
|
||||
mouse_btn_mode = 4
|
||||
hide_cursor = False
|
||||
system_name_tool = Tool
|
||||
system_name_g5x = G5x
|
||||
system_name_rot = Rot
|
||||
system_name_g92 = G92
|
||||
system_name_g54 = G54
|
||||
system_name_g55 = G55
|
||||
system_name_g56 = G56
|
||||
system_name_g57 = G57
|
||||
system_name_g58 = G58
|
||||
system_name_g59 = G59
|
||||
system_name_g59.1 = G59.1
|
||||
system_name_g59.2 = G59.2
|
||||
system_name_g59.3 = G59.3
|
||||
jump_to_dir = /home/emcmesa
|
||||
show_keyboard_on_offset = False
|
||||
show_keyboard_on_tooledit = False
|
||||
show_keyboard_on_edit = True
|
||||
show_keyboard_on_mdi = True
|
||||
show_keyboard_on_file_selection = False
|
||||
x_pos_popup = 45.0
|
||||
y_pos_popup = 55
|
||||
width_popup = 250.0
|
||||
max_messages = 10
|
||||
message_font = sans 10
|
||||
use_frames = True
|
||||
reload_tool = True
|
||||
blockdel = False
|
||||
opstop = False
|
||||
enable_dro = False
|
||||
show_offsets = False
|
||||
show_dtg = False
|
||||
view_tool_path = True
|
||||
view_dimension = True
|
||||
run_from_line = no_run
|
||||
unlock_way = use
|
||||
show_preview_on_offset = False
|
||||
use_keyboard_shortcuts = False
|
||||
dro_digits = 3
|
||||
toggle_readout = True
|
||||
tool_in_spindle = 0
|
||||
|
||||
23
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/gmoccapy_postgui.hal
Executable file
23
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/gmoccapy_postgui.hal
Executable file
@@ -0,0 +1,23 @@
|
||||
###################################################################
|
||||
# moccapy_postgui.hal file from Norbert Schechner #
|
||||
###################################################################
|
||||
|
||||
loadrt abs names=abs_spindle_feedback
|
||||
addf abs_spindle_feedback servo-thread
|
||||
|
||||
net spindle-speed-limited => abs_spindle_feedback.in
|
||||
net spindle-abs abs_spindle_feedback.out => gmoccapy.spindle_feedback_bar
|
||||
net spindle-at-speed gmoccapy.spindle_at_speed_led
|
||||
|
||||
# the unlink pin commands are only used, because they are connected
|
||||
# in core_sim.hal and we use this file to simulate
|
||||
unlinkp iocontrol.0.tool-change
|
||||
unlinkp iocontrol.0.tool-changed
|
||||
unlinkp iocontrol.0.tool-prep-number
|
||||
|
||||
net tool-change gmoccapy.toolchange-change <= iocontrol.0.tool-change
|
||||
net tool-changed gmoccapy.toolchange-changed <= iocontrol.0.tool-changed
|
||||
net tool-prep-number gmoccapy.toolchange-number <= iocontrol.0.tool-prep-number
|
||||
|
||||
net tooloffset-x gmoccapy.tooloffset-x <= motion.tooloffset.x
|
||||
net tooloffset-z gmoccapy.tooloffset-z <= motion.tooloffset.z
|
||||
32
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/grooving.ngc
Executable file
32
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/grooving.ngc
Executable file
@@ -0,0 +1,32 @@
|
||||
;grooving
|
||||
|
||||
O<grooving> sub
|
||||
|
||||
G8 ; Radius mode (easier maths)
|
||||
G18 ; XZ Plane
|
||||
G21 ; Metric Units
|
||||
G90 ; Absolute Distance
|
||||
G91.1 ; but not for arcs
|
||||
|
||||
M6 T#4 G43
|
||||
|
||||
#1 = [#1 / 2] ; because of radius mode
|
||||
|
||||
#14 = [#<_x>] (starting X)
|
||||
|
||||
G96 D1500 S#2 ; Constant Surface Speed Mode
|
||||
m3 ;Start Spindle
|
||||
g95 F#3 ; Feed-Per-Rev Mode
|
||||
|
||||
O90 IF [#5 GT 0.5]
|
||||
M8
|
||||
O90 ENDIF
|
||||
|
||||
g4p1 ; Wait to reach speed
|
||||
G1 F#3 X#1
|
||||
G0 X#14
|
||||
M5 M9
|
||||
G7
|
||||
O<grooving> endsub
|
||||
|
||||
M2
|
||||
70
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/hallib/README
Executable file
70
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/hallib/README
Executable file
@@ -0,0 +1,70 @@
|
||||
This directory contains halfiles (*.hal and *.tcl) that are available
|
||||
using the LinuxCNC halfile search path or by an explicit directive.
|
||||
|
||||
The HALLIB_PATH is '.:HALLIB_DIR'
|
||||
The '.' specifies the directory containing the INI file.
|
||||
HALIB_DIR specifies this directory.
|
||||
|
||||
The explicit directive uses a prefix (LIB:) to identify halfiles:
|
||||
[HAL]
|
||||
HALFILE = LIB:filename.[hal|tcl]
|
||||
|
||||
The LinuxCNC startup script (linuxcnc) finds each halfile using the
|
||||
HALLIB_PATH unless the explicit directive is used.
|
||||
|
||||
Also included in this directory are files associated with included
|
||||
system halfiles. For example, the button layout files
|
||||
(xhc-hb04-layout*.cfg) that are used with the halfile xhc-hb04.tcl.
|
||||
------------------------------------------------------------------------
|
||||
|
||||
|
||||
Hal files (*.hal) Notes
|
||||
----------------------- ---------------------------------------------
|
||||
axis_manualtoolchange.hal setup for using hal_manualtoolchange
|
||||
(for axis or other guis)
|
||||
core_sim.hal xyz simulator config
|
||||
core_servo.hal xyz servo (pid) config
|
||||
core_sim9.hal 9 axis (xyzabcuvw) simulation config
|
||||
core_stepper.hal xyz stepper config
|
||||
gantrysim.hal gantrykins config, 4 joints: X Y Y Z
|
||||
lathe.hal simulate spindle with encoder,sim_encoder
|
||||
locking_indexer.hal simulate locking rotary using timedelay comp
|
||||
wheeljogpins.tcl enable wheel jog pins for joints & axes
|
||||
moveoff_external.hal Simulate external control connections for
|
||||
a moveoff component
|
||||
servo_sim.hal simulate servo (pid) xyz using lowpass comp
|
||||
sim_spindle_encoder.hal simulate spindle with lowpass filter
|
||||
simulated-gantry-home.hal simulate gantry home switches (4 joints)
|
||||
simulated_home.hal simulate xyz home switches
|
||||
simulated_limits.hal simulate xyz limit switches
|
||||
tripodsim.hal simulated tripodkins system
|
||||
|
||||
Haltcl Files (*.tcl) Notes
|
||||
----------------------- ---------------------------------------------
|
||||
basic_sim.tcl set up a sim config (arbitrary no. of axes)
|
||||
var_show.tcl show INI variables and context
|
||||
hookup_moveoff.tcl make connections for a moveoff component
|
||||
plasmac.tcl common connections for the plasmac component
|
||||
|
||||
xhc-hb04.tcl Configuration builder for xhc-hb04 pendant
|
||||
xhc-hb04-layout1.cfg button layout 1 for xhc-hb04.tcl
|
||||
xhc-hb04-layout2.cfg button layout 2 for xhc-hb04.tcl
|
||||
|
||||
halcheck.tcl Report: 1) functions without addf
|
||||
2) signals with no inputs
|
||||
3) signals with no output
|
||||
|
||||
Haltcl libs (*_lib.tcl) Notes
|
||||
----------------------- ---------------------------------------------
|
||||
sim_lib.tcl simulator config procedures
|
||||
procs:
|
||||
core_sim (arbitrary axes)
|
||||
make-ddts (arbitrary axes)
|
||||
simulated_home (arbitrary axes)
|
||||
use_hal_manualtoolchange
|
||||
sim_spindle
|
||||
util_lib.tcl utility procedures
|
||||
procs:
|
||||
show_context (calling parms)
|
||||
show_ini (INI file settings)
|
||||
show_env (environmental vars)
|
||||
@@ -0,0 +1,10 @@
|
||||
loadusr -W hal_manualtoolchange
|
||||
|
||||
# in case they were linked already
|
||||
unlinkp iocontrol.0.tool-change
|
||||
unlinkp iocontrol.0.tool-changed
|
||||
|
||||
net tool-change hal_manualtoolchange.change iocontrol.0.tool-change
|
||||
net tool-changed hal_manualtoolchange.changed iocontrol.0.tool-changed
|
||||
net tool-prep-number hal_manualtoolchange.number iocontrol.0.tool-prep-number
|
||||
|
||||
71
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/hallib/basic_sim.tcl
Executable file
71
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/hallib/basic_sim.tcl
Executable file
@@ -0,0 +1,71 @@
|
||||
# basic_sim.tcl
|
||||
#
|
||||
# Provide common hal components and connections for a simulated machine.
|
||||
# By default, the script makes and connects ddts, simulated_home,
|
||||
# spindle, and hal_manualtoolchange components.
|
||||
#
|
||||
# Options are available to
|
||||
# a) disable specific hal components and connections
|
||||
# b) save a halfile equivalent to the hal commands executed by
|
||||
# this script (and any prior executed hal commands)
|
||||
#
|
||||
# Coordinate letters and number_of_joints are determined from the usual
|
||||
# INI file settings.
|
||||
#
|
||||
# INI file usage:
|
||||
# [HAL]HALFILE = basic_sim.tcl [Options]
|
||||
# Options:
|
||||
# -no_make_ddts
|
||||
# -no_simulated_home
|
||||
# -no_use_hal_manualtoolchange
|
||||
# -no_sim_spindle
|
||||
|
||||
#----------------------------------------------------------------------
|
||||
# Notes:
|
||||
# 1) ::env() is a global associative array of environmental variables
|
||||
# as exported by the main LinuxCNC script (linuxcnc)
|
||||
# 2) Settings from the INI file are available as global associative
|
||||
# arrays named: ::SECTION(varname)
|
||||
# example: ::EMCMOT(SERVO_PERIOD)
|
||||
# 3) procs are from sim_lib.tcl
|
||||
|
||||
#begin-----------------------------------------------------------------
|
||||
source [file join $::env(HALLIB_DIR) sim_lib.tcl]
|
||||
set save_options {}
|
||||
|
||||
if [catch {check_ini_items} msg] {
|
||||
puts "\nbasic_sim.tcl ERROR: $msg\n"
|
||||
exit 1
|
||||
}
|
||||
set axes [get_traj_coordinates]
|
||||
set number_of_joints $::KINS(JOINTS)
|
||||
|
||||
set base_period 0 ;# 0 means no thread
|
||||
if [info exists ::EMCMOT(BASE_PERIOD)] {
|
||||
set base_period $::EMCMOT(BASE_PERIOD)
|
||||
}
|
||||
|
||||
core_sim $axes \
|
||||
$number_of_joints \
|
||||
$::EMCMOT(SERVO_PERIOD) \
|
||||
$base_period \
|
||||
$::EMCMOT(EMCMOT)
|
||||
|
||||
if {[lsearch -nocase $::argv -no_make_ddts] < 0} {
|
||||
make_ddts $number_of_joints
|
||||
}
|
||||
if {[lsearch -nocase $::argv -no_simulated_home] < 0} {
|
||||
simulated_home $number_of_joints
|
||||
}
|
||||
if {[lsearch -nocase $::argv -no_use_hal_manualtoolchange] < 0} {
|
||||
use_hal_manualtoolchange
|
||||
lappend save_options use_hal_manualtoolchange
|
||||
}
|
||||
if {[lsearch -nocase $::argv -no_sim_spindle] < 0} {
|
||||
sim_spindle
|
||||
}
|
||||
|
||||
# make a halfile (inifilename_cmds.hal) with equivalent hal commands
|
||||
set savefilename \
|
||||
./[file rootname [file tail $::env(INI_FILE_NAME)]]_cmds.hal
|
||||
save_hal_cmds $savefilename $save_options
|
||||
240
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/hallib/check_config.tcl
Executable file
240
Cards/EaserCAT-2000/linuxcnc/sim.gmoccapy.lathe_configs/hallib/check_config.tcl
Executable file
@@ -0,0 +1,240 @@
|
||||
# check_config.tcl
|
||||
# Usage: tclsh path_to_this_file inifilename
|
||||
# if a check fails, print message and exit 1
|
||||
#
|
||||
# checks:
|
||||
# 1) mandatory items per ::mandatory_items list
|
||||
# 2) if trivkins, check consistency of [JOINT_] and [AXIS_]
|
||||
# MIN_LIMIT and MAX_LIMIT
|
||||
#----------------------------------------------------------------------
|
||||
set ::mandatory_items {KINS KINEMATICS
|
||||
KINS JOINTS
|
||||
}
|
||||
# Ref: src/emc/nml_intf/emccfg.h,src/emc/ini/inijoint.cc,src/emc/iniaxis.cc:
|
||||
set ::DEFAULT_AXIS_MAX_VELOCITY 1.0
|
||||
set ::DEFAULT_AXIS_MAX_ACCELERATION 1.0
|
||||
set ::DEFAULT_JOINT_MAX_VELOCITY 1.0
|
||||
set ::DEFAULT_JOINT_MAX_ACCELERATION 1.0
|
||||
|
||||
# Ref: src/emc/ini/iniaxis.cc:
|
||||
set ::DEFAULT_AXIS_MIN_LIMIT -1e99
|
||||
set ::DEFAULT_AXIS_MAX_LIMIT +1e99
|
||||
#----------------------------------------------------------------------
|
||||
proc warnings msg {
|
||||
puts -nonewline "\n$::progname:\n"
|
||||
catch {puts ($::kins(module) kinematics) WARNING:"}
|
||||
foreach m $msg {puts " $m"}
|
||||
puts ""
|
||||
} ;# warnings
|
||||
|
||||
proc err_exit msg {
|
||||
puts -nonewline "\n$::progname:\n"
|
||||
catch {puts ($::kins(module) kinematics) ERROR:"}
|
||||
foreach m $msg {puts " $m"}
|
||||
puts ""
|
||||
exit 1
|
||||
} ;# err_exit
|
||||
|
||||
proc check_mandatory_items {} {
|
||||
foreach {section item} $::mandatory_items {
|
||||
if  ] {
|
||||
set section [string trim $section :]
|
||||
lappend emsg "Missing \[$section\]$item="
|
||||
}
|
||||
}
|
||||
if [info exists emsg] {
|
||||
err_exit $emsg
|
||||
}
|
||||
} ;# check_mandatory_items
|
||||
|
||||
proc uniq {list_name} { ;# make list unique
|
||||
foreach item $list_name { set tmp($item) "" }
|
||||
return [array names tmp]
|
||||
} ;# uniq
|
||||
|
||||
proc joints_for_trivkins {coords} {
|
||||
# ref: src/emc/kinematics/trivkins.c
|
||||
# order of coord letters determines assigned joint number
|
||||
if {"$coords" == ""} {set coords {X Y Z A B C U V W}}
|
||||
set i 0
|
||||
foreach a [string toupper $coords] {
|
||||
# assign to consecutive joints:
|
||||
lappend ::kins(jointidx,$a) $i
|
||||
incr i
|
||||
}
|
||||
} ;# joints_for_trivkins
|
||||
|
||||
proc consistent_coords_for_trivkins {trivcoords} {
|
||||
set m {" " "" "\t" ""} ;# mapping to remove whitespace
|
||||
set trivcoords [string map $m $trivcoords]
|
||||
if {"$trivcoords" == "XYZABCUVW"} {
|
||||
return ;# unspecified trivkins coordinates
|
||||
# allows use of any coordinates
|
||||
}
|
||||
set trajcoords ""
|
||||
if [info exists ::TRAJ(COORDINATES)] {
|
||||
set trajcoords [string map $m [lindex $::TRAJ(COORDINATES) 0]]
|
||||
}
|
||||
if {[string toupper "$trivcoords"] != [string toupper "$trajcoords"]} {
|
||||
lappend ::wmsg "INCONSISTENT coordinates specifications:
|
||||
trivkins coordinates=$trivcoords
|
||||
\[TRAJ\]COORDINATES=$trajcoords"
|
||||
}
|
||||
} ;# consistent_coords_for_trivkins
|
||||
|
||||
proc validate_identity_kins_limits {} {
|
||||
set emsg ""
|
||||
for {set j 0} {$j < $::KINS(JOINTS)} {incr j} {
|
||||
if {] } {
|
||||
lappend ::wmsg "Unspecified \[JOINT_$j\]MAX_VELOCITY, default used: $::DEFAULT_JOINT_MAX_VELOCITY"
|
||||
}
|
||||
if {] } {
|
||||
lappend ::wmsg "Unspecified \[JOINT_$j\]MAX_ACCELERATION, default used: $::DEFAULT_JOINT_MAX_ACCELERATION"
|
||||
}
|
||||
}
|
||||
foreach c [uniq $::kins(coordinates)] {
|
||||
# array test avoids superfluous messages when coordinates= not specified
|
||||
if [array exists ::AXIS_[set c]] {
|
||||
if {] } {
|
||||
lappend ::wmsg "Unspecified \[AXIS_$c\]MAX_VELOCITY, default used: $::DEFAULT_AXIS_MAX_VELOCITY"
|
||||
}
|
||||
if {] } {
|
||||
lappend ::wmsg "Unspecified \[AXIS_$c\]MAX_ACCELERATION, default used: $::DEFAULT_AXIS_MAX_ACCELERATION"
|
||||
}
|
||||
}
|
||||
|
||||
set missing_axis_min_limit 0
|
||||
set missing_axis_max_limit 0
|
||||
if ] {
|
||||
set ::AXIS_[set c](MIN_LIMIT) $::DEFAULT_AXIS_MIN_LIMIT
|
||||
set missing_axis_min_limit 1
|
||||
}
|
||||
if ] {
|
||||
set ::AXIS_[set c](MAX_LIMIT) $::DEFAULT_AXIS_MAX_LIMIT
|
||||
set missing_axis_max_limit 1
|
||||
}
|
||||
foreach j $::kins(jointidx,$c) {
|
||||
if [info exists ::JOINT_[set j](MIN_LIMIT)] {
|
||||
set jlim [set ::JOINT_[set j](MIN_LIMIT)]
|
||||
set clim [set ::AXIS_[set c](MIN_LIMIT)]
|
||||
if {$jlim > $clim} {
|
||||
if $missing_axis_min_limit {
|
||||
lappend ::wmsg "Unspecified \[AXIS_$c\]MIN_LIMIT, default used: $::DEFAULT_AXIS_MIN_LIMIT"
|
||||
}
|
||||
lappend emsg "\[JOINT_$j\]MIN_LIMIT > \[AXIS_$c\]MIN_LIMIT ($jlim > $clim)"
|
||||
}
|
||||
}
|
||||
if [info exists ::JOINT_[set j](MAX_LIMIT)] {
|
||||
set jlim [set ::JOINT_[set j](MAX_LIMIT)]
|
||||
set clim [set ::AXIS_[set c](MAX_LIMIT)]
|
||||
if {$jlim < $clim} {
|
||||
if $missing_axis_max_limit {
|
||||
lappend ::wmsg "Unspecified \[AXIS_$c\]MAX_LIMIT, default used: $::DEFAULT_AXIS_MAX_LIMIT"
|
||||
}
|
||||
lappend emsg "\[JOINT_$j\]MAX_LIMIT < \[AXIS_$c\]MAX_LIMIT ($jlim < $clim)"
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return $emsg
|
||||
} ;# validate_identity_kins_limits
|
||||
|
||||
proc check_extrajoints {} {
|
||||
if ![info exists ::EMCMOT(EMCMOT)] return
|
||||
if {[string first motmod $::EMCMOT(EMCMOT)] <= 0} return
|
||||
set mot [split [lindex $::EMCMOT(EMCMOT) 0]]
|
||||
foreach item $mot {
|
||||
set pair [split $item =]
|
||||
set parm [lindex $pair 0]
|
||||
set val [lindex $pair 1]
|
||||
if {"$parm" == "num_extrajoints"} {
|
||||
set ::num_extrajoints $val
|
||||
}
|
||||
}
|
||||
if [info exists ::num_extrajoints] {
|
||||
lappend ::wmsg [format "Extra joints specified=%d\n \
|
||||
\[KINS\]JOINTS=%d must accommodate kinematic joints *plus* extra joints " \
|
||||
$::num_extrajoints $::KINS(JOINTS)]
|
||||
}
|
||||
} ;#check_extrajoints
|
||||
|
||||
proc warn_for_multiple_ini_values {} {
|
||||
set sections [info globals]
|
||||
set sections_to_check {JOINT_ AXIS_}
|
||||
|
||||
foreach section $sections {
|
||||
set enforce 0
|
||||
foreach csection $sections_to_check {
|
||||
if {[string first $csection $section"] >= 0} {
|
||||
set enforce 1
|
||||
break
|
||||
}
|
||||
}
|
||||
if !$enforce continue
|
||||
foreach name [array names ::$section] {
|
||||
set gsection ::$section
|
||||
set val [set [set gsection]($name)]
|
||||
set len [llength $val]
|
||||
if {$len > 1} {
|
||||
lappend ::wmsg "Unexpected multiple values \[$section\]$name: $val"
|
||||
}
|
||||
}
|
||||
}
|
||||
} ;# warn_for_multiple_ini_values
|
||||
|
||||
#----------------------------------------------------------------------
|
||||
# begin
|
||||
package require Linuxcnc ;# parse_ini
|
||||
|
||||
set ::progname [file rootname [file tail [info script]]]
|
||||
set inifile [lindex $::argv 0]
|
||||
if ![file exists $inifile] {
|
||||
err_exit [list "No such file <$inifile>"]
|
||||
}
|
||||
if ![file readable $inifile] {
|
||||
err_exit [list "File not readable <$inifile>"]
|
||||
}
|
||||
parse_ini $inifile
|
||||
|
||||
check_mandatory_items
|
||||
|
||||
set kins_kinematics [lindex $::KINS(KINEMATICS) end]
|
||||
set ::kins(module) [lindex $kins_kinematics 0]
|
||||
|
||||
# parameters specified as parm=value --> ::kins(parm)=value
|
||||
foreach item $kins_kinematics {
|
||||
if {[string first = $item] >= 0} {
|
||||
set l [split $item =]
|
||||
set ::kins([lindex $l 0]) [lindex $l 1]
|
||||
} else {
|
||||
if {"$item" != $::kins(module)} {
|
||||
puts "Unknown \[KINS\]KINEMATICS item: <$item>"
|
||||
}
|
||||
}
|
||||
}
|
||||
# coordinates --> ::kins(coordinates) (all if not specified)
|
||||
if [info exists ::kins(coordinates)] {
|
||||
set ::kins(coordinates) [split $::kins(coordinates) ""]
|
||||
set ::kins(coordinates) [string toupper $::kins(coordinates)]
|
||||
} else {
|
||||
set ::kins(coordinates) {X Y Z A B C U V W}
|
||||
}
|
||||
|
||||
# list of joints for each coord --> ::kins(jointidx,coordinateletter)
|
||||
switch $::kins(module) {
|
||||
trivkins {joints_for_trivkins $::kins(coordinates)}
|
||||
default {
|
||||
puts "$::progname: Unchecked: \[KINS\]KINEMATICS=$::KINS(KINEMATICS)"
|
||||
exit 0
|
||||
}
|
||||
}
|
||||
check_extrajoints
|
||||
|
||||
warn_for_multiple_ini_values
|
||||
#parray ::kins
|
||||
set emsg [validate_identity_kins_limits]
|
||||
consistent_coords_for_trivkins $::kins(coordinates)
|
||||
if [info exists ::wmsg] {warnings $::wmsg}
|
||||
|
||||
if {"$emsg" == ""} {exit 0}
|
||||
err_exit $emsg
|
||||
@@ -0,0 +1,63 @@
|
||||
# HAL config file to check vel/acc constraints
|
||||
#
|
||||
loadrt wcomp names=wcomp_xacc,wcomp_xvel,wcomp_yacc,wcomp_yvel,wcomp_zacc,wcomp_zvel
|
||||
|
||||
addf wcomp_xacc servo-thread
|
||||
addf wcomp_xvel servo-thread
|
||||
addf wcomp_yacc servo-thread
|
||||
addf wcomp_yvel servo-thread
|
||||
addf wcomp_zacc servo-thread
|
||||
addf wcomp_zvel servo-thread
|
||||
|
||||
net Xacc => wcomp_xacc.in
|
||||
net Xvel => wcomp_xvel.in
|
||||
net Yacc => wcomp_yacc.in
|
||||
net Yvel => wcomp_yvel.in
|
||||
net Zacc => wcomp_zacc.in
|
||||
net Zvel => wcomp_zvel.in
|
||||
|
||||
net acc-ok-x <= wcomp_xacc.out
|
||||
net vel-ok-x <= wcomp_xvel.out
|
||||
net acc-ok-y <= wcomp_yacc.out
|
||||
net vel-ok-y <= wcomp_yvel.out
|
||||
net acc-ok-z <= wcomp_zacc.out
|
||||
net vel-ok-z <= wcomp_zvel.out
|
||||
|
||||
setp wcomp_xacc.max 50.001
|
||||
setp wcomp_xacc.min -50.001
|
||||
setp wcomp_xvel.max 5.001
|
||||
setp wcomp_xvel.min -5.001
|
||||
setp wcomp_yacc.max 50.001
|
||||
setp wcomp_yacc.min -50.001
|
||||
setp wcomp_yvel.max 5.001
|
||||
setp wcomp_yvel.min -5.001
|
||||
setp wcomp_zacc.max 50.001
|
||||
setp wcomp_zacc.min -50.001
|
||||
setp wcomp_zvel.max 5.001
|
||||
setp wcomp_zvel.min -5.001
|
||||
|
||||
loadrt match8 names=match_all
|
||||
|
||||
addf match_all servo-thread
|
||||
|
||||
net acc-ok-x => match_all.a0
|
||||
setp match_all.b0 1
|
||||
net vel-ok-x => match_all.a1
|
||||
setp match_all.b1 1
|
||||
net acc-ok-y => match_all.a2
|
||||
setp match_all.b2 1
|
||||
net vel-ok-y => match_all.a3
|
||||
setp match_all.b3 1
|
||||
net acc-ok-z => match_all.a4
|
||||
setp match_all.b4 1
|
||||
net vel-ok-z => match_all.a5
|
||||
setp match_all.b5 1
|
||||
|
||||
setp match_all.a6 0
|
||||
setp match_all.a7 0
|
||||
setp match_all.b6 0
|
||||
setp match_all.b7 0
|
||||
|
||||
setp match_all.in 1
|
||||
|
||||
net constraints-ok <= match_all.out
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user