This commit is contained in:
Anders Sandstrom
2022-01-21 11:36:18 +01:00
parent 15fc72e326
commit a889eb0e8c
12 changed files with 4818 additions and 63 deletions

View File

@@ -20,7 +20,7 @@
#include "ecmcAsynPortDriver.h"
#include "ecmcAsynPortDriverUtils.h"
#include "epicsThread.h"
#include <time.h>
#include "ecmcMotion.h"
extern "C" {
@@ -96,17 +96,20 @@ ecmcGrbl::ecmcGrbl(char* configStr,
{
// Init
cfgDbgMode_ = 0;
destructs_ = 0;
connected_ = 0;
errorCode_ = 0;
exeSampleTimeMs_ = exeSampleTimeMs;
cfgXAxisId_ = -1;
cfgYAxisId_ = -1;
cfgZAxisId_ = -1;
cfgSpindleAxisId_ = -1;
grblInitDone_ = 0;
cfgDbgMode_ = 0;
destructs_ = 0;
connected_ = 0;
errorCode_ = 0;
exeSampleTimeMs_ = exeSampleTimeMs;
cfgXAxisId_ = -1;
cfgYAxisId_ = -1;
cfgZAxisId_ = -1;
cfgSpindleAxisId_ = -1;
grblInitDone_ = 0;
cfgAutoEnableAtStart_ = 0;
autoEnableExecuted_ = 0;
//grbl default rate 30khz..
grblExeCycles_ = 30000.0/(1/exeSampleTimeMs);
if(!(grblCommandBufferMutex_ = epicsMutexCreate())) {
throw std::runtime_error("Error: Failed create mutex thread for write().");
@@ -114,6 +117,10 @@ ecmcGrbl::ecmcGrbl(char* configStr,
parseConfigStr(configStr); // Assigns all configs
// simulate auto enable
if(!cfgAutoEnableAtStart_) {
autoEnableExecuted_ = 1;
}
//Check atleast one valid axis
if(cfgXAxisId_<0 && cfgXAxisId_<0 && cfgXAxisId_<0 && cfgSpindleAxisId_<0) {
throw std::out_of_range("No valid axis choosen.");
@@ -197,6 +204,12 @@ void ecmcGrbl::parseConfigStr(char *configStr) {
cfgSpindleAxisId_ = atoi(pThisOption);
}
// ECMC_PLUGIN_AUTO_ENABLE_AT_START_OPTION_CMD (1..ECMC_MAX_AXES)
if (!strncmp(pThisOption, ECMC_PLUGIN_AUTO_ENABLE_AT_START_OPTION_CMD, strlen(ECMC_PLUGIN_AUTO_ENABLE_AT_START_OPTION_CMD))) {
pThisOption += strlen(ECMC_PLUGIN_AUTO_ENABLE_AT_START_OPTION_CMD);
cfgAutoEnableAtStart_ = atoi(pThisOption);
}
pThisOption = pNextOption;
}
free(pOptions);
@@ -220,7 +233,7 @@ void ecmcGrbl::doWriteWorker() {
// simulate serial connection here (need mutex)
printf("%s:%s:%d\n",__FILE__,__FUNCTION__,__LINE__);
for(;;) {
if(grblCommandBuffer_.size()>0) {
if(grblCommandBuffer_.size()>0 && getEcmcEpicsIOCState()==16 && autoEnableExecuted_) {
printf("%s:%s:%d: Command in buffer!!!\n",__FILE__,__FUNCTION__,__LINE__);
epicsMutexLock(grblCommandBufferMutex_);
std::string command = grblCommandBuffer_.front() + '\n';
@@ -318,52 +331,78 @@ void ecmcGrbl::doMainWorker() {
}
}
}
// buf needs to store 30 characters
int timespec2str(char *buf, uint len, struct timespec *ts) {
int ret;
struct tm t;
tzset();
if (localtime_r(&(ts->tv_sec), &t) == NULL)
return 1;
void ecmcGrbl::autoEnableAtStart() {
if(!cfgAutoEnableAtStart_ || autoEnableExecuted_ || getEcmcEpicsIOCState()!=16) {
return;
}
// write to ecmc
if(cfgXAxisId_>=0) {
setAxisEnable(cfgXAxisId_,1);
}
if(cfgYAxisId_>=0) {
setAxisEnable(cfgYAxisId_,1);
}
if(cfgZAxisId_>=0) {
setAxisEnable(cfgZAxisId_,1);
}
ret = strftime(buf, len, "%F %T", &t);
if (ret == 0)
return 2;
len -= ret - 1;
if(getAllConfiguredAxisEnabled()) {
autoEnableExecuted_ = 1;
}
}
ret = snprintf(&buf[strlen(buf)], len, ".%09ld", ts->tv_nsec);
if (ret >= len)
return 3;
bool ecmcGrbl::getEcmcAxisEnabled(int axis) {
int ena=0;
getAxisEnabled(axis, &ena);
return ena;
}
return 0;
bool ecmcGrbl::getAllConfiguredAxisEnabled() {
int ena = 1;
if(cfgXAxisId_>=0 && ena) {
ena = getEcmcAxisEnabled(cfgXAxisId_);
}
if(cfgYAxisId_>=0 && ena) {
ena = getEcmcAxisEnabled(cfgYAxisId_);
}
if(cfgZAxisId_>=0 && ena) {
ena = getEcmcAxisEnabled(cfgZAxisId_);
}
if(cfgSpindleAxisId_>=0 && ena) {
ena = getEcmcAxisEnabled(cfgSpindleAxisId_);
}
return ena;
}
// grb realtime thread!!!
void ecmcGrbl::grblRTexecute() {
for(int i=0; i < 30; i++) {
if(!grblInitDone_) {
break;
}
ecmc_grbl_main_rt_thread();
void ecmcGrbl::grblRTexecute() {
autoEnableAtStart();
if(grblInitDone_ && autoEnableExecuted_) {
for(int i=0; i < grblExeCycles_; i++) {
ecmc_grbl_main_rt_thread();
}
struct timespec timeAbs_;
clock_gettime(CLOCK_REALTIME, &timeAbs_);
const uint TIME_FMT = strlen("2012-12-31 12:59:59.123456789") + 1;
char timestr[TIME_FMT];
// struct timespec ts, res;
// clock_getres(clk_id, &res);
// clock_gettime(clk_id, &ts);
timespec2str(timestr, sizeof(timestr), &timeAbs_);
//IOC_TEST:ec0-s4-EL7211-Enc-PosAct 2020-12-14 13:29:18.273839 -2.587392807
//printf("%s:%s:%d Positions(x,y,z)=%d,%d,%d..\n",__FILE__,__FUNCTION__,__LINE__,sys_position[X_AXIS], sys_position[Y_AXIS],sys_position[Z_AXIS] );
printf("IOC_TEST:Axis-X-PosAct %s %d\n",timestr,sys_position[X_AXIS]);
printf("IOC_TEST:Axis-Y-PosAct %s %d\n",timestr,sys_position[Y_AXIS]);
printf("IOC_TEST:Axis-Z-PosAct %s %d\n",timestr,sys_position[Z_AXIS]);
}
// write to ecmc
if(cfgXAxisId_>=0) {
if(grblInitDone_ && autoEnableExecuted_) {
printf("[X_AXIS]= %lf/%lf=%lf\n",double(sys_position[X_AXIS]),double(settings.steps_per_mm[X_AXIS]),double(sys_position[X_AXIS])/double(settings.steps_per_mm[X_AXIS]));
}
setAxisExtSetPos(cfgXAxisId_,double(sys_position[X_AXIS])/double(settings.steps_per_mm[X_AXIS]));
}
if(cfgYAxisId_>=0) {
setAxisExtSetPos(cfgYAxisId_,sys_position[Y_AXIS]/settings.steps_per_mm[Y_AXIS]);
}
if(cfgZAxisId_>=0) {
setAxisExtSetPos(cfgZAxisId_,sys_position[Z_AXIS]/settings.steps_per_mm[Z_AXIS]);
}
// if(cfgSpindleAxisId_>=0) {
// setAxisTargetVel(xxx);
// }
}
// Avoid issues with std:to_string()

View File

@@ -51,12 +51,17 @@ class ecmcGrbl : public asynPortDriver {
private:
void testGrbl();
void parseConfigStr(char *configStr);
void autoEnableAtStart();
bool getEcmcAxisEnabled(int axis_id);
bool getAllConfiguredAxisEnabled();
static std::string to_string(int value);
int cfgDbgMode_;
int cfgXAxisId_;
int cfgYAxisId_;
int cfgZAxisId_;
int cfgSpindleAxisId_;
int cfgAutoEnableAtStart_;
int destructs_;
int connected_;
int errorCode_;
@@ -65,6 +70,8 @@ class ecmcGrbl : public asynPortDriver {
std::queue<std::string> grblCommandBuffer_;
epicsMutexId grblCommandBufferMutex_;
bool firstCommandWritten_;
int autoEnableExecuted_;
int grblExeCycles_;
};
#endif /* ECMC_GRBL_H_ */

View File

@@ -19,6 +19,8 @@
#define ECMC_PLUGIN_Y_AXIS_ID_OPTION_CMD "Y_AXIS="
#define ECMC_PLUGIN_Z_AXIS_ID_OPTION_CMD "Z_AXIS="
#define ECMC_PLUGIN_SPINDLE_AXIS_ID_OPTION_CMD "SPINDLE_AXIS="
#define ECMC_PLUGIN_AUTO_ENABLE_AT_START_OPTION_CMD "AUTO_ENABLE="
#define ECMC_PLUGIN_ASYN_PREFIX "plugin.grbl"
#define ECMC_PLUGIN_GRBL_GENERAL_ERROR_CODE 1

View File

@@ -113,7 +113,13 @@ struct ecmcPluginData pluginDataDef = {
// Description
.desc = "grbl plugin for use with ecmc.",
// Option description
.optionDesc = "\n "ECMC_PLUGIN_DBG_PRINT_OPTION_CMD"<1/0> : Enables/disables printouts from plugin, default = disabled (=0).\n",
.optionDesc = "\n "ECMC_PLUGIN_DBG_PRINT_OPTION_CMD"<1/0> : Enables/disables printouts from plugin, default = disabled (=0).\n"
" "ECMC_PLUGIN_X_AXIS_ID_OPTION_CMD"<axis id>: Ecmc Axis id for use as grbl X axis, default = disabled (=-1).\n"
" "ECMC_PLUGIN_Y_AXIS_ID_OPTION_CMD"<axis id>: Ecmc Axis id for use as grbl Y axis, default = disabled (=-1).\n"
" "ECMC_PLUGIN_Z_AXIS_ID_OPTION_CMD"<axis id>: Ecmc Axis id for use as grbl Z axis, default = disabled (=-1).\n"
" "ECMC_PLUGIN_SPINDLE_AXIS_ID_OPTION_CMD"<axis id>: Ecmc Axis id for use as grbl spindle axis, default = disabled (=-1).\n"
" "ECMC_PLUGIN_AUTO_ENABLE_AT_START_OPTION_CMD"<1/0>: Auto enable the linked ecmc axes autmatically before start, default = disabled (=0).\n"
,
// Plugin version
.version = ECMC_EXAMPLE_PLUGIN_VERSION,
// Optional construct func, called once at load. NULL if not definded.

View File

@@ -128,7 +128,7 @@ void spindle_stop()
// and stepper ISR. Keep routine small and efficient.
void spindle_set_speed(uint8_t pwm_value)
{
printf("%s:%s:%d Not supported yet..\n",__FILE__,__FUNCTION__,__LINE__);
// printf("%s:%s:%d Not supported yet..\n",__FILE__,__FUNCTION__,__LINE__);
// SPINDLE_OCR_REGISTER = pwm_value; // Set PWM output level.
// #ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED

0
iocsh/0: Normal file
View File

95
iocsh/cfg/linear_1.ax Normal file
View File

@@ -0,0 +1,95 @@
#General
epicsEnvSet("ECMC_MOTOR_NAME", "Axis1")
epicsEnvSet("ECMC_R", "Axis1-")
epicsEnvSet("ECMC_AXIS_NO", "1")
epicsEnvSet("ECMC_DESC", "MCU1021 Lower Axis (1)")
epicsEnvSet("ECMC_EGU", "mm") # Motor Record Unit
epicsEnvSet("ECMC_PREC", "3") # Motor Record Precision
epicsEnvSet("ECMC_AXISCONFIG", "") # Extra parameters to driver
epicsEnvSet("ECMC_EC_AXIS_HEALTH", "") # Entry for axis health output (example: ec0.s1.binaryOutput01.0)
epicsEnvSet("ECMC_MOD_RANGE" , "0") # Modulo range (traj setpoints and encoder values will be in range 0..ECMC_MOD_RANGE)
epicsEnvSet("ECMC_MOD_TYPE", "0") # For positioning and MOD_RANGE>0: 0 = Normal, 1 = Always Fwd, 2 = Always Bwd, 3 = Closest Distance
#Encoder
epicsEnvSet("ECMC_ENC_SCALE_NUM" "-60")
epicsEnvSet("ECMC_ENC_SCALE_DENOM" "2000")
epicsEnvSet("ECMC_ENC_TYPE" "0") # Type: 0=Incremental, 1=Absolute
epicsEnvSet("ECMC_ENC_BITS" "16") # Total bit count of encoder raw data
epicsEnvSet("ECMC_ENC_ABS_BITS", "0") # Absolute bit count (for absolute encoders) always least significant part of ECMC_ENC_BITS
epicsEnvSet("ECMC_ENC_ABS_OFFSET" "0") # Encoder offset in eng units (for absolute encoders)
epicsEnvSet("ECMC_EC_ENC_ACTPOS", "ec0.s3.positionActual01") # Ethercat entry for actual position input (encoder)
epicsEnvSet("ECMC_EC_ENC_RESET", "") # Reset (if no encoder reset bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_ALARM_0", "") # Error 0 (if no encoder error bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_ALARM_1", "") # Error 1 (if no encoder error bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_ALARM_2", "") # Error 2 (if no encoder error bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_WARNING", "") # Warning (if no encoder warning bit then leave empty)
#Drive
epicsEnvSet("ECMC_DRV_TYPE" "0") # Stepper: 0. DS402: 1 (DS402 = servos and advanced stepper drives)
epicsEnvSet("ECMC_DRV_SCALE_NUM" "600.0") # Fastest speed in engineering units
epicsEnvSet("ECMC_DRV_SCALE_DENOM" "32768.0") # I/O range for ECMC_EC_ALIAS_DRV_VELO_SET
epicsEnvSet("ECMC_EC_DRV_CONTROL", "ec0.s8.driveControl01.0") # Ethercat entry for control word or bit output
epicsEnvSet("ECMC_EC_DRV_STATUS", "ec0.s8.driveStatus01.1") # Ethercat entry for status word or bit input
epicsEnvSet("ECMC_EC_DRV_VELOCITY", "ec0.s8.velocitySetpoint01") # Ethercat entry for velocity setpoint output
epicsEnvSet("ECMC_EC_DRV_REDUCE_TORQUE", "ec0.s8.driveControl01.2") # Ethercat entry for reduce torque output
epicsEnvSet("ECMC_EC_DRV_BRAKE", "") # Ethercat entry for brake output
epicsEnvSet("ECMC_DRV_BRAKE_OPEN_DLY_TIME", "0") # Brake timing parameter in cycles (default 1kHz)
epicsEnvSet("ECMC_DRV_BRAKE_CLOSE_AHEAD_TIME", "0") # Brake timing parameter in cycles (default 1kHz)
epicsEnvSet("ECMC_EC_DRV_RESET", "ec0.s8.driveControl01.1") # Reset
epicsEnvSet("ECMC_EC_DRV_ALARM_0", "ec0.s8.driveStatus01.3") # Error
epicsEnvSet("ECMC_EC_DRV_ALARM_1", "ec0.s8.driveStatus01.7") # Stall
epicsEnvSet("ECMC_EC_DRV_ALARM_2", "ec0.s8.driveStatus01.14") # Sync error
epicsEnvSet("ECMC_EC_DRV_WARNING", "ec0.s8.driveStatus01.2") # Warning
#Trajectory
epicsEnvSet("ECMC_TRAJ_TYPE" "1") # Trapetz: 0. S-Curve: 1
epicsEnvSet("ECMC_VELO", "10.0")
epicsEnvSet("ECMC_JOG_VEL", "5")
epicsEnvSet("ECMC_JAR", "0.0") # JAR defaults to VELO/ACCL
epicsEnvSet("ECMC_ACCS_EGU_PER_S2", "10")
epicsEnvSet("ECMC_EMERG_DECEL", "100") # Emergency deceleration
epicsEnvSet("ECMC_JERK", "10.0") # Only valid for ECMC_TRAJ_TYPE==1
#Homing
epicsEnvSet("ECMC_HOME_PROC", "3")
epicsEnvSet("ECMC_HOME_POS", "0.0")
epicsEnvSet("ECMC_HOME_VEL_TO", "5")
epicsEnvSet("ECMC_HOME_VEL_FRM", "4")
epicsEnvSet("ECMC_HOME_ACC", "21")
epicsEnvSet("ECMC_HOME_DEC", "100")
epicsEnvSet("ECMC_HOME_POS_MOVE_ENA", "0") # Enable move to position after successfull homing
epicsEnvSet("ECMC_HOME_POS_MOVE_TARG_POS","0") # Target position to go to after successfull homing
#Controller
epicsEnvSet("ECMC_CNTRL_KP", "15.0")
epicsEnvSet("ECMC_CNTRL_KI", "0.02")
epicsEnvSet("ECMC_CNTRL_KD", "0.0")
epicsEnvSet("ECMC_CNTRL_KFF", "1.0")
#Monitoring
# Switches
epicsEnvSet("ECMC_EC_MON_LOWLIM", "ec0.s1.binaryInput02.0") # Ethercat entry for low limit switch input
epicsEnvSet("ECMC_EC_MON_HIGHLIM", "ec0.s1.binaryInput01.0") # Ethercat entry for high limit switch inpuit
epicsEnvSet("ECMC_EC_MON_HOME_SWITCH", "ec0.s1.binaryInput03.0") # Ethercat entry for home switch input
epicsEnvSet("ECMC_EC_MON_EXT_INTERLOCK", "ec0.s1.ONE.0") # Ethercat entry for external interlock input
# Softlimits (disable with 0,0,0)
epicsEnvSet("ECMC_SOFT_LOW_LIM", "-20")
epicsEnvSet("ECMC_SOFT_HIGH_LIM", "130")
epicsEnvSet("ECMC_DXLM_ENABLE", "1")
# Position lag
epicsEnvSet("ECMC_MON_LAG_MON_TOL", "1.0")
epicsEnvSet("ECMC_MON_LAG_MON_TIME", "10")
epicsEnvSet("ECMC_MON_LAG_MON_ENA", "1")
# At target
epicsEnvSet("ECMC_MON_AT_TARGET_TOL", "0.1")
epicsEnvSet("ECMC_MON_AT_TARGET_TIME", "100")
epicsEnvSet("ECMC_MON_AT_TARGET_ENA", "1")
# Velocity
epicsEnvSet("ECMC_MON_VELO_MAX", "100.0")
epicsEnvSet("ECMC_MON_VELO_MAX_TRAJ_TIME","100")
epicsEnvSet("ECMC_MON_VELO_MAX_DRV_TIME", "200")
epicsEnvSet("ECMC_MON_VELO_MAX_ENA", "1")

25
iocsh/cfg/linear_1.sax Normal file
View File

@@ -0,0 +1,25 @@
############# Encoder
epicsEnvSet("ECMC_ENC_SOURCE", "0") # 0 Internal (from hardware), 1 from PLC
epicsEnvSet("ECMC_ENC_VELO_FILT_ENABLE", "1") # Enable velocity filter
epicsEnvSet("ECMC_ENC_VELO_FILT_SIZE", "20") # Encoder velocity Low pass filter size
############# Trajectory
epicsEnvSet("ECMC_TRAJ_SOURCE", "1") # 0 Internal (from hardware), 1 from PLC
epicsEnvSet("ECMC_TRAJ_VELO_FILT_ENABLE", "1") # Enable velocity filter
epicsEnvSet("ECMC_TRAJ_VELO_FILT_SIZE", "20") # Trajectory velocity Low pass filter size
############# Commands
epicsEnvSet("ECMC_CMD_FRM_OTHER_PLC_ENABLE", "1") # Allow commands from PLC
epicsEnvSet("ECMC_CMD_AXIS_PLC_ENABLE", "0") # Enable Axis PLC
# Each line below is appended to one single expression/source.
# Executed in sync with axis (before)
epicsEnvSet("ECMC_AXIS_EXPR_LINE_1", "var a:=1|")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_2", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_3", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_4", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_5", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_6", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_7", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_8", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_9", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_10", "")

93
iocsh/cfg/linear_2.ax Normal file
View File

@@ -0,0 +1,93 @@
#General
epicsEnvSet("ECMC_MOTOR_NAME", "Axis2")
epicsEnvSet("ECMC_R", "Axis2-")
epicsEnvSet("ECMC_AXIS_NO", "2")
epicsEnvSet("ECMC_DESC", "MCU1021 Upper Axis (2)")
epicsEnvSet("ECMC_EGU", "mm") # Motor Record Unit
epicsEnvSet("ECMC_PREC", "3") # Motor Record Precision
epicsEnvSet("ECMC_AXISCONFIG", "") # Extra parameters to driver
epicsEnvSet("ECMC_EC_AXIS_HEALTH", "") # Entry for axis health output (example: ec0.s1.binaryOutput01.0)
epicsEnvSet("ECMC_MOD_RANGE" , "0") # Modulo range (traj setpoints and encoder values will be in range 0..ECMC_MOD_RANGE)
epicsEnvSet("ECMC_MOD_TYPE", "0") # For positioning and MOD_RANGE>0: 0 = Normal, 1 = Always Fwd, 2 = Always Bwd, 3 = Closest Distance
#Encoder
epicsEnvSet("ECMC_ENC_SCALE_NUM" "60")
epicsEnvSet("ECMC_ENC_SCALE_DENOM" "2000")
epicsEnvSet("ECMC_ENC_TYPE" "0") # Type: 0=Incremental, 1=Absolute
epicsEnvSet("ECMC_ENC_BITS" "16") # Total bit count of encoder raw data
epicsEnvSet("ECMC_ENC_ABS_BITS", "0") # Absolute bit count (for absolute encoders) always least significant part of ECMC_ENC_BITS
epicsEnvSet("ECMC_ENC_ABS_OFFSET" "0") # Encoder offset in eng units (for absolute encoders)
epicsEnvSet("ECMC_EC_ENC_ACTPOS", "ec0.s4.positionActual01") # Ethercat entry for actual position input (encoder)
epicsEnvSet("ECMC_EC_ENC_RESET", "") # Reset (if no encoder reset bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_ALARM_0", "") # Error 0 (if no encoder error bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_ALARM_1", "") # Error 1 (if no encoder error bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_ALARM_2", "") # Error 2 (if no encoder error bit then leave empty)
epicsEnvSet("ECMC_EC_ENC_WARNING", "") # Warning (if no encoder warning bit then leave empty)
#Drive
epicsEnvSet("ECMC_DRV_TYPE" "0") # Stepper: 0. DS402: 1 (DS402 = servos and advanced stepper drives)
epicsEnvSet("ECMC_DRV_SCALE_NUM" "-600.0") # Fastest speed in engineering units
epicsEnvSet("ECMC_DRV_SCALE_DENOM" "32768.0") # I/O range for ECMC_EC_ALIAS_DRV_VELO_SET
epicsEnvSet("ECMC_EC_DRV_CONTROL", "ec0.s9.driveControl01.0") # Ethercat entry for control word or bit output
epicsEnvSet("ECMC_EC_DRV_STATUS", "ec0.s9.driveStatus01.1") # Ethercat entry for status word or bit input
epicsEnvSet("ECMC_EC_DRV_VELOCITY", "ec0.s9.velocitySetpoint01") # Ethercat entry for velocity setpoint output
epicsEnvSet("ECMC_EC_DRV_REDUCE_TORQUE", "ec0.s9.driveControl01.2") # Ethercat entry for reduce torque output
epicsEnvSet("ECMC_EC_DRV_BRAKE", "") # Ethercat entry for brake output
epicsEnvSet("ECMC_DRV_BRAKE_OPEN_DLY_TIME", "0") # Brake timing parameter in cycles (default 1kHz)
epicsEnvSet("ECMC_DRV_BRAKE_CLOSE_AHEAD_TIME", "0") # Brake timing parameter in cycles (default 1kHz)
epicsEnvSet("ECMC_EC_DRV_RESET", "ec0.s9.driveControl01.1") # Reset
epicsEnvSet("ECMC_EC_DRV_ALARM_0", "ec0.s9.driveStatus01.3") # Error
epicsEnvSet("ECMC_EC_DRV_ALARM_1", "ec0.s9.driveStatus01.7") # Stall
epicsEnvSet("ECMC_EC_DRV_ALARM_2", "ec0.s9.driveStatus01.14") # Sync error
epicsEnvSet("ECMC_EC_DRV_WARNING", "ec0.s9.driveStatus01.2") # Warning
#Trajectory
epicsEnvSet("ECMC_VELO", "10.0")
epicsEnvSet("ECMC_JOG_VEL", "5")
epicsEnvSet("ECMC_JAR", "0.0") # JAR defaults to VELO/ACCL
epicsEnvSet("ECMC_ACCS_EGU_PER_S2", "10")
epicsEnvSet("ECMC_EMERG_DECEL", "100") # Emergency deceleration
#Homing
epicsEnvSet("ECMC_HOME_PROC", "3")
epicsEnvSet("ECMC_HOME_POS", "0.0")
epicsEnvSet("ECMC_HOME_VEL_TO", "5")
epicsEnvSet("ECMC_HOME_VEL_FRM", "4")
epicsEnvSet("ECMC_HOME_ACC", "21")
epicsEnvSet("ECMC_HOME_DEC", "100")
epicsEnvSet("ECMC_HOME_POS_MOVE_ENA", "0") # Enable move to position after successfull homing
epicsEnvSet("ECMC_HOME_POS_MOVE_TARG_POS","0") # Target position to go to after successfull homing
#Controller
epicsEnvSet("ECMC_CNTRL_KP", "15.0")
epicsEnvSet("ECMC_CNTRL_KI", "0.02")
epicsEnvSet("ECMC_CNTRL_KD", "0.0")
epicsEnvSet("ECMC_CNTRL_KFF", "1.0")
#Monitoring
# Switches
epicsEnvSet("ECMC_EC_MON_LOWLIM", "ec0.s1.binaryInput06.0") # Ethercat entry for low limit switch input
epicsEnvSet("ECMC_EC_MON_HIGHLIM", "ec0.s1.binaryInput05.0") # Ethercat entry for high limit switch inpuit
epicsEnvSet("ECMC_EC_MON_HOME_SWITCH", "ec0.s1.binaryInput07.0") # Ethercat entry for home switch input
epicsEnvSet("ECMC_EC_MON_EXT_INTERLOCK", "ec0.s0.ONE.0") # Ethercat entry for external interlock input
# Softlimits (disable with 0,0)
epicsEnvSet("ECMC_SOFT_LOW_LIM", "-130")
epicsEnvSet("ECMC_SOFT_HIGH_LIM", "20")
epicsEnvSet("ECMC_DXLM_ENABLE", "1")
# Position lag
epicsEnvSet("ECMC_MON_LAG_MON_TOL", "1.0")
epicsEnvSet("ECMC_MON_LAG_MON_TIME", "10")
epicsEnvSet("ECMC_MON_LAG_MON_ENA", "1")
# At target
epicsEnvSet("ECMC_MON_AT_TARGET_TOL", "0.1")
epicsEnvSet("ECMC_MON_AT_TARGET_TIME", "100")
epicsEnvSet("ECMC_MON_AT_TARGET_ENA", "1")
# Velocity
epicsEnvSet("ECMC_MON_VELO_MAX", "100.0")
epicsEnvSet("ECMC_MON_VELO_MAX_TRAJ_TIME","100")
epicsEnvSet("ECMC_MON_VELO_MAX_DRV_TIME", "200")
epicsEnvSet("ECMC_MON_VELO_MAX_ENA", "1")

25
iocsh/cfg/linear_2.sax Normal file
View File

@@ -0,0 +1,25 @@
############# Encoder
epicsEnvSet("ECMC_ENC_SOURCE", "0") # 0 Internal (from hardware), 1 from PLC
epicsEnvSet("ECMC_ENC_VELO_FILT_ENABLE", "1") # Enable velocity filter
epicsEnvSet("ECMC_ENC_VELO_FILT_SIZE", "20") # Encoder velocity Low pass filter size
############# Trajectory
epicsEnvSet("ECMC_TRAJ_SOURCE", "1") # 0 Internal (from hardware), 1 from PLC
epicsEnvSet("ECMC_TRAJ_VELO_FILT_ENABLE", "1") # Enable velocity filter
epicsEnvSet("ECMC_TRAJ_VELO_FILT_SIZE", "20") # Trajectory velocity Low pass filter size
############# Commands
epicsEnvSet("ECMC_CMD_FRM_OTHER_PLC_ENABLE", "1") # Allow commands from PLC
epicsEnvSet("ECMC_CMD_AXIS_PLC_ENABLE", "0") # Enable Axis PLC
# Each line below is appended to one single expression/source.
# Executed in sync with axis (before)
epicsEnvSet("ECMC_AXIS_EXPR_LINE_1", "var a:=1|")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_2", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_3", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_4", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_5", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_6", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_7", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_8", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_9", "")
epicsEnvSet("ECMC_AXIS_EXPR_LINE_10", "")

4430
iocsh/log2.log Normal file

File diff suppressed because it is too large Load Diff

View File

@@ -10,14 +10,47 @@ epicsEnvSet("IOC" ,"$(IOC="IOC_TEST")")
epicsEnvSet("ECMCCFG_INIT" ,"") #Only run startup once (auto at PSI, need call at ESS), variable set to "#" in startup.cmd
epicsEnvSet("SCRIPTEXEC" ,"$(SCRIPTEXEC="iocshLoad")")
require ecmccfg 7.0.1
require ecmccfg ruckig
# Epics Motor record driver that will be used:
epicsEnvShow(ECMC_MR_MODULE)
# run module startup.cmd (only needed at ESS PSI auto call at require)
$(ECMCCFG_INIT)$(SCRIPTEXEC) ${ecmccfg_DIR}startup.cmd, "IOC=$(IOC),ECMC_VER=7.0.1,MASTER_ID=-1"
$(ECMCCFG_INIT)$(SCRIPTEXEC) ${ecmccfg_DIR}startup.cmd, "IOC=$(IOC),ECMC_VER=ruckig"
##############################################################################
## Configure hardware:
# No EtherCAT hardware (in this example)..
$(SCRIPTEXEC) $(ecmccfg_DIR)ecmcMCU1021_coupler.cmd
# ADDITIONAL SETUP
# Set all outputs to feed switches
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput01,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput02,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput03,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput04,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput05,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput06,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput07,1)"
ecmcConfigOrDie "Cfg.WriteEcEntryIDString(${ECMC_EC_SLAVE_NUM_DIG_OUT},binaryOutput08,1)"
# END of ADDITIONAL SETUP
##############################################################################
## AXIS 1
#
epicsEnvSet("DEV", "$(IOC)")
$(SCRIPTEXEC) ($(ecmccfg_DIR)configureAxis.cmd, CONFIG=./cfg/linear_1.ax)
# Set external setpoints
$(SCRIPTEXEC) ($(ecmccfg_DIR)applyAxisSynchronization.cmd, CONFIG=./cfg/linear_1.sax)
##############################################################################
## AXIS 2
#
#epicsEnvSet("DEV", "$(IOC)")
$(SCRIPTEXEC) ($(ecmccfg_DIR)configureAxis.cmd, CONFIG=./cfg/linear_2.ax)
# Set external setpoints
$(SCRIPTEXEC) ($(ecmccfg_DIR)applyAxisSynchronization.cmd, CONFIG=./cfg/linear_2.sax)
##############################################################################
## Load plugin:
@@ -25,18 +58,18 @@ epicsEnvSet("PLUGIN_VER" ,"develop")
require ecmc_plugin_grbl $(PLUGIN_VER)
epicsEnvSet(ECMC_PLUGIN_FILNAME,"/home/pi/epics/base-7.0.5/require/${E3_REQUIRE_VERSION}/siteMods/ecmc_plugin_grbl/$(PLUGIN_VER)/lib/${EPICS_HOST_ARCH=linux-x86_64}/libecmc_plugin_grbl.so")
epicsEnvSet(ECMC_PLUGIN_CONFIG,"DBG_PRINT=1;X_AXIS=1;") # Only one option implemented in this plugin
epicsEnvSet(ECMC_PLUGIN_CONFIG,"DBG_PRINT=1;X_AXIS=1;AUTO_ENABLE=1;") # Only one option implemented in this plugin
${SCRIPTEXEC} ${ecmccfg_DIR}loadPlugin.cmd, "PLUGIN_ID=0,FILE=${ECMC_PLUGIN_FILNAME},CONFIG='${ECMC_PLUGIN_CONFIG}', REPORT=1"
epicsEnvUnset(ECMC_PLUGIN_FILNAME)
epicsEnvUnset(ECMC_PLUGIN_CONFIG)
ecmcGrblAddCommand("G1X0Y20F20");
ecmcGrblAddCommand("G2X0Y-20R20");
ecmcGrblAddCommand("G0X10Y10");
ecmcGrblAddCommand("G4P1");
ecmcGrblAddCommand("G1X10Y0F20");
ecmcGrblAddCommand("G1X100Y100F20");
ecmcGrblAddCommand("G1X0Y0F20");
#ecmcGrblAddCommand("G2X0Y-20R20");
#ecmcGrblAddCommand("G0X10Y10");
#ecmcGrblAddCommand("G4P1");
#ecmcGrblAddCommand("G1X10Y0F10");
#ecmcGrblAddCommand("G1X50Y50F10");
#ecmcGrblAddCommand("G1X0Y0F10");
#
#ecmcGrblAddCommand("$");
#