diff --git a/ecmc_plugin_grbl/ecmcGrbl.cpp b/ecmc_plugin_grbl/ecmcGrbl.cpp index c64db58..9bc6e65 100644 --- a/ecmc_plugin_grbl/ecmcGrbl.cpp +++ b/ecmc_plugin_grbl/ecmcGrbl.cpp @@ -20,7 +20,7 @@ #include "ecmcAsynPortDriver.h" #include "ecmcAsynPortDriverUtils.h" #include "epicsThread.h" -#include +#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() diff --git a/ecmc_plugin_grbl/ecmcGrbl.h b/ecmc_plugin_grbl/ecmcGrbl.h index 2f61d9e..7c35718 100644 --- a/ecmc_plugin_grbl/ecmcGrbl.h +++ b/ecmc_plugin_grbl/ecmcGrbl.h @@ -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 grblCommandBuffer_; epicsMutexId grblCommandBufferMutex_; bool firstCommandWritten_; + int autoEnableExecuted_; + int grblExeCycles_; }; #endif /* ECMC_GRBL_H_ */ diff --git a/ecmc_plugin_grbl/ecmcGrblDefs.h b/ecmc_plugin_grbl/ecmcGrblDefs.h index ca95e15..f9075fa 100644 --- a/ecmc_plugin_grbl/ecmcGrblDefs.h +++ b/ecmc_plugin_grbl/ecmcGrblDefs.h @@ -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 diff --git a/ecmc_plugin_grbl/ecmcPluginGrbl.c b/ecmc_plugin_grbl/ecmcPluginGrbl.c index ae29a37..bba78ce 100644 --- a/ecmc_plugin_grbl/ecmcPluginGrbl.c +++ b/ecmc_plugin_grbl/ecmcPluginGrbl.c @@ -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": Ecmc Axis id for use as grbl X axis, default = disabled (=-1).\n" + " "ECMC_PLUGIN_Y_AXIS_ID_OPTION_CMD": Ecmc Axis id for use as grbl Y axis, default = disabled (=-1).\n" + " "ECMC_PLUGIN_Z_AXIS_ID_OPTION_CMD": Ecmc Axis id for use as grbl Z axis, default = disabled (=-1).\n" + " "ECMC_PLUGIN_SPINDLE_AXIS_ID_OPTION_CMD": 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. diff --git a/grbl/grbl_spindle_control.c b/grbl/grbl_spindle_control.c index ca24afa..110b969 100644 --- a/grbl/grbl_spindle_control.c +++ b/grbl/grbl_spindle_control.c @@ -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 diff --git a/iocsh/0: b/iocsh/0: new file mode 100644 index 0000000..e69de29 diff --git a/iocsh/cfg/linear_1.ax b/iocsh/cfg/linear_1.ax new file mode 100644 index 0000000..be3ddfe --- /dev/null +++ b/iocsh/cfg/linear_1.ax @@ -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") diff --git a/iocsh/cfg/linear_1.sax b/iocsh/cfg/linear_1.sax new file mode 100644 index 0000000..863c806 --- /dev/null +++ b/iocsh/cfg/linear_1.sax @@ -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", "") diff --git a/iocsh/cfg/linear_2.ax b/iocsh/cfg/linear_2.ax new file mode 100644 index 0000000..a023c96 --- /dev/null +++ b/iocsh/cfg/linear_2.ax @@ -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") diff --git a/iocsh/cfg/linear_2.sax b/iocsh/cfg/linear_2.sax new file mode 100644 index 0000000..863c806 --- /dev/null +++ b/iocsh/cfg/linear_2.sax @@ -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", "") diff --git a/iocsh/log2.log b/iocsh/log2.log new file mode 100644 index 0000000..e51537c --- /dev/null +++ b/iocsh/log2.log @@ -0,0 +1,4430 @@ +registerChannelProviderLocal firstTime true +# +# Start at "2022-W03-Jan21-1134-14-CET" +# +# Version information: +# European Spallation Source ERIC : iocsh.bash (3.4.0-PID-2584) +# +# --->--> snip -->--> +# Please Use Version and other environment variables +# in order to report or debug this shell +# +# HOSTDISPLAY="" +# WINDOWID="" +# PWD="/home/pi/sources/e3-ecmc_plugin_grbl/ecmc_plugin_grbl-dev/iocsh" +# USER="pi" +# LOGNAME="pi" +# EPICS_HOST_ARCH="linux-arm" +# EPICS_BASE="/home/pi/epics/base-7.0.5" +# E3_REQUIRE_NAME="require" +# E3_REQUIRE_VERSION="3.4.0" +# E3_REQUIRE_LOCATION="/home/pi/epics/base-7.0.5/require/3.4.0" +# E3_REQUIRE_BIN="/home/pi/epics/base-7.0.5/require/3.4.0/bin" +# E3_REQUIRE_DB="/home/pi/epics/base-7.0.5/require/3.4.0/db" +# E3_REQUIRE_DBD="/home/pi/epics/base-7.0.5/require/3.4.0/dbd" +# E3_REQUIRE_INC="/home/pi/epics/base-7.0.5/require/3.4.0/include" +# E3_REQUIRE_LIB="/home/pi/epics/base-7.0.5/require/3.4.0/lib" +# EPICS_DRIVER_PATH="/home/pi/epics/base-7.0.5/require/3.4.0/siteMods:/home/pi/epics/base-7.0.5/require/3.4.0/siteApps" +# EPICS_CA_AUTO_ADDR_LIST="" +# EPICS_CA_ADDR_LIST="" +# PATH="/home/pi/epics/base-7.0.5/require/3.4.0/bin:/home/pi/epics/base-7.0.5/bin/linux-arm:/home/pi/berryconda3/bin:/home/pi/.local/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/local/games:/usr/games" +# --->--> snip -->--> +# +# Set REQUIRE_IOC for its internal PVs +epicsEnvSet REQUIRE_IOC "REQMOD:raspberrypi-2584" +# +# Enable an exit subroutine for sotfioc +dbLoadRecords "/home/pi/epics/base-7.0.5/db/softIocExit.db" "IOC=REQMOD:raspberrypi-2584" +# +# Set E3_IOCSH_TOP for the absolute path where iocsh.bash is executed. +epicsEnvSet E3_IOCSH_TOP "/home/pi/sources/e3-ecmc_plugin_grbl/ecmc_plugin_grbl-dev/iocsh" +# +# +# Load require module, which has the version 3.4.0 +# +dlload /home/pi/epics/base-7.0.5/require/3.4.0/lib/linux-arm/librequire.so +dbLoadDatabase /home/pi/epics/base-7.0.5/require/3.4.0/dbd/require.dbd +require_registerRecordDeviceDriver +Loading module info records for require +# +# Set E3_CMD_TOP for the absolute path where test.script exists +epicsEnvSet E3_CMD_TOP "/home/pi/sources/e3-ecmc_plugin_grbl/ecmc_plugin_grbl-dev/iocsh" +# +iocshLoad 'test.script','' +############################################################################## +## Example: Demo of ecmc SocketCAN plugin +## https://github.com/anderssandstrom/e3-ecmc_plugin_socketcan +## +## The plugin exposes: +## +## Initiation: +epicsEnvSet("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" ,"iocshLoad") +require ecmccfg ruckig +Module ecmccfg version ruckig found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/lib/linux-arm/libecmccfg.so +Loaded ecmccfg version ruckig +Loading dbd file /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/dbd/ecmccfg.dbd +Calling function ecmccfg_registerRecordDeviceDriver +Loading module info records for ecmccfg +# Epics Motor record driver that will be used: +epicsEnvShow(ECMC_MR_MODULE) +ECMC_MR_MODULE is not an environment variable. +# run module startup.cmd (only needed at ESS PSI auto call at require) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/startup.cmd, "IOC=IOC_TEST,ECMC_VER=ruckig" +#============================================================================== +# startup.cmd +on error halt +require ecmc "ruckig" +Module ecmc version ruckig found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc/ruckig/ +Module ecmc depends on asyn 4.41.0 +Module asyn version 4.41.0 found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/asyn/4.41.0/ +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/asyn/4.41.0/lib/linux-arm/libasyn.so +Loaded asyn version 4.41.0 +Loading dbd file /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/asyn/4.41.0/dbd/asyn.dbd +Calling function asyn_registerRecordDeviceDriver +Loading module info records for asyn +Module ecmc depends on exprtk 1.2.1 +Module exprtk version 1.2.1 found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/exprtk/1.2.1/ +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/exprtk/1.2.1/lib/linux-arm/libexprtk.so +Loaded exprtk version 1.2.1 +exprtk has no dbd file +Loading module info records for exprtk +Module ecmc depends on motor develop +Module motor version develop found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/motor/develop/ +Module motor depends on asyn 4.41.0 +Module asyn version 4.41.0 already loaded +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/motor/develop/lib/linux-arm/libmotor.so +Loaded motor version develop +Loading dbd file /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/motor/develop/dbd/motor.dbd +Calling function motor_registerRecordDeviceDriver +Loading module info records for motor +Module ecmc depends on ruckig 1.0.0 +Module ruckig version 1.0.0 found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ruckig/1.0.0/ +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ruckig/1.0.0/lib/linux-arm/libruckig.so +Loaded ruckig version 1.0.0 +ruckig has no dbd file +Loading module info records for ruckig +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc/ruckig/lib/linux-arm/libecmc.so +Loaded ecmc version ruckig +Loading dbd file /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc/ruckig/dbd/ecmc.dbd +Calling function ecmc_registerRecordDeviceDriver +Loading module info records for ecmc +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'ecmcMotorRecord'='EthercatMC'", "require EthercatMC 3.0.2 # Using EthercatMC motor record support.","# Using ecmcMotorRecord motor record support.") +# Using ecmcMotorRecord motor record support. +epicsEnvUnset(ECMC_EXE_CMD) +epicsEnvSet("ECMC_CONFIG_ROOT", "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/") +epicsEnvSet("ECMC_CONFIG_DB", "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/db") +epicsEnvSet("SCRIPTEXEC", "iocshLoad") +epicsEnvSet("SM_PREFIX", "IOC_TEST:") # colon added since IOC is _not_ PREFIX +epicsEnvSet("ECMC_PROC_HOOK", "") +epicsEnvSet(ECMC_MODE, FULL) +ecmcEpicsEnvSetCalcTernary(ECMC_SUPPORT_MOTION, "'FULL'!='DAQ'","","# MODE == DAQ, DISABLING MOTION.") +epicsEnvShow(ECMC_SUPPORT_MOTION) +ECMC_SUPPORT_MOTION= +ecmcEpicsEnvSetCalcTernary(ECMC_USE_MOTOR_RECORD, "'FULL'=='FULL'","","# MODE != FULL, DISABLING MOTOR RECORD.") +epicsEnvShow(ECMC_USE_MOTOR_RECORD) +ECMC_USE_MOTOR_RECORD= +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/initAll.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/initAll.cmd" +#============================================================================== +# initAll.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/init.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/init.cmd +#============================================================================== +# init.cmd +epicsEnvSet("ECMC_ASYN_TIMEOUT", 1) # Asyn timeout +epicsEnvSet("ECMC_ASYN_ADDR", 0) # Asyn Address +epicsEnvSet("ECMC_MOTOR_PORT", "NOT SET") +epicsEnvSet("ECMC_ASYN_PORT", "NOT SET") +epicsEnvSet("ECMC_PREFIX", "NOT SET") +epicsEnvSet("ECMC_GEN_EC_RECORDS", "NOT SET") +epicsEnvSet("ECMC_GEN_AX_RECORDS", "NOT SET") +epicsEnvSet("ECMC_EC_AXIS_HEALTH", "NOT SET") +epicsEnvSet("ECMC_PLC_SAMPLE_RATE_MS", "NOT SET") +epicsEnvSet("ECMC_TSE", -2) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/initAxis.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/initAxis.cmd" +#============================================================================== +# initAxis.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_unset.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_unset.cmd" +#============================================================================== +# ecmc_axis_unset.cmd +epicsEnvUnset(ECMC_AXISCONFIG) +epicsEnvUnset(ECMC_AXISFIELDINIT) +epicsEnvUnset(ECMC_PREC) +epicsEnvUnset(ECMC_EGU) +epicsEnvUnset(ECMC_DESC) +epicsEnvUnset(ECMC_R) +epicsEnvUnset(ECMC_MOTOR_NAME) +epicsEnvUnset(ECMC_EC_AXIS_HEALTH) +epicsEnvUnset(ECMC_MOD_RANGE) +epicsEnvUnset(ECMC_MOD_TYPE) +epicsEnvUnset(ECMC_EMERG_DECEL) +epicsEnvUnset(ECMC_VELO) +epicsEnvUnset(ECMC_ACCL) +epicsEnvUnset(ECMC_ACCS_EGU_PER_S2) +epicsEnvUnset(ECMC_HOME_VEL_TO) +epicsEnvUnset(ECMC_HOME_VEL_FRM) +epicsEnvUnset(ECMC_CNTRL_KP) +epicsEnvUnset(ECMC_CNTRL_KI) +epicsEnvUnset(ECMC_CNTRL_KD) +epicsEnvUnset(ECMC_CNTRL_KFF) +epicsEnvUnset(ECMC_EC_ENC_ACTPOS) +epicsEnvUnset(ECMC_EC_ENC_LATCHPOS) +epicsEnvUnset(ECMC_EC_ENC_LATCH_CONTROL) +epicsEnvUnset(ECMC_EC_ENC_LATCH_STATUS) +epicsEnvUnset(ECMC_HOME_LATCH_COUNT_OFFSET) +epicsEnvUnset(ECMC_ENC_SCALE_DENOM) +epicsEnvUnset(ECMC_ENC_SCALE_NUM) +epicsEnvUnset(ECMC_ENC_TYPE) +epicsEnvUnset(ECMC_ENC_BITS) +epicsEnvUnset(ECMC_ENC_ABS_BITS) +epicsEnvUnset(ECMC_ENC_ABS_OFFSET) +epicsEnvUnset(ECMC_ENC_VEL_FILTER_SIZE) +epicsEnvUnset(ECMC_ENC_POS_FILTER_SIZE) +epicsEnvUnset(ECMC_ENC_POS_FILTER_ENABLE) +epicsEnvUnset(ECMC_EC_ENC_RESET) +epicsEnvUnset(ECMC_EC_ENC_ALARM_0) +epicsEnvUnset(ECMC_EC_ENC_ALARM_1) +epicsEnvUnset(ECMC_EC_ENC_ALARM_2) +epicsEnvUnset(ECMC_EC_ENC_WARNING) +epicsEnvUnset(ECMC_EC_DRV_CONTROL) +epicsEnvUnset(ECMC_EC_DRV_STATUS) +epicsEnvUnset(ECMC_EC_DRV_VELOCITY) +epicsEnvUnset(ECMC_EC_DRV_BRAKE) +epicsEnvUnset(ECMC_EC_DRV_REDUCE_TORQUE) +epicsEnvUnset(ECMC_EC_DRV_RESET) +epicsEnvUnset(ECMC_EC_DRV_ALARM_0) +epicsEnvUnset(ECMC_EC_DRV_ALARM_1) +epicsEnvUnset(ECMC_EC_DRV_ALARM_2) +epicsEnvUnset(ECMC_EC_DRV_WARNING) +epicsEnvUnset(ECMC_DRV_SCALE_DENOM) +epicsEnvUnset(ECMC_DRV_SCALE_NUM) +epicsEnvUnset(ECMC_DRV_BRAKE_OPEN_DLY_TIME) +epicsEnvUnset(ECMC_DRV_BRAKE_CLOSE_AHEAD_TIME) +epicsEnvUnset(ECMC_SOFT_LOW_LIM) +epicsEnvUnset(ECMC_DXLM_ENABLE) +epicsEnvUnset(ECMC_SOFT_HIGH_LIM) +epicsEnvUnset(ECMC_DXLM_ENABLE) +epicsEnvUnset(ECMC_EC_MON_LOWLIM) +epicsEnvUnset(ECMC_EC_MON_HIGHLIM) +epicsEnvUnset(ECMC_EC_MON_HOME_SWITCH) +epicsEnvUnset(ECMC_EC_MON_EXT_INTERLOCK) +epicsEnvUnset(ECMC_MON_AT_TARGET_TOL) +epicsEnvUnset(ECMC_MON_AT_TARGET_TIME) +epicsEnvUnset(ECMC_MON_AT_TARGET_ENA) +epicsEnvUnset(ECMC_MON_LAG_MON_TOL) +epicsEnvUnset(ECMC_MON_LAG_MON_TIME) +epicsEnvUnset(ECMC_MON_LAG_MON_ENA) +epicsEnvUnset(ECMC_MON_VELO_MAX) +epicsEnvUnset(ECMC_MON_VELO_MAX_ENA) +epicsEnvUnset(ECMC_MON_VELO_MAX_DRV_TIME) +epicsEnvUnset(ECMC_MON_VELO_MAX_TRAJ_TIME) +epicsEnvUnset(ECMC_JOG_VEL) +epicsEnvUnset(ECMC_JAR) +epicsEnvUnset(ECMC_HOME_PROC) +epicsEnvUnset(ECMC_HOME_POS) +epicsEnvUnset(ECMC_HOME_ACC) +epicsEnvUnset(ECMC_HOME_DEC) +epicsEnvUnset(ECMC_DRV_TYPE) +epicsEnvUnset(ECMC_VELO) +epicsEnvUnset(ECMC_SOFT_LOW_LIM) +epicsEnvUnset(ECMC_SOFT_HIGH_LIM) +epicsEnvUnset(ECMC_HOME_POS_MOVE_ENA) +epicsEnvUnset(ECMC_HOME_POS_MOVE_TARG_POS) +epicsEnvUnset(ECMC_TRAJ_TYPE) +epicsEnvUnset(ECMC_JERK) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync_unset.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync_unset.cmd" +#============================================================================== +# ecmc_axis_sync_unset.cmd +epicsEnvUnset(ECMC_CMD_FRM_OTHER_PLC_ENABLE) +epicsEnvUnset(ECMC_CMD_AXIS_PLC_ENABLE) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_1) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_2) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_3) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_4) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_5) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_6) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_7) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_8) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_9) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_10) +epicsEnvUnset(ECMC_ENC_VELO_FILT_SIZE) +epicsEnvUnset(ECMC_ENC_VELO_FILT_ENABLE) +epicsEnvUnset(ECMC_ENC_SOURCE) +epicsEnvUnset(ECMC_TRAJ_VELO_FILT_SIZE) +epicsEnvUnset(ECMC_TRAJ_VELO_FILT_ENABLE) +epicsEnvUnset(ECMC_TRAJ_SOURCE) +epicsEnvSet("ECMC_EGU", "mm") +epicsEnvSet("ECMC_PREC", 3) +epicsEnvSet("ECMC_AXISFIELDINIT", "") # Extra field init to motor record +epicsEnvSet("ECMC_AXISCONFIG", 2022/01/21 11:34:14.969 +ECMC Initializes............. +2022/01/21 11:34:14.970 ESS Open Source EtherCAT Motion Control Epics Module2022/01/21 11:34:14.970 +Mode: Configuration +2022/01/21 11:34:14.970 OK +2022/01/21 11:34:14.970 OK +2022/01/21 11:34:14.971 OK +2022/01/21 11:34:14.973 OK +2022/01/21 11:34:14.994 OK +2022/01/21 11:34:14.994 OK +2022/01/21 11:34:14.994 OK + "") # Extra parameters to driver +############################################################ +############# ASYN Configuration: +epicsEnvSet("ECMC_MOTOR_PORT" "MCU1") +epicsEnvSet("ECMC_ASYN_PORT" "MC_CPU1") +epicsEnvSet("ECMC_PREFIX" "IOC_TEST:") +ecmcAsynPortDriverConfigure(MC_CPU1,1000,0,0,100) +ecmcAsynPortDriverConfigure: portName = MC_CPU1, paramTableSize = 1000, disableAutoConnect = 0, priority = 0, defaultSampleRateMS = 100.000000 +asynOctetSetOutputEos(MC_CPU1, -1, ";\n") +asynOctetSetInputEos(MC_CPU1, -1, ";\n") +asynSetTraceMask(MC_CPU1, -1, 0x41) +asynSetTraceIOMask(MC_CPU1, -1, 6) +asynSetTraceInfoMask(MC_CPU1, -1, 1) +ecmcMotorRecordCreateController(MCU1, MC_CPU1, "64", 200, 1000, "") +############################################################ +############# Misc settings: +# Disable function call trace printouts +ecmcConfigOrDie "Cfg.SetEnableFuncCallDiag(0)" +# Disable on change printouts from objects (enable for easy logging) +ecmcConfigOrDie "Cfg.SetTraceMaskBit(15,0)" +# Choose to generate EPICS-records for EtherCAT-entries +# (For records use ECMC_GEN_EC_RECORDS="-records" otherwise ECMC_GEN_EC_RECORDS="") +epicsEnvSet("ECMC_GEN_EC_RECORDS", "-records") +# Choose to generate EPICS-records for ax-entries (PosAct, SetPos,..) +# (For records use ECMC_GEN_AX_RECORDS="-records" otherwise ECMC_GEN_AX_RECORDS="") +epicsEnvSet("ECMC_GEN_AX_RECORDS", "-records") +# suffix for pva enabled scripts, templates and substitutions +ecmcEpicsEnvSetCalcTernary(ECMC_PVA, "0", "Pva","") +# Set EtherCAT frequency (defaults to 1000) +ecmcConfigOrDie "Cfg.SetSampleRate(1000)" +epicsEnvSet("ECMC_EC_SAMPLE_RATE" , 1000) +ecmcEpicsEnvSetCalc("ECMC_EC_SAMPLE_RATE_MS" ,1000/1000) +# Update records in 10ms (100Hz) for FULL MODE and in EC_RATE for DAQ mode +ecmcEpicsEnvSetCalcTernary(ECMC_SAMPLE_RATE_MS, "'FULL'=='DAQ'","1","10") +epicsEnvSet("ECMC_P_SCRIPT", "mXsXXX") +ecmcEpicsEnvSetCalcTernary(ECMC_MASTER_CMD, "0>=0", "","#- ") + ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addMaster.cmd",1) + iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addMaster.cmd", "MASTER_ID=0" +#=============================================================================== +# addMaster.cfg +epicsEnvSet("ECMC_EC_MASTER_ID" "0") +# Claim master +ecmcConfigOrDie "Cfg.EcSetMaster(0)" +epicsEnvSet("ECMC_EC_MASTER_ID" ,0) +epicsEnvSet("ECMC_TMP_DIR", "/tmp/IOC_TEST/EcMaster_0/") +system "mkdir -p /tmp/IOC_TEST/EcMaster_0/" +epicsEnvSet("ECMC_TMP_DIR", "/tmp/IOC_TEST/EcMaster_0/") +system "mkdir -p /tmp/IOC_TEST/EcMaster_0/" +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/setDiagnostics.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/setDiagnostics.cmd +#============================================================================== +# setDiagnostics.cmd +ecmcConfigOrDie "Cfg.EcSetDiagnostics(1)" +ecmcConfigOrDie "Cfg.EcEnablePrintouts(0)" +ecmcConfigOrDie "Cfg.EcSetDomainFailedCyclesLimit(100)" +epicsEnvSet("ECMCCFG_INIT" ,"#") +############################################################################## +## Configure hardware: +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcMCU1021_coupler.cmd +############################################################ +############# MCU1021: +#Configure EK1100 coupler terminal +epicsEnvSet(ECMC_EC_SLAVE_NUM,0) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=0, HW_DESC=EK1100" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "0") +epicsEnvSet("HW_DESC", "EK1100") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEK1100.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEK1100.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EK112022/01/21 11:34:14.996 OK +2022/01/21 11:34:14.997 OK +2022/01/21 11:34:15.004 OK +2022/01/21 11:34:15.005 OK +2022/01/21 11:34:15.005 OK +2022/01/21 11:34:15.006 OK +2022/01/21 11:34:15.006 OK +00") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x044c2c52") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,0,0x2,0x044c2c52)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "0>0", "","#- ") +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +ecmcConfigOrDie "Cfg.EcAddSlave(0,0,0x2,0x044c2c52)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=0,HWTYPE=EK1100" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "0","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s000") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s000-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEK1100.substitutions,ECMC_P=IOC_TEST:m0s000-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEK1100.substitutions,1,1) +dbLoadTemplate(ecmcEK1100.substitutions,"ECMC_P=IOC_TEST:m0s000-,ECMC_G=IOC_TEST:m0s000,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=0,HWTYPE=EK1100,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s000-,ECMC_G=IOC_TEST:m0s000" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s000-,ECMC_G=IOC_TEST:m0s000,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=0,HWTYPE=EK1100,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "0+1","%d") +#Configure EL1018 digital input terminal +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "0+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=1, HW_DESC=EL1018" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "1") +epicsEnvSet("HW_DESC", "EL1018") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL1018.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL1018.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL1018") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x03fa3052") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,1,0x2,0x03fa3052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "0>0", "","#- ") +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEX1008.cmd +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a00,0x6000,0x1,B1,binaryInput01)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a01,0x6010,0x1,B1,binaryInput02)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a02,0x6020,0x1,B1,binaryInput03)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a03,0x6030,0x1,B1,binaryInput04)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a04,0x6040,0x1,B1,binaryI2022/01/21 11:34:15.006 OK +2022/01/21 11:34:15.006 OK +2022/01/21 11:34:15.006 OK +2022/01/21 11:34:15.006 OK +2022/01/21 11:34:15.014 OK +2022/01/21 11:34:15.016 OK +2022/01/21 11:34:15.016 OK +2022/01/21 11:34:15.016 OK +2022/01/21 11:34:15.016 OK +2022/01/21 11:34:15.017 OK +2022/01/21 11:34:15.017 OK +2022/01/21 11:34:15.017 OK +nput05)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a05,0x6050,0x1,B1,binaryInput06)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a06,0x6060,0x1,B1,binaryInput07)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(1,0x2,0x03fa3052,2,0,0x1a07,0x6070,0x1,B1,binaryInput08)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=1,HWTYPE=EL1018" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "1","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s001") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s001-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL1018.substitutions,ECMC_P=IOC_TEST:m0s001-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL1018.substitutions,1,1) +dbLoadTemplate(ecmcEL1018.substitutions,"ECMC_P=IOC_TEST:m0s001-,ECMC_G=IOC_TEST:m0s001,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=1,HWTYPE=EL1018,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s001-,ECMC_G=IOC_TEST:m0s001" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s001-,ECMC_G=IOC_TEST:m0s001,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=1,HWTYPE=EL1018,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "1+1","%d") +#Configure EL2808 digital output terminal +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "1+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=2, HW_DESC=EL2808" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "2") +epicsEnvSet("HW_DESC", "EL2808") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL2808.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL2808.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL2808") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x0af83052") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,2,0x2,0x0af83052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "0>0", "","#- ") +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEX2008.cmd +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1600,0x7000,0x1,B1,binaryOutput01)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1601,0x7010,0x1,B1,binaryOutput02)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1602,0x7020,0x1,B1,binaryOutput03)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1603,0x7030,0x1,B1,binaryOutput04)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1604,0x7040,0x1,B1,binaryOutput05)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1605,0x7050,0x1,B1,binaryOutput06)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af83052,1,0,0x1606,0x7060,0x1,B1,binaryOutput07)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(2,0x2,0x0af8302022/01/21 11:34:15.017 OK +2022/01/21 11:34:15.027 OK +2022/01/21 11:34:15.112 OK +2022/01/21 11:34:15.202 14385 +2022/01/21 11:34:15.203 OK +2022/01/21 11:34:15.203 OK +2022/01/21 11:34:15.203 OK +2022/01/21 11:34:15.203 OK +2022/01/21 11:34:15.203 OK +52,1,0,0x1607,0x7070,0x1,B1,binaryOutput08)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=2,HWTYPE=EL2808" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "2","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s002") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s002-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL2808.substitutions,ECMC_P=IOC_TEST:m0s002-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL2808.substitutions,1,1) +dbLoadTemplate(ecmcEL2808.substitutions,"ECMC_P=IOC_TEST:m0s002-,ECMC_G=IOC_TEST:m0s002,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=2,HWTYPE=EL2808,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s002-,ECMC_G=IOC_TEST:m0s002" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s002-,ECMC_G=IOC_TEST:m0s002,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=2,HWTYPE=EL2808,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "2+1","%d") +# Save the slave number for later +epicsEnvSet("ECMC_EC_SLAVE_NUM_DIG_OUT", "2") +#Configure EL5101 Incremental Encoder Interface +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "2+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=3, HW_DESC=EL5101" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "3") +epicsEnvSet("HW_DESC", "EL5101") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL5101.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL5101.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL5101") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x13ed3052") +ecmcFileExist(/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd,1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd "RESET=true" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,3,0x2,0x13ed3052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "true>0", "","#- ") +ecmcConfigOrDie "Cfg.EcWriteSdo(3,0x1011,0x1,1684107116,4)" +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +ecmcConfig "EcReadSdo(3,0x100a,0x0,2)" +ecmcEpicsEnvSetCalc("ECMC_EC_SLAVE_FW", "14385", "0x%04x") +# Firmware version: 0x3831 +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +ecmcConfigOrDie "Cfg.EcAddEntryComplete(3,0x2,0x13ed3052,1,2,0x1600,0x7000,0x01,8,encoderControl01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(3,0x2,0x13ed3052,1,2,0x1600,0x7000,0x02,16,encoderValue01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(3,0x2,0x13ed3052,2,3,0x1a03,0x6010,0x00,16,encoderStatus01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(3,0x2,0x13ed3052,2,3,0x1a03,0x6010,0x10,16,positionActual01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(3,0x2,0x13ed3052,2,3,0x1a03,0x6010,0x20,16,encoderLatchPostion01)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +2022/01/21 11:34:15.211 OK +2022/01/21 11:34:15.282 OK +2022/01/21 11:34:15.372 14385 +2022/01/21 11:34:15.373 OK +2022/01/21 11:34:15.373 OK +2022/01/21 11:34:15.373 OK +2022/01/21 11:34:15.373 OK +2022/01/21 11:34:15.373 OK +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=3,HWTYPE=EL5101" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "3","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s003") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s003-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL5101.substitutions,ECMC_P=IOC_TEST:m0s003-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL5101.substitutions,1,1) +dbLoadTemplate(ecmcEL5101.substitutions,"ECMC_P=IOC_TEST:m0s003-,ECMC_G=IOC_TEST:m0s003,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=3,HWTYPE=EL5101,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s003-,ECMC_G=IOC_TEST:m0s003" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s003-,ECMC_G=IOC_TEST:m0s003,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=3,HWTYPE=EL5101,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "3+1","%d") +#Configure EL5101 Incremental Encoder Interface +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "3+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=4, HW_DESC=EL5101" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "4") +epicsEnvSet("HW_DESC", "EL5101") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL5101.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL5101.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL5101") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x13ed3052") +ecmcFileExist(/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd,1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd "RESET=true" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,4,0x2,0x13ed3052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "true>0", "","#- ") +ecmcConfigOrDie "Cfg.EcWriteSdo(4,0x1011,0x1,1684107116,4)" +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +ecmcConfig "EcReadSdo(4,0x100a,0x0,2)" +ecmcEpicsEnvSetCalc("ECMC_EC_SLAVE_FW", "14385", "0x%04x") +# Firmware version: 0x3831 +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +ecmcConfigOrDie "Cfg.EcAddEntryComplete(4,0x2,0x13ed3052,1,2,0x1600,0x7000,0x01,8,encoderControl01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(4,0x2,0x13ed3052,1,2,0x1600,0x7000,0x02,16,encoderValue01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(4,0x2,0x13ed3052,2,3,0x1a03,0x6010,0x00,16,encoderStatus01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(4,0x2,0x13ed3052,2,3,0x1a03,0x6010,0x10,16,positionActual01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(4,0x2,0x13ed3052,2,3,0x1a03,0x6010,0x20,16,encoderLatchPostion01)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=4,HWTYPE=EL5101" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "4"2022/01/21 11:34:15.381 OK +2022/01/21 11:34:15.383 OK +2022/01/21 11:34:15.383 OK +,"%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s004") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s004-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL5101.substitutions,ECMC_P=IOC_TEST:m0s004-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL5101.substitutions,1,1) +dbLoadTemplate(ecmcEL5101.substitutions,"ECMC_P=IOC_TEST:m0s004-,ECMC_G=IOC_TEST:m0s004,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=4,HWTYPE=EL5101,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s004-,ECMC_G=IOC_TEST:m0s004" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s004-,ECMC_G=IOC_TEST:m0s004,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=4,HWTYPE=EL5101,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "4+1","%d") +# Configure EL9505 Power supply terminal 5V +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "4+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=5, HW_DESC=EL9505" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "5") +epicsEnvSet("HW_DESC", "EL9505") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL9505.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL9505.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL9505") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x25213052") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,5,0x2,0x25213052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "0>0", "","#- ") +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +ecmcConfigOrDie "Cfg.EcAddEntryComplete(5,0x2,0x25213052,2,0,0x1a00,0x6000,0x1,1,powerOk01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(5,0x2,0x25213052,2,0,0x1a00,0x6000,0x2,1,overload01)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=5,HWTYPE=EL9505" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "5","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s005") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s005-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL9505.substitutions,ECMC_P=IOC_TEST:m0s005-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL9505.substitutions,1,1) +dbLoadTemplate(ecmcEL9505.substitutions,"ECMC_P=IOC_TEST:m0s005-,ECMC_G=IOC_TEST:m0s005,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=5,HWTYPE=EL9505,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.42022/01/21 11:34:15.392 OK +2022/01/21 11:34:15.393 OK +2022/01/21 11:34:15.393 OK +2022/01/21 11:34:15.393 OK +2022/01/21 11:34:15.393 OK +2022/01/21 11:34:15.394 OK +2022/01/21 11:34:15.394 OK +2022/01/21 11:34:15.394 OK +2022/01/21 11:34:15.394 OK +.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s005-,ECMC_G=IOC_TEST:m0s005" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s005-,ECMC_G=IOC_TEST:m0s005,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=5,HWTYPE=EL9505,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "5+1","%d") +# Configure EL1252 digital input terminal +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "5+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd, "SLAVE_ID=6, HW_DESC=EL1252" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "6") +epicsEnvSet("HW_DESC", "EL1252") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL1252.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL1252.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL1252") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x04e43052") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,6,0x2,0x04e43052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "0>0", "","#- ") +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEX1002.cmd +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,0,0x1a00,0x6000,0x1,B1,binaryInput01)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,0,0x1a01,0x6010,0x1,B1,binaryInput02)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,1,0x1a13,0x1d09,0xae,U8,status01)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,1,0x1a13,0x1d09,0xaf,U8,status02)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,1,0x1a13,0x1d09,0xb0,U64,timestampLatchPositive01)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,1,0x1a13,0x1d09,0xb8,U64,timestampLatchNegative01)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,1,0x1a13,0x1d09,0xc0,U64,timestampLatchPositive02)" +ecmcConfigOrDie "Cfg.EcAddEntryDT(6,0x2,0x04e43052,2,1,0x1a13,0x1d09,0xc8,U64,timestampLatchNegative02)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=6,HWTYPE=EL1252" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "6","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s006") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s006-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL1252.substitutions,ECMC_P=IOC_TEST:m0s006-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL1252.substitutions,1,1) +dbLoadTemplate(ecmcEL1252.substitutions,"ECMC_P=IOC_TEST:m0s006-,ECMC_G=IOC_TEST:m0s006,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=6,HWTYPE=EL1252,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s006-,ECMC_G=IOC_TEST:m0s006" +#=========================================================================2022/01/21 11:34:15.403 OK +2022/01/21 11:34:15.522 OK +2022/01/21 11:34:15.602 12848 +2022/01/21 11:34:15.604 OK +2022/01/21 11:34:15.605 OK +2022/01/21 11:34:15.605 OK +2022/01/21 11:34:15.605 OK +2022/01/21 11:34:15.606 OK +2022/01/21 11:34:15.606 OK +2022/01/21 11:34:15.606 OK +2022/01/21 11:34:15.606 OK +2022/01/21 11:34:15.607 OK +2022/01/21 11:34:15.607 OK +2022/01/21 11:34:15.607 OK +2022/01/21 11:34:15.607 OK +===== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s006-,ECMC_G=IOC_TEST:m0s006,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=6,HWTYPE=EL1252,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "6+1","%d") +# Configure EL9410 Power supply with refresh of E-Bus. +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "6+1") +#${SCRIPTEXEC} ${ecmccfg_DIR}addSlave.cmd, "SLAVE_ID=${ECMC_EC_SLAVE_NUM}, HW_DESC=EL9410" +#Configure EL7037 stepper drive terminal, motor 1 +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "7+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/configureSlave.cmd, "SLAVE_ID=8, HW_DESC=EL7037, CONFIG=-Motor-Nanotec-ST4118L1804-B" +#============================================================================== +# configureSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "8") +epicsEnvSet("HW_DESC", "EL7037") +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd "SLAVE_ID=8, HW_DESC=EL7037, NELM=1" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "8") +epicsEnvSet("HW_DESC", "EL7037") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL7037") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x1b7d3052") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd "RESET=true" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,8,0x2,0x1b7d3052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "true>0", "","#- ") +ecmcConfigOrDie "Cfg.EcWriteSdo(8,0x1011,0x1,1684107116,4)" +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +ecmcConfig "EcReadSdo(8,0x100a,0x0,2)" +ecmcEpicsEnvSetCalc("ECMC_EC_SLAVE_FW", "12848", "0x%04x") +# Firmware version: 0x3230 +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEX70XX.cmd +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,1,2,0x1600,0x7000,0x01,16,encoderControl01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,1,2,0x1600,0x7000,0x11,16,encoderValue01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,1,2,0x1602,0x7010,0x1,16,driveControl01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,1,2,0x1604,0x7010,0x21,16,1,velocitySetpoint01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,2,3,0x1a00,0x6000,0x0,16,encoderStatus01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,2,3,0x1a00,0x6000,0x11,16,positionActual01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,2,3,0x1a00,0x6000,0x12,16,encoderLatchPostion01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(8,0x2,0x1b7d3052,2,3,0x1a03,0x6010,0x1,16,driveStatus01)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8012,0x5,1,1)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8012,0xA,1,1)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8012,0x8,1,1)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8012,0x9,0,1)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=8,HWTYPE=EL7037" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "8","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s008") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s008-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTern2022/01/21 11:34:15.626 OK +2022/01/21 11:34:15.626 OK +2022/01/21 11:34:15.627 OK +2022/01/21 11:34:15.627 OK +2022/01/21 11:34:15.627 OK +2022/01/21 11:34:15.627 OK +ary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL7037.substitutions,ECMC_P=IOC_TEST:m0s008-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL7037.substitutions,1,1) +dbLoadTemplate(ecmcEL7037.substitutions,"ECMC_P=IOC_TEST:m0s008-,ECMC_G=IOC_TEST:m0s008,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=8,HWTYPE=EL7037,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s008-,ECMC_G=IOC_TEST:m0s008" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s008-,ECMC_G=IOC_TEST:m0s008,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=8,HWTYPE=EL7037,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "8+1","%d") +# apply config ${CONFIG} for ${HW_DESC} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037-Motor-Nanotec-ST4118L1804-B.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037-Motor-Nanotec-ST4118L1804-B.cmd "" +epicsEnvSet(I_MAX_MA_LOCAL,"1500") +epicsEnvSet(I_RUN_MA_LOCAL,1000) +epicsEnvSet(I_STDBY_MA_LOCAL,500) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/chkValidCurrentSetOrDie.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/chkValidCurrentSetOrDie.cmd "I_RUN_MA=1000,I_STDBY_MA=500,I_MAX_MA=1500" +#============================================================================== +# chkValidCurrentSetOrDie.cmd +# Ensure running current is below max current otherwise exit +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "1000>1500 or 1000<=0", "ecmcExit Error: Run current setpoint to high or negative...","# Run current setting OK (1000)...") +# Result: +# Run current setting OK (1000)... +epicsEnvUnset(ECMC_EXE_CMD) +# Ensure standby current is below max current otherwise exit +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "500>1500 or 500<0", "ecmcExit Error: Standby current setpoint to high or negative...","# Standby current setting OK (500)...") +# Result: +# Standby current setting OK (500)... +epicsEnvUnset(ECMC_EXE_CMD) +# Ensure standby current is below run current otherwise exit +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "500>1000", "ecmcExit Error: Standby current higher than run current...","# Standby current and run current setting OK (500<1000)...") +# Result: +# Standby current and run current setting OK (500<1000)... +epicsEnvUnset(ECMC_EXE_CMD) +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8010,0x1,1000,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8010,0x2,500,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8010,0x3,2400,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8010,0x4,175,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8010,0x6,200,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(8,0x8010,0xA,330,2)" +epicsEnvUnset("I_RUN_MA_LOCAL") +epicsEnvUnset("I_STDBY_MA_LOCAL") +epicsEnvUnset("I_MAX_MA_LOCAL") +#Configure EL7037 stepper drive terminal, motor 2 +ecmcEpicsEnvSetCalc(ECMC_EC_SLAVE_NUM, "8+1") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/configureSlave.cmd, "SLAVE_ID=9, HW_DESC=EL7037, CONFIG=-Motor-Nanotec-ST4118L1804-B" +#============================================================================== +# configureSlave.cmd +epicsEnvSet("ECMC_EC_SLAVE_NUM", "9") +epicsEnvSet("HW_DESC", "EL7037") +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addSlave.cmd "SLAVE_ID=9, HW_DESC=EL7037, NELM=1" +#============================================================================== +# addSlave.cmd +epicsEnvSet("ECMC_EC_SL2022/01/21 11:34:15.632 OK +2022/01/21 11:34:15.742 OK +2022/01/21 11:34:15.822 12848 +2022/01/21 11:34:15.825 OK +2022/01/21 11:34:15.825 OK +2022/01/21 11:34:15.825 OK +2022/01/21 11:34:15.826 OK +2022/01/21 11:34:15.826 OK +2022/01/21 11:34:15.826 OK +2022/01/21 11:34:15.826 OK +2022/01/21 11:34:15.827 OK +2022/01/21 11:34:15.827 OK +2022/01/21 11:34:15.827 OK +2022/01/21 11:34:15.827 OK +2022/01/21 11:34:15.827 OK +AVE_NUM", "9") +epicsEnvSet("HW_DESC", "EL7037") +epicsEnvSet("P_SCRIPT", "mXsXXX") +# add ${HW_DESC} to the bus at position ${SLAVE_ID} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037.cmd" "NELM=1" +epicsEnvSet("ECMC_EC_HWTYPE" "EL7037") +epicsEnvSet("ECMC_EC_VENDOR_ID" "0x2") +epicsEnvSet("ECMC_EC_PRODUCT_ID" "0x1b7d3052") +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/slaveVerify.cmd "RESET=true" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_VERIFY, "0==0", "","#- ") +ecmcConfigOrDie "Cfg.EcSlaveVerify(0,9,0x2,0x1b7d3052)" +ecmcEpicsEnvSetCalcTernary(ECMC_SLAVE_RESET, "true>0", "","#- ") +ecmcConfigOrDie "Cfg.EcWriteSdo(9,0x1011,0x1,1684107116,4)" +epicsEnvSet(ECMC_EC_SLAVE_FW, "0x0000") +ecmcConfig "EcReadSdo(9,0x100a,0x0,2)" +ecmcEpicsEnvSetCalc("ECMC_EC_SLAVE_FW", "12848", "0x%04x") +# Firmware version: 0x3230 +epicsEnvUnset(ECMC_SLAVE_VERIFY) +epicsEnvUnset(ECMC_COMMENT) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEX70XX.cmd +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,1,2,0x1600,0x7000,0x01,16,encoderControl01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,1,2,0x1600,0x7000,0x11,16,encoderValue01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,1,2,0x1602,0x7010,0x1,16,driveControl01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,1,2,0x1604,0x7010,0x21,16,1,velocitySetpoint01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,2,3,0x1a00,0x6000,0x0,16,encoderStatus01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,2,3,0x1a00,0x6000,0x11,16,positionActual01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,2,3,0x1a00,0x6000,0x12,16,encoderLatchPostion01)" +ecmcConfigOrDie "Cfg.EcAddEntryComplete(9,0x2,0x1b7d3052,2,3,0x1a03,0x6010,0x1,16,driveStatus01)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8012,0x5,1,1)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8012,0xA,1,1)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8012,0x8,1,1)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8012,0x9,0,1)" +# deduce what the prefix should be +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd",1) +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcmXsXXX.cmd" "MASTER_ID=0,SLAVE_POS=9,HWTYPE=EL7037" +#============================================================================== +# ecmcmXsXXX.cmd +ecmcEpicsEnvSetCalc("sid", "9","%03d") +ecmcEpicsEnvSetCalc("mid", "0","%01d") +epicsEnvSet("ECMC_G", "IOC_TEST:m0s009") +epicsEnvSet("ECMC_P", "IOC_TEST:m0s009-") +epicsEnvUnset(sid) +epicsEnvUnset(mid) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SUBS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applySubstitutions.cmd" "SUBST_FILE=ecmcEL7037.substitutions,ECMC_P=IOC_TEST:m0s009-" +#============================================================================== +# applySubstitutions.cmd +ecmcFileExist(ecmcEL7037.substitutions,1,1) +dbLoadTemplate(ecmcEL7037.substitutions,"ECMC_P=IOC_TEST:m0s009-,ECMC_G=IOC_TEST:m0s009,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=9,HWTYPE=EL7037,T_SMP_MS=10,TSE=-2,NELM=1") +epicsEnvUnset(DEFAULT_SUBS) +ecmcEpicsEnvSetCalcTernary(DEFAULT_SLAVE_PVS, "True", "","#- ") +iocshLoad "/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyTemplate.cmd" "TEMPLATE_FILE=ecmcEcSlave.template,ECMC_P=IOC_TEST:m0s009-,ECMC_G=IOC_TEST:m0s009" +#============================================================================== +# applyTemplate.cmd +ecmcFileExist(ecmcEcSlave.template,1,1) +dbLoadRecords("ecmcEcSlave.template", "ECMC_P=IOC_TEST:m0s009-,ECMC_G=IOC_TEST:m0s009,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,SLAVE_POS=9,HWTYPE=EL7037,T_SMP_MS=10,TSE=-2,") +epicsEnvUnset(DEFAULT_SLAVE_PVS) +# increment SLAVE_ID +ecmcEpicsEnvSetCalc("SLAVE_ID", "9+1","%d") +# apply config ${CONFIG} for ${HW_DESC} +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/s2022/01/21 11:34:15.847 OK +2022/01/21 11:34:15.847 OK +2022/01/21 11:34:15.847 OK +2022/01/21 11:34:15.847 OK +2022/01/21 11:34:15.847 OK +2022/01/21 11:34:15.847 OK +2022/01/21 11:34:15.848 OK +2022/01/21 11:34:15.848 OK +2022/01/21 11:34:15.848 OK +2022/01/21 11:34:15.848 OK +2022/01/21 11:34:15.848 OK +2022/01/21 11:34:15.848 OK +2022/01/21 11:34:15.849 OK +2022/01/21 11:34:15.849 OK +2022/01/21 11:34:15.849 OK +iteMods/ecmccfg/ruckig/ecmcEL7037-Motor-Nanotec-ST4118L1804-B.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmcEL7037-Motor-Nanotec-ST4118L1804-B.cmd "" +epicsEnvSet(I_MAX_MA_LOCAL,"1500") +epicsEnvSet(I_RUN_MA_LOCAL,1000) +epicsEnvSet(I_STDBY_MA_LOCAL,500) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/chkValidCurrentSetOrDie.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/chkValidCurrentSetOrDie.cmd "I_RUN_MA=1000,I_STDBY_MA=500,I_MAX_MA=1500" +#============================================================================== +# chkValidCurrentSetOrDie.cmd +# Ensure running current is below max current otherwise exit +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "1000>1500 or 1000<=0", "ecmcExit Error: Run current setpoint to high or negative...","# Run current setting OK (1000)...") +# Result: +# Run current setting OK (1000)... +epicsEnvUnset(ECMC_EXE_CMD) +# Ensure standby current is below max current otherwise exit +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "500>1500 or 500<0", "ecmcExit Error: Standby current setpoint to high or negative...","# Standby current setting OK (500)...") +# Result: +# Standby current setting OK (500)... +epicsEnvUnset(ECMC_EXE_CMD) +# Ensure standby current is below run current otherwise exit +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "500>1000", "ecmcExit Error: Standby current higher than run current...","# Standby current and run current setting OK (500<1000)...") +# Result: +# Standby current and run current setting OK (500<1000)... +epicsEnvUnset(ECMC_EXE_CMD) +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8010,0x1,1000,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8010,0x2,500,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8010,0x3,2400,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8010,0x4,175,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8010,0x6,200,2)" +ecmcConfigOrDie "Cfg.EcAddSdo(9,0x8010,0xA,330,2)" +epicsEnvUnset("I_RUN_MA_LOCAL") +epicsEnvUnset("I_STDBY_MA_LOCAL") +epicsEnvUnset("I_MAX_MA_LOCAL") +#Apply hardware configuration +ecmcConfigOrDie "Cfg.EcApplyConfig(1)" +# ADDITIONAL SETUP +# Set all outputs to feed switches +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput01,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput02,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput03,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput04,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput05,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput06,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput07,1)" +ecmcConfigOrDie "Cfg.WriteEcEntryIDString(2,binaryOutput08,1)" +# END of ADDITIONAL SETUP +############################################################################## +## AXIS 1 +# +epicsEnvSet("DEV", "IOC_TEST") +iocshLoad (/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/configureAxis.cmd, CONFIG=./cfg/linear_1.ax) +#============================================================================== +# configureAxis.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'FULL'='DAQ'","ecmcExit Error: ECMC started in DAQ mode. Motion not supported..","#-") +epicsEnvUnset(ECMC_EXE_CMD) +epicsEnvSet("ECMC_PREFIX" "IOC_TEST:") +ecmcFileExist("./cfg/linear_1.ax",1) +iocshLoad ./cfg/linear_1.ax "" +#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") +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addAxis.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addAxis.cmd +#============================================================================== +# addAxis.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'FULL'='DAQ'","ecmcExit Error: ECMC started in DAQ mode. Motion not supported..","#-") +epicsEnvUnset(ECMC_EXE_CMD) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis-records.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis-records.cmd +#============================================================================== +# ecmc_axis-records.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis.cmd +#============================================================================== +# ecmc_axis.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(-60)<>0',SUCCESS_STR='ECMC_ENC_SCALE_NUM value OK == -60...',ERROR_STR='ECMC_ENC_SCALE_NUM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(-60)<>0","# ECMC_ENC_SCALE_NUM value OK == -60...", "ecmcExit Error: ECMC_ENC_SCALE_NUM == 0...") +# ECMC_ENC_SCALE_NUM value OK == -60... +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(2000)<>0',SUCCESS_STR='ECMC_ENC_SCALE_DENOM value OK == 2000...',ERROR_STR='ECMC_ENC_SCALE_DENOM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(2000)<>0","# ECMC_ENC_SCALE_DENOM value OK == 2000...", "ecmcExit Error: ECMC_ENC_SCALE_DENOM == 0...") +# ECMC_ENC_SCALE_DENOM value OK == 2000... +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(600.0)<>0',SUCCESS_STR='ECMC_DRV_SCALE_NUM value OK == 600.0...',ERROR_STR='ECMC_DRV_SCALE_NUM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(600.0)<>0","# ECMC_DRV_SCALE_NU2022/01/21 11:34:15.866 OK +2022/01/21 11:34:15.866 OK +2022/01/21 11:34:15.866 OK +2022/01/21 11:34:15.866 OK +2022/01/21 11:34:15.871 OK +2022/01/21 11:34:15.871 OK +2022/01/21 11:34:15.871 OK +2022/01/21 11:34:15.871 OK +2022/01/21 11:34:15.871 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.872 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.873 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.874 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +M value OK == 600.0...", "ecmcExit Error: ECMC_DRV_SCALE_NUM == 0...") +# ECMC_DRV_SCALE_NUM value OK == 600.0... +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(32768.0)<>0',SUCCESS_STR='ECMC_DRV_SCALE_DENOM value OK == 32768.0...',ERROR_STR='ECMC_DRV_SCALE_DENOM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(32768.0)<>0","# ECMC_DRV_SCALE_DENOM value OK == 32768.0...", "ecmcExit Error: ECMC_DRV_SCALE_DENOM == 0...") +# ECMC_DRV_SCALE_DENOM value OK == 32768.0... +epicsEnvUnset(ECMC_EXE_CMD) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd "EXPR_STR='-1>0',WARNING_STR='WARNING: ECMC_MRES setting is deprecated and will not be used. (MRES will be calulated instead: ECMC_ENC_SCALE_NUM/ECMC_ENC_SCALE_DENOM).. '" +#============================================================================== +# issueWarning.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"-1>0","", "#-") +epicsEnvUnset(ECMC_EXE_CMD) +ecmcConfigOrDie "Cfg.CreateAxis(1,1,0,1)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.health")" +ecmcConfigOrDie "Cfg.SetAxisModRange(1, 0)" +ecmcConfigOrDie "Cfg.SetAxisModType(1, 0)" +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd "EXPR_STR='-1>0',WARNING_STR='WARNING: ECMC_ACCL setting is deprecated. Please use ECMC_ACCS_EGU_PER_S2 instead..'" +#============================================================================== +# issueWarning.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"-1>0","", "#-") +epicsEnvUnset(ECMC_EXE_CMD) +ecmcEpicsEnvSetCalcTernary(ECMC_BLOCK_ACCL,"'EMPTY'!='EMPTY'","", "#-") +ecmcEpicsEnvSetCalcTernary(ECMC_BLOCK_ACCS,"'EMPTY'=='EMPTY'","", "#-") + ecmcConfigOrDie "Cfg.SetAxisAcc(1,10)" + ecmcConfigOrDie "Cfg.SetAxisDec(1,10)" +ecmcConfigOrDie "Cfg.SetAxisJerk(1,10.0)" +ecmcConfigOrDie "Cfg.SetAxisVel(1,10.0)" +ecmcConfigOrDie "Cfg.SetAxisEmergDeceleration(1,100)" +ecmcConfigOrDie "Cfg.SetAxisHomeVelTwordsCam(1,5)" +ecmcConfigOrDie "Cfg.SetAxisHomeVelOffCam(1,4)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKp(1,15.0)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKi(1,0.02)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKd(1,0.0)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKff(1,1.0)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s3.positionActual01,"ax1.enc.actpos")" +ecmcConfigOrDie "Cfg.SetAxisEncScaleDenom(1,2000)" +ecmcConfigOrDie "Cfg.SetAxisEncScaleNum(1,-60)" +ecmcConfigOrDie "Cfg.SetAxisEncType(1,0)" +ecmcConfigOrDie "Cfg.SetAxisEncBits(1,16)" +ecmcConfigOrDie "Cfg.SetAxisEncAbsBits(1,0)" +ecmcConfigOrDie "Cfg.SetAxisEncOffset(1,0)" +ecmcConfigOrDie "Cfg.SetAxisEncVelFilterSize(1,100)" +ecmcConfigOrDie "Cfg.SetAxisEncPosFilterSize(1,1)" +ecmcConfigOrDie "Cfg.SetAxisEncPosFilterEnable(1,0)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.reset")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.alarm0")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.alarm1")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.alarm2")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.warning")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.latchpos")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.latchcontrol")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.enc.latchstatus")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveControl01.0,"ax1.drv.control")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveStatus01.1,"ax1.drv.status")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.velocitySetpoint01,"ax1.drv.velocity")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.drv.position")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax1.drv.brake")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveControl01.2,"ax1.drv.reducetorque")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveControl01.2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.875 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.876 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.877 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.878 OK +2022/01/21 11:34:15.879 OK +2022/01/21 11:34:15.879 OK +2022/01/21 11:34:15.879 OK +2022/01/21 11:34:15.879 OK +2022/01/21 11:34:15.880 ecmcMotorRecord:: setIntegerParam(1 motorPowerAutoOnOff_)=2 +2022/01/21 11:34:15.880 ecmcMotorRecord:: setDoubleParam(1 motorPowerOnDelay_)=6 +2022/01/21 11:34:15.880 ecmcMotorRecord:: setDoubleParam(1 motorPowerOffDelay_=-1 +2022/01/21 11:34:15.881 ecmcMotorRecord:: udateMotorLimitsRO(1) enabledHighAndLow=1 valid=1 fValueHigh=130 fValueLow=-20 +2022/01/21 11:34:15.881 ecmcMotorRecord:: connected(1) +2022/01/21 11:34:15.881 ecmcMotorRecord:: initialPoll(1) status=0 +1,"ax1.drv.reset")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveStatus01.3,"ax1.drv.alarm0")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveStatus01.7,"ax1.drv.alarm1")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveStatus01.14,"ax1.drv.alarm2")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s8.driveStatus01.2,"ax1.drv.warning")" +ecmcConfigOrDie "Cfg.SetAxisDrvScaleDenom(1,32768.0)" +ecmcConfigOrDie "Cfg.SetAxisDrvScaleNum(1,600.0)" +ecmcConfigOrDie "Cfg.SetAxisDrvBrakeOpenDelayTime(1,0)" +ecmcConfigOrDie "Cfg.SetAxisDrvBrakeCloseAheadTime(1,0)" +ecmcConfigOrDie "Cfg.SetAxisSoftLimitPosBwd(1,-20)" +ecmcConfigOrDie "Cfg.SetAxisEnableSoftLimitBwd(1,1)" +ecmcConfigOrDie "Cfg.SetAxisSoftLimitPosFwd(1,130)" +ecmcConfigOrDie "Cfg.SetAxisEnableSoftLimitFwd(1,1)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.binaryInput02.0,"ax1.mon.lowlim")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.binaryInput01.0,"ax1.mon.highlim")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.binaryInput03.0,"ax1.mon.homesensor")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.ONE.0,"ax1.mon.extinterlock")" +ecmcConfigOrDie "Cfg.SetAxisMonAtTargetTol(1,0.1)" +ecmcConfigOrDie "Cfg.SetAxisMonAtTargetTime(1,100)" +ecmcConfigOrDie "Cfg.SetAxisMonEnableAtTargetMon(1,1)" +ecmcConfigOrDie "Cfg.SetAxisMonPosLagTol(1,1.0)" +ecmcConfigOrDie "Cfg.SetAxisMonPosLagTime(1,10)" +ecmcConfigOrDie "Cfg.SetAxisMonEnableLagMon(1,1)" +ecmcConfigOrDie "Cfg.SetAxisMonMaxVel(1,100.0)" +ecmcConfigOrDie "Cfg.SetAxisMonEnableMaxVel(1,1)" +ecmcConfigOrDie "Cfg.SetAxisMonMaxVelDriveILDelay(1,200)" +ecmcConfigOrDie "Cfg.SetAxisMonMaxVelTrajILDelay(1,100)" +ecmcConfigOrDie "Cfg.SetAxisMonHomeSwitchPolarity(1,0)" +ecmcConfigOrDie "Cfg.SetAxisHomeLatchCountOffset(1,0.0)" +ecmcConfigOrDie "Cfg.SetAxisHomePosition(1,0.0)" +ecmcConfigOrDie "Cfg.SetAxisHomePostMoveEnable(1, 0)" +ecmcConfigOrDie "Cfg.SetAxisHomePostMoveTargetPosition(1, 0)" + ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_mr.cmd",1) + iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_mr.cmd +#============================================================================== +# ecmc_axis_mr.cmd +ecmcMotorRecordCreateAxis(MCU1, "1", "6", ) +ecmcEpicsEnvSetCalc("ECMC_TEMP_SREV","if(abs(2000)>0){RESULT:=abs(2000);} else {RESULT:=1.0};","%d") +ecmcEpicsEnvSetCalc("ECMC_TEMP_UREV","if(abs(-60)>0){RESULT:=abs(-60);} else {RESULT:=1.0};","%lf") +ecmcFileExist(ecmcMotorRecord.template,1,1) + dbLoadRecords(ecmcMotorRecord.template, "PREFIX=IOC_TEST:, MOTOR_NAME=Axis1, MOTOR_PORT=MCU1, AXIS_NO=1, DESC=MCU1021 Lower Axis (1), EGU=mm, PREC=3, VELO=10.0, JVEL=5, JAR=0.0, ACCS=10, RDBD=0.1, DLLM=-20, DHLM=130, HOMEPROC=3,SREV=2000,UREV=60.000000, ") +epicsEnvSet("ECMC_AXISFIELDINIT", "") +ecmcFileExist(ecmcMotorRecordhome.template,1,1) +dbLoadRecords(ecmcMotorRecordhome.template, "PREFIX=IOC_TEST:, MOTOR_NAME=Axis1, MOTOR_PORT=MCU1, AXIS_NO=1,HOMEPROC=3, HOMEPOS=0.0, HVELTO=5, HVELFRM=4, HOMEACC=21, HOMEDEC=100") +epicsEnvUnset(ECMC_TEMP_SREV) +epicsEnvUnset(ECMC_TEMP_UREV) +epicsEnvUnset(ECMC_BLOCK_ACCL) +epicsEnvUnset(ECMC_BLOCK_ACCS) +ecmcFileExist("ecmcAxis.db",1,1) +dbLoadRecords("ecmcAxis.db","P=IOC_TEST:,AXIS_NAME=Axis1,AXIS_NO=1,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,T_SMP_MS=10,TSE=-2") +ecmcFileExist("ecmcAxisType.db",1,1) +dbLoadRecords("ecmcAxisType.db","P=IOC_TEST:,AXIS_NAME=Axis1,AXIS_TYPE=1") +ecmcFileExist(/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_unset.cmd,1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_unset.cmd +#============================================================================== +# ecmc_axis_unset.cmd +epicsEnvUnset(ECMC_AXISCONFIG) +epicsEnvUnset(ECMC_AXISFIELDINIT) +epicsEnvUnset(ECMC_PREC) +epicsEnvUnset(ECMC_EGU) +epicsEnvUnset(ECMC_DESC) +epicsEnvUnset(ECMC_R) +epicsEnvUnset(ECMC_MOTOR_NAME) +epicsEnvUnset(ECMC_EC_AXIS_HEALTH) +epicsEnvUnset(ECMC_MOD_RANGE) +epicsEnvUnset(ECMC_MOD_TYPE) +epicsEnvUnset(ECMC_EMERG_DECEL) +epicsEnvUnset(ECMC_VELO) +epicsEnvUnset(ECMC_ACCL) +epicsEnvUnset(ECMC_ACCS_EGU_PmacLib: macro ECMC_EXE_CMD is undefined (expanding string ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'${ECMC_MODE=FULL}'='DAQ'","ecmcExit Error: ECMC started in DAQ mode. Motion not supported..","#-")${ECMC_EXE_CMD}) +macLib: macro ECMC_EXE_CMD is undefined (expanding string ${ECMC_EXE_CMD}) +ER_S2) +epicsEnvUnset(ECMC_HOME_VEL_TO) +epicsEnvUnset(ECMC_HOME_VEL_FRM) +epicsEnvUnset(ECMC_CNTRL_KP) +epicsEnvUnset(ECMC_CNTRL_KI) +epicsEnvUnset(ECMC_CNTRL_KD) +epicsEnvUnset(ECMC_CNTRL_KFF) +epicsEnvUnset(ECMC_EC_ENC_ACTPOS) +epicsEnvUnset(ECMC_EC_ENC_LATCHPOS) +epicsEnvUnset(ECMC_EC_ENC_LATCH_CONTROL) +epicsEnvUnset(ECMC_EC_ENC_LATCH_STATUS) +epicsEnvUnset(ECMC_HOME_LATCH_COUNT_OFFSET) +epicsEnvUnset(ECMC_ENC_SCALE_DENOM) +epicsEnvUnset(ECMC_ENC_SCALE_NUM) +epicsEnvUnset(ECMC_ENC_TYPE) +epicsEnvUnset(ECMC_ENC_BITS) +epicsEnvUnset(ECMC_ENC_ABS_BITS) +epicsEnvUnset(ECMC_ENC_ABS_OFFSET) +epicsEnvUnset(ECMC_ENC_VEL_FILTER_SIZE) +epicsEnvUnset(ECMC_ENC_POS_FILTER_SIZE) +epicsEnvUnset(ECMC_ENC_POS_FILTER_ENABLE) +epicsEnvUnset(ECMC_EC_ENC_RESET) +epicsEnvUnset(ECMC_EC_ENC_ALARM_0) +epicsEnvUnset(ECMC_EC_ENC_ALARM_1) +epicsEnvUnset(ECMC_EC_ENC_ALARM_2) +epicsEnvUnset(ECMC_EC_ENC_WARNING) +epicsEnvUnset(ECMC_EC_DRV_CONTROL) +epicsEnvUnset(ECMC_EC_DRV_STATUS) +epicsEnvUnset(ECMC_EC_DRV_VELOCITY) +epicsEnvUnset(ECMC_EC_DRV_BRAKE) +epicsEnvUnset(ECMC_EC_DRV_REDUCE_TORQUE) +epicsEnvUnset(ECMC_EC_DRV_RESET) +epicsEnvUnset(ECMC_EC_DRV_ALARM_0) +epicsEnvUnset(ECMC_EC_DRV_ALARM_1) +epicsEnvUnset(ECMC_EC_DRV_ALARM_2) +epicsEnvUnset(ECMC_EC_DRV_WARNING) +epicsEnvUnset(ECMC_DRV_SCALE_DENOM) +epicsEnvUnset(ECMC_DRV_SCALE_NUM) +epicsEnvUnset(ECMC_DRV_BRAKE_OPEN_DLY_TIME) +epicsEnvUnset(ECMC_DRV_BRAKE_CLOSE_AHEAD_TIME) +epicsEnvUnset(ECMC_SOFT_LOW_LIM) +epicsEnvUnset(ECMC_DXLM_ENABLE) +epicsEnvUnset(ECMC_SOFT_HIGH_LIM) +epicsEnvUnset(ECMC_DXLM_ENABLE) +epicsEnvUnset(ECMC_EC_MON_LOWLIM) +epicsEnvUnset(ECMC_EC_MON_HIGHLIM) +epicsEnvUnset(ECMC_EC_MON_HOME_SWITCH) +epicsEnvUnset(ECMC_EC_MON_EXT_INTERLOCK) +epicsEnvUnset(ECMC_MON_AT_TARGET_TOL) +epicsEnvUnset(ECMC_MON_AT_TARGET_TIME) +epicsEnvUnset(ECMC_MON_AT_TARGET_ENA) +epicsEnvUnset(ECMC_MON_LAG_MON_TOL) +epicsEnvUnset(ECMC_MON_LAG_MON_TIME) +epicsEnvUnset(ECMC_MON_LAG_MON_ENA) +epicsEnvUnset(ECMC_MON_VELO_MAX) +epicsEnvUnset(ECMC_MON_VELO_MAX_ENA) +epicsEnvUnset(ECMC_MON_VELO_MAX_DRV_TIME) +epicsEnvUnset(ECMC_MON_VELO_MAX_TRAJ_TIME) +epicsEnvUnset(ECMC_JOG_VEL) +epicsEnvUnset(ECMC_JAR) +epicsEnvUnset(ECMC_HOME_PROC) +epicsEnvUnset(ECMC_HOME_POS) +epicsEnvUnset(ECMC_HOME_ACC) +epicsEnvUnset(ECMC_HOME_DEC) +epicsEnvUnset(ECMC_DRV_TYPE) +epicsEnvUnset(ECMC_VELO) +epicsEnvUnset(ECMC_SOFT_LOW_LIM) +epicsEnvUnset(ECMC_SOFT_HIGH_LIM) +epicsEnvUnset(ECMC_HOME_POS_MOVE_ENA) +epicsEnvUnset(ECMC_HOME_POS_MOVE_TARG_POS) +epicsEnvUnset(ECMC_TRAJ_TYPE) +epicsEnvUnset(ECMC_JERK) +epicsEnvSet("ECMC_PREFIX" "IOC_TEST:") +# Set external setpoints +iocshLoad (/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyAxisSynchronization.cmd, CONFIG=./cfg/linear_1.sax) +#============================================================================== +# applyAxisSynchronization.cmd +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad ./cfg/linear_1.sax +############# 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", "") +2022/01/21 11:34:15.900 OK +2022/01/21 11:34:15.900 OK +2022/01/21 11:34:15.900 OK +2022/01/21 11:34:15.900 OK +2022/01/21 11:34:15.900 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.901 OK +2022/01/21 11:34:15.902 OK +2022/01/21 11:34:15.902 OK +2022/01/21 11:34:15.902 OK +2022/01/21 11:34:15.902 OK +2022/01/21 11:34:15.902 OK +2022/01/21 11:34:15.903 OK +epicsEnvSet("ECMC_AXIS_EXPR_LINE_8", "") +epicsEnvSet("ECMC_AXIS_EXPR_LINE_9", "") +epicsEnvSet("ECMC_AXIS_EXPR_LINE_10", "") +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync.cmd +#============================================================================== +# ecmc_axis_sync.cmd +ecmcConfigOrDie "Cfg.SetAxisAllowCommandsFromPLC(1,1)" +ecmcConfigOrDie "Cfg.SetAxisPLCEnable(1,0)" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=var a:=1|" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(1)=" +ecmcConfigOrDie "Cfg.SetAxisPLCEncVelFilterSize(1,20)" +ecmcConfigOrDie "Cfg.SetAxisPLCEncVelFilterEnable(1,1)" +ecmcConfigOrDie "Cfg.SetAxisEncSourceType(1,0)" +ecmcConfigOrDie "Cfg.SetAxisPLCTrajVelFilterSize(1,20)" +ecmcConfigOrDie "Cfg.SetAxisPLCTrajVelFilterEnable(1,1)" +ecmcConfigOrDie "Cfg.SetAxisTrajSourceType(1,1)" +ecmcFileExist(/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync_unset.cmd,1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync_unset.cmd +#============================================================================== +# ecmc_axis_sync_unset.cmd +epicsEnvUnset(ECMC_CMD_FRM_OTHER_PLC_ENABLE) +epicsEnvUnset(ECMC_CMD_AXIS_PLC_ENABLE) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_1) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_2) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_3) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_4) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_5) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_6) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_7) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_8) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_9) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_10) +epicsEnvUnset(ECMC_ENC_VELO_FILT_SIZE) +epicsEnvUnset(ECMC_ENC_VELO_FILT_ENABLE) +epicsEnvUnset(ECMC_ENC_SOURCE) +epicsEnvUnset(ECMC_TRAJ_VELO_FILT_SIZE) +epicsEnvUnset(ECMC_TRAJ_VELO_FILT_ENABLE) +epicsEnvUnset(ECMC_TRAJ_SOURCE) +############################################################################## +## AXIS 2 +# +#epicsEnvSet("DEV", "$(IOC)") +iocshLoad (/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/configureAxis.cmd, CONFIG=./cfg/linear_2.ax) +#============================================================================== +# configureAxis.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'FULL'='DAQ'","ecmcExit Error: ECMC started in DAQ mode. Motion not supported..","#-") +epicsEnvUnset(ECMC_EXE_CMD) +epicsEnvSet("ECMC_PREFIX" "IOC_TEST:") +ecmcFileExist("./cfg/linear_2.ax",1) +iocshLoad ./cfg/linear_2.ax "" +#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") +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addAxis.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/addAxis.cmd +#============================================================================== +# addAxis.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'FULL'='DAQ'","ecmcExit Error: ECMC started in DAQ mode. Motion not supported..","#-") +epicsEnvUnset(ECMC_EXE_CMD) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis-records.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis-records.cmd +#============================================================================== +# ecmc_axis-records.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis.cmd +#============================================================================== +# ecmc_axis.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(60)<>0',SUCCESS_STR='ECMC_ENC_SCALE_NUM value OK == 60...',ERROR_STR='ECMC_ENC_SCALE_NUM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(60)<>0","# ECMC_ENC_SCALE_NUM value OK == 60...", "ecmcExit Error: ECMC_ENC_SCALE_NUM == 0...") +# ECMC_ENC_SCALE_NUM value OK == 60... +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(2000)<>0',SUCCESS_STR='ECMC_ENC_SCALE_DENOM value OK == 2000...',ERROR_STR='ECMC_ENC_SCALE_DENOM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(2000)<>0","# ECMC_ENC_SCALE_DENOM value OK == 2000...", "ecmcExit Error: ECMC_ENC_SCALE_DENOM == 0...") +# ECMC_ENC_SCALE_DENOM value OK == 2000... +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(-600.0)<>0',SUCCESS_STR='ECMC_DRV_SCALE_NUM value OK == -600.0...',ERROR_STR='ECMC_DRV_SCALE_NUM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(-600.0)<>0","# ECMC_DRV_SCALE_NUM value OK == -600.0...", "ecmcExit Error: ECMC_DRV_SCALE_NUM == 0...") +# ECMC_DRV_SCALE_NUM value OK == -600.0... +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/verifyOrDie.cmd "EXPR_STR='abs(32768.0)<>0',SUCCESS_STR='ECMC_DRV_SCALE_DENOM value OK == 32768.0...',ERROR_STR='ECMC_DRV_SCALE_DENOM == 0...'" +#============================================================================== +# verifyOrDie.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"abs(32768.0)<>0","# ECMC_DRV_SCALE_DENOM value OK == 32768.0...", "ecmcExit Error: ECMC_DRV_SCALE_DEN2022/01/21 11:34:15.923 OK +2022/01/21 11:34:15.924 OK +2022/01/21 11:34:15.924 OK +2022/01/21 11:34:15.924 OK +2022/01/21 11:34:15.927 OK +2022/01/21 11:34:15.927 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.928 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.929 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.930 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.931 OK +2022/01/21 11:34:15.932 OK +2022/01/21 11:34:15.932 OK +2022/01/21 11:34:15.932 OK +2022/01/21 11:34:15.932 OK +2022/01/21 11:34:15.932 OK +2022/01/21 11:34:15.932 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +OM == 0...") +# ECMC_DRV_SCALE_DENOM value OK == 32768.0... +epicsEnvUnset(ECMC_EXE_CMD) +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd "EXPR_STR='-1>0',WARNING_STR='WARNING: ECMC_MRES setting is deprecated and will not be used. (MRES will be calulated instead: ECMC_ENC_SCALE_NUM/ECMC_ENC_SCALE_DENOM).. '" +#============================================================================== +# issueWarning.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"-1>0","", "#-") +epicsEnvUnset(ECMC_EXE_CMD) +ecmcConfigOrDie "Cfg.CreateAxis(2,1,0,0)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.health")" +ecmcConfigOrDie "Cfg.SetAxisModRange(2, 0)" +ecmcConfigOrDie "Cfg.SetAxisModType(2, 0)" +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/issueWarning.cmd "EXPR_STR='-1>0',WARNING_STR='WARNING: ECMC_ACCL setting is deprecated. Please use ECMC_ACCS_EGU_PER_S2 instead..'" +#============================================================================== +# issueWarning.cmd +ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD,"-1>0","", "#-") +epicsEnvUnset(ECMC_EXE_CMD) +ecmcEpicsEnvSetCalcTernary(ECMC_BLOCK_ACCL,"'EMPTY'!='EMPTY'","", "#-") +ecmcEpicsEnvSetCalcTernary(ECMC_BLOCK_ACCS,"'EMPTY'=='EMPTY'","", "#-") + ecmcConfigOrDie "Cfg.SetAxisAcc(2,10)" + ecmcConfigOrDie "Cfg.SetAxisDec(2,10)" +ecmcConfigOrDie "Cfg.SetAxisJerk(2,0)" +ecmcConfigOrDie "Cfg.SetAxisVel(2,10.0)" +ecmcConfigOrDie "Cfg.SetAxisEmergDeceleration(2,100)" +ecmcConfigOrDie "Cfg.SetAxisHomeVelTwordsCam(2,5)" +ecmcConfigOrDie "Cfg.SetAxisHomeVelOffCam(2,4)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKp(2,15.0)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKi(2,0.02)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKd(2,0.0)" +ecmcConfigOrDie "Cfg.SetAxisCntrlKff(2,1.0)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s4.positionActual01,"ax2.enc.actpos")" +ecmcConfigOrDie "Cfg.SetAxisEncScaleDenom(2,2000)" +ecmcConfigOrDie "Cfg.SetAxisEncScaleNum(2,60)" +ecmcConfigOrDie "Cfg.SetAxisEncType(2,0)" +ecmcConfigOrDie "Cfg.SetAxisEncBits(2,16)" +ecmcConfigOrDie "Cfg.SetAxisEncAbsBits(2,0)" +ecmcConfigOrDie "Cfg.SetAxisEncOffset(2,0)" +ecmcConfigOrDie "Cfg.SetAxisEncVelFilterSize(2,100)" +ecmcConfigOrDie "Cfg.SetAxisEncPosFilterSize(2,1)" +ecmcConfigOrDie "Cfg.SetAxisEncPosFilterEnable(2,0)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.reset")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.alarm0")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.alarm1")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.alarm2")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.warning")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.latchpos")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.latchcontrol")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.enc.latchstatus")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveControl01.0,"ax2.drv.control")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveStatus01.1,"ax2.drv.status")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.velocitySetpoint01,"ax2.drv.velocity")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.drv.position")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(,"ax2.drv.brake")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveControl01.2,"ax2.drv.reducetorque")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveControl01.1,"ax2.drv.reset")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveStatus01.3,"ax2.drv.alarm0")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveStatus01.7,"ax2.drv.alarm1")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveStatus01.14,"ax2.drv.alarm2")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s9.driveStatus01.2,"ax2.drv.warning")" +ecmcConfigOrDie "Cfg.SetAxisDrvScaleDenom(2,32768.0)" +ecmcConfigOrDie "Cfg.SetAxisDrvScaleNum(2,-600.0)" +ecmcConfigOrDie "Cfg.SetAxisDrvBrakeOpenDelayTime(2,0)" +ecmcConfigOrDie "Cfg.SetAxisDrvBrakeCloseAheadTime(2,0)" +ecmcConfigOrDie "Cfg.SetAxisSof2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.933 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.934 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.935 OK +2022/01/21 11:34:15.936 OK +2022/01/21 11:34:15.936 ecmcMotorRecord:: setIntegerParam(2 motorPowerAutoOnOff_)=2 +2022/01/21 11:34:15.936 ecmcMotorRecord:: setDoubleParam(2 motorPowerOnDelay_)=6 +2022/01/21 11:34:15.936 ecmcMotorRecord:: setDoubleParam(2 motorPowerOffDelay_=-1 +2022/01/21 11:34:15.936 ecmcMotorRecord:: udateMotorLimitsRO(2) enabledHighAndLow=1 valid=1 fValueHigh=20 fValueLow=-130 +2022/01/21 11:34:15.937 ecmcMotorRecord:: connected(2) +2022/01/21 11:34:15.937 ecmcMotorRecord:: initialPoll(2) status=0 +tLimitPosBwd(2,-130)" +ecmcConfigOrDie "Cfg.SetAxisEnableSoftLimitBwd(2,1)" +ecmcConfigOrDie "Cfg.SetAxisSoftLimitPosFwd(2,20)" +ecmcConfigOrDie "Cfg.SetAxisEnableSoftLimitFwd(2,1)" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.binaryInput06.0,"ax2.mon.lowlim")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.binaryInput05.0,"ax2.mon.highlim")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s1.binaryInput07.0,"ax2.mon.homesensor")" +ecmcConfigOrDie "Cfg.LinkEcEntryToObject(ec0.s0.ONE.0,"ax2.mon.extinterlock")" +ecmcConfigOrDie "Cfg.SetAxisMonAtTargetTol(2,0.1)" +ecmcConfigOrDie "Cfg.SetAxisMonAtTargetTime(2,100)" +ecmcConfigOrDie "Cfg.SetAxisMonEnableAtTargetMon(2,1)" +ecmcConfigOrDie "Cfg.SetAxisMonPosLagTol(2,1.0)" +ecmcConfigOrDie "Cfg.SetAxisMonPosLagTime(2,10)" +ecmcConfigOrDie "Cfg.SetAxisMonEnableLagMon(2,1)" +ecmcConfigOrDie "Cfg.SetAxisMonMaxVel(2,100.0)" +ecmcConfigOrDie "Cfg.SetAxisMonEnableMaxVel(2,1)" +ecmcConfigOrDie "Cfg.SetAxisMonMaxVelDriveILDelay(2,200)" +ecmcConfigOrDie "Cfg.SetAxisMonMaxVelTrajILDelay(2,100)" +ecmcConfigOrDie "Cfg.SetAxisMonHomeSwitchPolarity(2,0)" +ecmcConfigOrDie "Cfg.SetAxisHomeLatchCountOffset(2,0.0)" +ecmcConfigOrDie "Cfg.SetAxisHomePosition(2,0.0)" +ecmcConfigOrDie "Cfg.SetAxisHomePostMoveEnable(2, 0)" +ecmcConfigOrDie "Cfg.SetAxisHomePostMoveTargetPosition(2, 0)" + ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_mr.cmd",1) + iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_mr.cmd +#============================================================================== +# ecmc_axis_mr.cmd +ecmcMotorRecordCreateAxis(MCU1, "2", "6", ) +ecmcEpicsEnvSetCalc("ECMC_TEMP_SREV","if(abs(2000)>0){RESULT:=abs(2000);} else {RESULT:=1.0};","%d") +ecmcEpicsEnvSetCalc("ECMC_TEMP_UREV","if(abs(60)>0){RESULT:=abs(60);} else {RESULT:=1.0};","%lf") +ecmcFileExist(ecmcMotorRecord.template,1,1) + dbLoadRecords(ecmcMotorRecord.template, "PREFIX=IOC_TEST:, MOTOR_NAME=Axis2, MOTOR_PORT=MCU1, AXIS_NO=2, DESC=MCU1021 Upper Axis (2), EGU=mm, PREC=3, VELO=10.0, JVEL=5, JAR=0.0, ACCS=10, RDBD=0.1, DLLM=-130, DHLM=20, HOMEPROC=3,SREV=2000,UREV=60.000000, ") +epicsEnvSet("ECMC_AXISFIELDINIT", "") +ecmcFileExist(ecmcMotorRecordhome.template,1,1) +dbLoadRecords(ecmcMotorRecordhome.template, "PREFIX=IOC_TEST:, MOTOR_NAME=Axis2, MOTOR_PORT=MCU1, AXIS_NO=2,HOMEPROC=3, HOMEPOS=0.0, HVELTO=5, HVELFRM=4, HOMEACC=21, HOMEDEC=100") +epicsEnvUnset(ECMC_TEMP_SREV) +epicsEnvUnset(ECMC_TEMP_UREV) +epicsEnvUnset(ECMC_BLOCK_ACCL) +epicsEnvUnset(ECMC_BLOCK_ACCS) +ecmcFileExist("ecmcAxis.db",1,1) +dbLoadRecords("ecmcAxis.db","P=IOC_TEST:,AXIS_NAME=Axis2,AXIS_NO=2,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,T_SMP_MS=10,TSE=-2") +ecmcFileExist("ecmcAxisType.db",1,1) +dbLoadRecords("ecmcAxisType.db","P=IOC_TEST:,AXIS_NAME=Axis2,AXIS_TYPE=1") +ecmcFileExist(/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_unset.cmd,1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_unset.cmd +#============================================================================== +# ecmc_axis_unset.cmd +epicsEnvUnset(ECMC_AXISCONFIG) +epicsEnvUnset(ECMC_AXISFIELDINIT) +epicsEnvUnset(ECMC_PREC) +epicsEnvUnset(ECMC_EGU) +epicsEnvUnset(ECMC_DESC) +epicsEnvUnset(ECMC_R) +epicsEnvUnset(ECMC_MOTOR_NAME) +epicsEnvUnset(ECMC_EC_AXIS_HEALTH) +epicsEnvUnset(ECMC_MOD_RANGE) +epicsEnvUnset(ECMC_MOD_TYPE) +epicsEnvUnset(ECMC_EMERG_DECEL) +epicsEnvUnset(ECMC_VELO) +epicsEnvUnset(ECMC_ACCL) +epicsEnvUnset(ECMC_ACCS_EGU_PER_S2) +epicsEnvUnset(ECMC_HOME_VEL_TO) +epicsEnvUnset(ECMC_HOME_VEL_FRM) +epicsEnvUnset(ECMC_CNTRL_KP) +epicsEnvUnset(ECMC_CNTRL_KI) +epicsEnvUnset(ECMC_CNTRL_KD) +epicsEnvUnset(ECMC_CNTRL_KFF) +epicsEnvUnset(ECMC_EC_ENC_ACTPOS) +epicsEnvUnset(ECMC_EC_ENC_LATCHPOS) +epicsEnvUnset(ECMC_EC_ENC_LATCH_CONTROL) +epicsEnvUnset(ECMC_EC_ENC_LATCH_STATUS) +epicsEnvUnset(ECMC_HOME_LATCH_COUNT_OFFSET) +epicsEnvUnset(ECMC_ENC_SCALE_DENOM) +epicsEnvUnset(ECMC_ENC_SCALE_NUM) +epicsEnvUnset(ECMC_ENC_TYPE) +epicsEnvUnset(ECMC_ENC_BITS) +epicsEnvUnset(ECMC_ENC_ABS_BITS) +epicsEnvUnset(ECMC_ENC_ABS_OFFSET) +epicsEnvUnset(ECMC_ENC_VmacLib: macro ECMC_EXE_CMD is undefined (expanding string ecmcEpicsEnvSetCalcTernary(ECMC_EXE_CMD, "'${ECMC_MODE=FULL}'='DAQ'","ecmcExit Error: ECMC started in DAQ mode. Motion not supported..","#-")${ECMC_EXE_CMD}) +macLib: macro ECMC_EXE_CMD is undefined (expanding string ${ECMC_EXE_CMD}) +2022/01/21 11:34:15.952 OK +2022/01/21 11:34:15.952 OK +2022/01/21 11:34:15.952 OK +EL_FILTER_SIZE) +epicsEnvUnset(ECMC_ENC_POS_FILTER_SIZE) +epicsEnvUnset(ECMC_ENC_POS_FILTER_ENABLE) +epicsEnvUnset(ECMC_EC_ENC_RESET) +epicsEnvUnset(ECMC_EC_ENC_ALARM_0) +epicsEnvUnset(ECMC_EC_ENC_ALARM_1) +epicsEnvUnset(ECMC_EC_ENC_ALARM_2) +epicsEnvUnset(ECMC_EC_ENC_WARNING) +epicsEnvUnset(ECMC_EC_DRV_CONTROL) +epicsEnvUnset(ECMC_EC_DRV_STATUS) +epicsEnvUnset(ECMC_EC_DRV_VELOCITY) +epicsEnvUnset(ECMC_EC_DRV_BRAKE) +epicsEnvUnset(ECMC_EC_DRV_REDUCE_TORQUE) +epicsEnvUnset(ECMC_EC_DRV_RESET) +epicsEnvUnset(ECMC_EC_DRV_ALARM_0) +epicsEnvUnset(ECMC_EC_DRV_ALARM_1) +epicsEnvUnset(ECMC_EC_DRV_ALARM_2) +epicsEnvUnset(ECMC_EC_DRV_WARNING) +epicsEnvUnset(ECMC_DRV_SCALE_DENOM) +epicsEnvUnset(ECMC_DRV_SCALE_NUM) +epicsEnvUnset(ECMC_DRV_BRAKE_OPEN_DLY_TIME) +epicsEnvUnset(ECMC_DRV_BRAKE_CLOSE_AHEAD_TIME) +epicsEnvUnset(ECMC_SOFT_LOW_LIM) +epicsEnvUnset(ECMC_DXLM_ENABLE) +epicsEnvUnset(ECMC_SOFT_HIGH_LIM) +epicsEnvUnset(ECMC_DXLM_ENABLE) +epicsEnvUnset(ECMC_EC_MON_LOWLIM) +epicsEnvUnset(ECMC_EC_MON_HIGHLIM) +epicsEnvUnset(ECMC_EC_MON_HOME_SWITCH) +epicsEnvUnset(ECMC_EC_MON_EXT_INTERLOCK) +epicsEnvUnset(ECMC_MON_AT_TARGET_TOL) +epicsEnvUnset(ECMC_MON_AT_TARGET_TIME) +epicsEnvUnset(ECMC_MON_AT_TARGET_ENA) +epicsEnvUnset(ECMC_MON_LAG_MON_TOL) +epicsEnvUnset(ECMC_MON_LAG_MON_TIME) +epicsEnvUnset(ECMC_MON_LAG_MON_ENA) +epicsEnvUnset(ECMC_MON_VELO_MAX) +epicsEnvUnset(ECMC_MON_VELO_MAX_ENA) +epicsEnvUnset(ECMC_MON_VELO_MAX_DRV_TIME) +epicsEnvUnset(ECMC_MON_VELO_MAX_TRAJ_TIME) +epicsEnvUnset(ECMC_JOG_VEL) +epicsEnvUnset(ECMC_JAR) +epicsEnvUnset(ECMC_HOME_PROC) +epicsEnvUnset(ECMC_HOME_POS) +epicsEnvUnset(ECMC_HOME_ACC) +epicsEnvUnset(ECMC_HOME_DEC) +epicsEnvUnset(ECMC_DRV_TYPE) +epicsEnvUnset(ECMC_VELO) +epicsEnvUnset(ECMC_SOFT_LOW_LIM) +epicsEnvUnset(ECMC_SOFT_HIGH_LIM) +epicsEnvUnset(ECMC_HOME_POS_MOVE_ENA) +epicsEnvUnset(ECMC_HOME_POS_MOVE_TARG_POS) +epicsEnvUnset(ECMC_TRAJ_TYPE) +epicsEnvUnset(ECMC_JERK) +epicsEnvSet("ECMC_PREFIX" "IOC_TEST:") +# Set external setpoints +iocshLoad (/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/applyAxisSynchronization.cmd, CONFIG=./cfg/linear_2.sax) +#============================================================================== +# applyAxisSynchronization.cmd +epicsEnvUnset(ECMC_EXE_CMD) +iocshLoad ./cfg/linear_2.sax +############# 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", "") +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync.cmd +#============================================================================== +# ecmc_axis_sync.cmd +ecmcConfigOrDie "Cfg.SetAxisAllowCommandsFromPLC(2,1)" +ecmcConfigOrDie "Cfg.SetAxisPLCEnable(2,0)" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=var a:=1|" +ecm2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.953 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +2022/01/21 11:34:15.954 OK +cConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.AppendAxisPLCExpr(2)=" +ecmcConfigOrDie "Cfg.SetAxisPLCEncVelFilterSize(2,20)" +ecmcConfigOrDie "Cfg.SetAxisPLCEncVelFilterEnable(2,1)" +ecmcConfigOrDie "Cfg.SetAxisEncSourceType(2,0)" +ecmcConfigOrDie "Cfg.SetAxisPLCTrajVelFilterSize(2,20)" +ecmcConfigOrDie "Cfg.SetAxisPLCTrajVelFilterEnable(2,1)" +ecmcConfigOrDie "Cfg.SetAxisTrajSourceType(2,1)" +ecmcFileExist(/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync_unset.cmd,1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/ecmc_axis_sync_unset.cmd +#============================================================================== +# ecmc_axis_sync_unset.cmd +epicsEnvUnset(ECMC_CMD_FRM_OTHER_PLC_ENABLE) +epicsEnvUnset(ECMC_CMD_AXIS_PLC_ENABLE) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_1) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_2) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_3) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_4) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_5) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_6) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_7) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_8) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_9) +epicsEnvUnset(ECMC_AXIS_EXPR_LINE_10) +epicsEnvUnset(ECMC_ENC_VELO_FILT_SIZE) +epicsEnvUnset(ECMC_ENC_VELO_FILT_ENABLE) +epicsEnvUnset(ECMC_ENC_SOURCE) +epicsEnvUnset(ECMC_TRAJ_VELO_FILT_SIZE) +epicsEnvUnset(ECMC_TRAJ_VELO_FILT_ENABLE) +epicsEnvUnset(ECMC_TRAJ_SOURCE) +############################################################################## +## Load plugin: +epicsEnvSet("PLUGIN_VER" ,"develop") +require ecmc_plugin_grbl develop +Module ecmc_plugin_grbl version develop found in /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/ +Module ecmc_plugin_grbl depends on asyn 4.41.0 +Module asyn version 4.41.0 already loaded +Module ecmc_plugin_grbl depends on ecmc ruckig +Module ecmc version ruckig already loaded +Loading library /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/lib/linux-arm/libecmc_plugin_grbl.so +Loaded ecmc_plugin_grbl version develop +Loading dbd file /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/dbd/ecmc_plugin_grbl.dbd +Calling function ecmc_plugin_grbl_registerRecordDeviceDriver +Loading module info records for ecmc_plugin_grbl +epicsEnvSet(ECMC_PLUGIN_FILNAME,"/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/lib/linux-arm/libecmc_plugin_grbl.so") +epicsEnvSet(ECMC_PLUGIN_CONFIG,"DBG_PRINT=1;X_AXIS=1;AUTO_ENABLE=1;") # Only one option implemented in this plugin +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/loadPlugin.cmd, "PLUGIN_ID=0,FILE=/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/lib/linux-arm/libecmc_plugin_grbl.so,CONFIG='DBG_PRINT=1;X_AXIS=1;AUTO_ENABLE=1;', REPORT=1" +#============================================================================== +# loadPlugin.cmd +ecmcConfigOrDie "Cfg.LoadPlugin(0,/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/lib/linux-arm/libecmc_plugin_grbl.so,DBG_PRINT=1;X_AXIS=1;AUTO_ENABLE=1;)" +../ecmc_plugin_grbl/ecmcGrbl.cpp:doReadWorker:222 +../ecmc_plugin_grbl/ecmcGrbl.cpp:doMainWorker:260 +../grbl/grbl_serial.c:serial_init:70: +../grbl/grbl_eeprom.c:ecmc_init_file:53 +../grbl/grbl_settings.c:settings_restore:132 settings_restore complete!!!.. +../grbl/grbl_eeprom.c:memcpy_from_eeprom_with_checksum:215 EEPROM simulated by file.. +../grbl/grbl_stepper.c:stepper_init:626 +../grbl/grbl_system.c:system_init:26: +../grbl/grbl_gcode.c:gc_init:44: +../grbl/grbl_eeprom.c:memcpy_from_eeprom_with_checksum:215 EEPROM simulated by file.. +../grbl/grbl_spindle_control.c:spindle_init:31 Not supported yet.. +../grbl/grbl_coolant_control.c:coolant_init:25 Not supported yet.. +../grbl/grbl_limits.c:limits_init:44 Not s2022/01/21 11:34:16.163 OK +2022/01/21 11:34:16.164 OK +upported yet.. +../grbl/grbl_probe.c:probe_init:31 Not supported yet.. +../grbl/grbl_stepper.c:st_reset:593 +../grbl/grbl_stepper.c:st_go_idle:297 +Waiting for grbl init..../ecmc_plugin_grbl/ecmcGrbl.cpp:doWriteWorker:234 +../grbl/grbl_stepper.c:st_generate_step_dir_invert_masks:571 +../grbl/grbl_gcode.c:gc_sync_position:59: +../grbl/grbl_protocol.c:protocol_main_loop:40 +../grbl/grbl_system.c:system_check_safety_door_ajar:93: +../grbl/grbl_system.c:system_execute_startup:107: +../grbl/grbl_eeprom.c:memcpy_from_eeprom_with_checksum:215 EEPROM simulated by file.. +../grbl/grbl_eeprom.c:memcpy_from_eeprom_with_checksum:215 EEPROM simulated by file.. + +Grbl 1.1h ['$' for help] +.ecmcEpicsEnvSetCalcTernary("ECMC_PLUGIN_REPORT", "1>0","","#") +ecmcConfigOrDie "Cfg.ReportPlugin(0)" +Plugin info: + Index = 0 + Name = ecmcPluginGrbl + Description = grbl plugin for use with ecmc. + Option description = + DBG_PRINT=<1/0> : Enables/disables printouts from plugin, default = disabled (=0). + X_AXIS=: Ecmc Axis id for use as grbl X axis, default = disabled (=-1). + Y_AXIS=: Ecmc Axis id for use as grbl Y axis, default = disabled (=-1). + Z_AXIS=: Ecmc Axis id for use as grbl Z axis, default = disabled (=-1). + SPINDLE_AXIS=: Ecmc Axis id for use as grbl spindle axis, default = disabled (=-1). + AUTO_ENABLE=<1/0>: Auto enable the linked ecmc axes autmatically before start, default = disabled (=0). + + Filename = /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmc_plugin_grbl/develop/lib/linux-arm/libecmc_plugin_grbl.so + Config string = DBG_PRINT=1;X_AXIS=1;AUTO_ENABLE=1; + Version = 2 + Interface version = 65536 (ecmc = 65536) + max plc funcs = 64 + max plc func args = 10 + max plc consts = 64 + Construct func = @0xb5111d40 + Enter realtime func = @0xb5111ce8 + Exit realtime func = @0xb5111cf0 + Realtime func = @0xb5111d30 + Destruct func = @0xb5111d08 + dlhandle = @0x664f90 + Plc functions: + funcs[00]: + Name = "grbl_connect();" + Desc = double grbl_connect() : Connect to grbl interface (from config str). + Arg count = 0 + func = @0xb5111cf8 + Plc constants: + +epicsEnvUnset(ECMC_PLUGIN_REPORT); +epicsEnvUnset(ECMC_PLUGIN_FILNAME) +epicsEnvUnset(ECMC_PLUGIN_CONFIG) +ecmcGrblAddCommand("G1X0Y20F20"); +../ecmc_plugin_grbl/ecmcGrbl.cpp:addCommand:416: +../ecmc_plugin_grbl/ecmcGrbl.cpp:addCommand:420: Buffer size 1 +#ecmcGrblAddCommand("G2X0Y-20R20"); +#ecmcGrblAddCommand("G0X10Y10"); +#ecmcGrblAddCommand("G4P1"); +#ecmcGrblAddCommand("G1X10Y0F10"); +#ecmcGrblAddCommand("G1X50Y50F10"); +#ecmcGrblAddCommand("G1X0Y0F10"); +# +#ecmcGrblAddCommand("$"); +# +#ecmcGrblAddCommand("G0X10Y100"); +# +#ecmcGrblAddCommand("$G"); +# +#ecmcGrblAddCommand("G4P1"); +# +#ecmcGrblAddCommand("G1X20Y20F20"); +# +#ecmcGrblAddCommand("G4P1"); +# +#ecmcGrblAddCommand("G2X40Y40R20"); +# +#ecmcGrblAddCommand("$"); +############################################################################## +## PLC 0 +# $(SCRIPTEXEC) $(ecmccfg_DIR)loadPLCFile.cmd, "PLC_ID=0, SAMPLE_RATE_MS=1000,FILE=./plc/can.plc") +iocshLoad (/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/setAppMode.cmd) +#============================================================================== +# setAppMode.cmd +ecmcFileExist("/home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/general.cmd",1) +iocshLoad /home/pi/epics/base-7.0.5/require/3.4.0/siteMods/ecmccfg/ruckig/general.cmd +#============================================================================== +# general.cmd +ecmcFileExist("ecmcGeneral.db",1,1) +dbLoadRecords("ecmcGeneral.db","P=IOC_TEST:,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,T_SMP_MS=10,TSE=-2,ECMC_PROC_HOOK=") +# Examples of commands for info: +# ecmcReport or asynReport +# ecmcReport 3 +# ecmcGrepParam +# List all ecmc params for ethercat slave 2: +# ecmcGrepParam *s2* +# +ecmcEpicsEnvSetCalcTernary(ECMC_MASTER_CMD, "0>=0", "","#- ") + ecmcFileExist("ecmcEc.d2022/01/21 11:34:16.168 INFO: Locking memory +2022/01/21 11:34:16.269 ../devEcmcSup/motion/ecmcMonitor.cpp/checkLimits:501: ERROR_MON_BOTH_LIMIT_INTERLOCK (0x14c10). +2022/01/21 11:34:16.269 ../devEcmcSup/motion/ecmcAxisReal.cpp/execute:185: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315). +2022/01/21 11:34:16.269 ../devEcmcSup/motion/ecmcMonitor.cpp/checkLimits:501: ERROR_MON_BOTH_LIMIT_INTERLOCK (0x14c10). +2022/01/21 11:34:16.269 ../devEcmcSup/motion/ecmcAxisReal.cpp/execute:185: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315). +2022/01/21 11:34:16.269 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 0: Not operational (0x24011). +2022/01/21 11:34:16.269 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.269 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 1: Not operational (0x24011). +2022/01/21 11:34:16.269 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.269 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 2: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 3: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 4: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 5: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 6: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 8: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:374: ERROR: Slave 9: Not operational (0x24011). +2022/01/21 11:34:16.270 ../devEcmcSup/ethercat/ecmcEcSlave.cpp/checkConfigState:379: ERROR_EC_SLAVE_NOT_OPERATIONAL (0x24011). +2022/01/21 11:34:16.270 ecmc:: Ax PosSet PosAct PosErr PosTarg DistLeft CntrOut VelFFSet VelAct VelFFRaw VelRaw Error Co CD St IL LI TS ES En Ex Bu Ta Hd L- L+ Ho +2022/01/21 11:34:16.270 ecmc:: 2 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 -0.000 0 14315 0 0 0 7 16 1 0 00 0 1 1 0 0 0 0 +2022/01/21 11:34:16.296 Starting up EtherCAT bus: 0 second(s). Max wait time 30 second(s). +2022/01/21 11:34:16.370 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=0 fPos=0 fActPosition=0 time=0.000014 +2022/01/21 11:34:16.370 ecmcMotorRecord:: poll(1) bError=1 drvlocal.statusBinData.onChangeData.error=0x14315 +2022/01/21 11:34:16.370 ecmcMotorRecord:: sErrorMessage(1)="ERROR_AXIS_HARDWARE_STATUS_NOT_OK" +2022/01/21 11:34:16.370 ecmcMotorRecord:: poll(1) callParamCallbacksUpdateError Error=1 old=-1 ErrID=0x14315 old=0x0 Warn=0 nCmd=0 old=0 txt=E: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315) +2022/01/21 11:34:16.370 ecmc:: 2 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 -0.000 0 14315 0 0 0 7 7 1 0 00 0 1 1 0 0 0 0 +2022/01/21 11:34:16.370 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=0 fPos=0 fActPosition=0 time=0.000008 +2022/01/21 11:34:16.370 ecmcMotorRecord:: poll(2) bError=1 drvlocal.statusBinData.onChangeData.error=0x14315 +2022/01/21 11:34:16.370 ecmcMotorRecord:: sErrorMessage(2)="ERROR_AXIS_HARDWARE_STATUS_NOT_OK" +2022/01/21 11:34:16.370 ecmcMotorRecord:: poll(2) callParamCallbacksUpdateError Error=1 old=-1 ErrID=0x14315 old=0x0 Warn=0 nCmd=0 old=0 txt=E: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315) +2022/01/21 11:34:16.571 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=0 fPos=0 fActPosition=0 time=0.000012 +2022/01/21 11:34:16.571 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=0 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:16.771 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=0 fPos=0 fActPosition=0 time=0.000019 +2022/01/21 11:34:16.771 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=0 fPos=0 fActPosition=0 time=0.000011 +2022/01/21 11:34:16.875 ecmc:: 2 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 -0.000 0 14315 0 0 0 16 16 1 0 00 0 1 1 0 1 1 0 +2022/01/21 11:34:16.971 ecmcMotorRecord:: poll(1) LLS=0 +2022/01/21 11:34:16.971 ecmcMotorRecord:: poll(1) HLS=0 +2022/01/21 11:34:16.971 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=6.09 time=0.000080 +2022/01/21 11:34:16.971 ecmcMotorRecord:: poll(2) LLS=0 +2022/01/21 11:34:16.971 ecmcMotorRecord:: poll(2) HLS=0 +2022/01/21 11:34:16.971 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=6.12 time=0.000039 +2022/01/21 11:34:16.976 ecmc:: 2 0.000 6.120 -6.120 0.000 -6.120 0.000 0.000 61.200 -0.000 0 14315 0 0 0 16 16 1 0 00 0 1 1 0 1 1 0 +2022/01/21 11:34:17.077 ecmc:: 2 0.000 6.120 -6.120 0.000 -6.120 0.000 0.000 0.000 -0.000 0 14315 0 0 0 16 16 1 0 00 0 1 1 0 1 1 0 +2022/01/21 11:34:17.171 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=6.09 time=0.000011 +2022/01/21 11:34:17.171 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=6.12 time=0.000009 +2022/01/21 11:34:17.203 ../devEcmcSup/motion/ecmcDriveBase.cpp/readEntries:328: WARNING (axis 1): Drive hardware in warning state. +2022/01/21 11:34:17.296 Starting up EtherCAT bus: 1 second(s). Max wait time 30 second(s). +2022/01/21 11:34:17.371 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=6.09 time=0.000011 +2022/01/21 11:34:17.372 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=6.12 time=0.000005 +2022/01/21 11:34:17.434 ../devEcmcSup/motion/ecmcDriveBase.cpp/readEntries:328: WARNING (axis 2): Drive hardware in warning state. +2022/01/21 11:34:17.481 ../devEcmcSup/ethercat/ecmcEc.cpp/checkState:573: ERROR_EC_AL_STATE_PREOP (0x2600f). +2022/01/21 11:34:17.572 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=6.09 time=0.000011 +2022/01/21 11:34:17.572 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=6.12 time=0.000006 +2022/01/21 11:34:17.583 ../devEcmcSup/main/ecmcError.cpp/errorReset:103: NO_ERROR (0x0). +2022/01/21 11:34:17.583 ../devEcmcSup/main/ecmcError.cpp/errorReset:103: NO_ERROR (0x0). +2022/01/21 11:34:17.583 ../devEcmcSup/main/ecmcError.cpp/errorReset:103: NO_ERROR (0x0). +2022/01/21 11:34:17.583 ../devEcmcSup/main/ecmcError.cpp/errorReset:103: NO_ERROR (0x0). +2022/01/21 11:34:17.583 ../devEcmcSup/main/ecmcError.cpp/errorReset:103: NO_ERROR (0x0). +2022/01/21 11:34:17.683 ecmc:: 2 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 -0.000 0 0 0 0 0 0 0 1 0 00 0 1 1 0 1 1 0 +2022/01/21 11:34:17.772 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000014 +2022/01/21 11:34:17.772 ecmcMotorRecord:: poll(1) bError=0 drvlocal.statusBinData.onChangeData.error=0x0 +2022/01/21 11:34:17.772 ecmcMotorRecord:: poll(1) callParamCallbacksUpdateError Error=4 old=1 ErrID=0x0 old=0x14315 Warn=0 nCmd=0 old=0 txt=NULL +2022/01/21 11:34:17.772 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000007 +2022/01/21 11:34:17.772 ecmcMotorRecord:: poll(2) bError=0 drvlocal.statusBinData.onChangeData.error=0x0 +2022/01/21 11:34:17.772 ecmcMotorRecord:: poll(2) callParamCallbacksUpdateError Error=4 old=1 ErrID=0x0 old=0x14315 Warn=0 nCmd=0 old=0 txt=NULL +2022/01/21 11:34:17.972 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000011 +2022/01/21 11:34:17.972 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:18.172 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000011 +2022/01/21 11:34:18.172 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000005 +2022/01/21 11:34:18.373 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000021 +2022/01/21 11:34:18.373 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000010 +2022/01/21 11:34:18.573 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000013 +2022/01/21 11:34:18.573 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:18.773 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000012 +2022/01/21 11:34:18.773 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000050 +2022/01/21 11:34:18.973 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000012 +2022/01/21 11:34:18.973 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000007 +2022/01/21 11:34:19.174 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000012 +2022/01/21 11:34:19.174 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:19.296 EtherCAT bus started! +2022/01/21 11:34:19.296 OK +2022/01/21 11:34:19.296 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAtIocBuild (0). Allow callbacks: true. +Starting iocInit +2022/01/21 11:34:19.296 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAtBeginning (1). Allow callbacks: true. +2022/01/21 11:34:19.320 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterCallbackInit (2). Allow callbacks: true. +2022/01/21 11:34:19.328 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterCaLinkInit (3). Allow callbacks: true. +2022/01/21 11:34:19.328 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterInitDrvSup (4). Allow callbacks: true. +2022/01/21 11:34:19.328 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterInitRecSup (5). Allow callbacks: true. +2022/01/21 11:34:19.334 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterInitDevSup (6). Allow callbacks: true. +2022/01/21 11:34:19.341 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.positionActual01 linked to record (asyn reason 1). +2022/01/21 11:34:19.341 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.encoderLatchPostion01 linked to record (asyn reason 2). +2022/01/21 11:34:19.342 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.encoderControl01 linked to record (asyn reason 3). +2022/01/21 11:34:19.342 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.encoderValue01 linked to record (asyn reason 4). +2022/01/21 11:34:19.343 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.positionActual01 linked to record (asyn reason 5). +2022/01/21 11:34:19.343 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.encoderLatchPostion01 linked to record (asyn reason 6). +2022/01/21 11:34:19.344 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.encoderControl01 linked to record (asyn reason 7). +2022/01/21 11:34:19.344 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.encoderValue01 linked to record (asyn reason 8). +2022/01/21 11:34:19.345 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.timestampLatchPositive01 linked to record (asyn reason 9). +2022/01/21 11:34:19.345 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.timestampLatchNegative01 linked to record (asyn reason 10). +2022/01/21 11:34:19.346 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.timestampLatchPositive02 linked to record (asyn reason 11). +2022/01/21 11:34:19.346 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.timestampLatchNegative02 linked to record (asyn reason 12). +2022/01/21 11:34:19.347 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.driveControl01 linked to record (asyn reason 13). +2022/01/21 11:34:19.347 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.velocitySetpoint01 linked to record (asyn reason 14). +2022/01/21 11:34:19.348 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.positionActual01 linked to record (asyn reason 15). +2022/01/21 11:34:19.349 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.encoderLatchPostion01 linked to record (asyn reason 16). +2022/01/21 11:34:19.350 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.encoderControl01 linked to record (asyn reason 17). +2022/01/21 11:34:19.351 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.encoderValue01 linked to record (asyn reason 18). +2022/01/21 11:34:19.351 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.driveControl01 linked to record (asyn reason 19). +2022/01/21 11:34:19.352 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.velocitySetpoint01 linked to record (asyn reason 20). +2022/01/21 11:34:19.353 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.positionActual01 linked to record (asyn reason 21). +2022/01/21 11:34:19.354 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.encoderLatchPostion01 linked to record (asyn reason 22). +2022/01/21 11:34:19.355 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.encoderControl01 linked to record (asyn reason 23). +2022/01/21 11:34:19.356 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.encoderValue01 linked to record (asyn reason 24). +2022/01/21 11:34:19.358 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.actpos linked to record (asyn reason 25). +2022/01/21 11:34:19.360 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.setpos linked to record (asyn reason 26). +2022/01/21 11:34:19.361 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.poserr linked to record (asyn reason 27). +2022/01/21 11:34:19.362 ecmcAsynPortDriver:drvUserCreate: Parameter plcs.ax1.plc.error linked to record (asyn reason 28). +2022/01/21 11:34:19.366 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.actpos linked to record (asyn reason 29). +2022/01/21 11:34:19.369 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.setpos linked to record (asyn reason 30). +2022/01/21 11:34:19.371 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.poserr linked to record (asyn reason 31). +2022/01/21 11:34:19.373 ecmcAsynPortDriver:drvUserCreate: Parameter plcs.ax2.plc.error linked to record (asyn reason 32). +2022/01/21 11:34:19.374 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000028 +2022/01/21 11:34:19.374 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000047 +2022/01/21 11:34:19.375 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.appmode linked to record (asyn reason 33). +2022/01/21 11:34:19.378 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.error.id linked to record (asyn reason 34). +2022/01/21 11:34:19.379 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.latency.min linked to record (asyn reason 35). +2022/01/21 11:34:19.382 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.latency.max linked to record (asyn reason 36). +2022/01/21 11:34:19.383 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.period.min linked to record (asyn reason 37). +2022/01/21 11:34:19.385 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.period.max linked to record (asyn reason 38). +2022/01/21 11:34:19.387 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.execute.min linked to record (asyn reason 39). +2022/01/21 11:34:19.389 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.execute.max linked to record (asyn reason 40). +2022/01/21 11:34:19.391 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.send.min linked to record (asyn reason 41). +2022/01/21 11:34:19.393 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.thread.send.max linked to record (asyn reason 42). +2022/01/21 11:34:19.394 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput01 linked to record (asyn reason 43). +2022/01/21 11:34:19.396 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput02 linked to record (asyn reason 44). +2022/01/21 11:34:19.397 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput03 linked to record (asyn reason 45). +2022/01/21 11:34:19.400 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput04 linked to record (asyn reason 46). +2022/01/21 11:34:19.402 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput05 linked to record (asyn reason 47). +2022/01/21 11:34:19.404 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput06 linked to record (asyn reason 48). +2022/01/21 11:34:19.405 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput07 linked to record (asyn reason 49). +2022/01/21 11:34:19.407 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.binaryInput08 linked to record (asyn reason 50). +2022/01/21 11:34:19.409 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput01 linked to record (asyn reason 51). +2022/01/21 11:34:19.412 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput02 linked to record (asyn reason 52). +2022/01/21 11:34:19.414 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput03 linked to record (asyn reason 53). +2022/01/21 11:34:19.416 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput04 linked to record (asyn reason 54). +2022/01/21 11:34:19.417 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput05 linked to record (asyn reason 55). +2022/01/21 11:34:19.419 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput06 linked to record (asyn reason 56). +2022/01/21 11:34:19.421 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput07 linked to record (asyn reason 57). +2022/01/21 11:34:19.423 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.binaryOutput08 linked to record (asyn reason 58). +2022/01/21 11:34:19.425 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s5.powerOk01 linked to record (asyn reason 59). +2022/01/21 11:34:19.427 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s5.overload01 linked to record (asyn reason 60). +2022/01/21 11:34:19.429 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.binaryInput01 linked to record (asyn reason 61). +2022/01/21 11:34:19.433 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.binaryInput02 linked to record (asyn reason 62). +2022/01/21 11:34:19.435 ecmcAsynPortDriver:drvUserCreate: Parameter plcs.ax1.plc.enable linked to record (asyn reason 63). +2022/01/21 11:34:19.438 ecmcAsynPortDriver:drvUserCreate: Parameter plcs.ax1.plc.firstscan linked to record (asyn reason 64). +2022/01/21 11:34:19.440 ecmcAsynPortDriver:drvUserCreate: Parameter plcs.ax2.plc.enable linked to record (asyn reason 65). +2022/01/21 11:34:19.444 ecmcAsynPortDriver:drvUserCreate: Parameter plcs.ax2.plc.firstscan linked to record (asyn reason 66). +2022/01/21 11:34:19.447 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.ok linked to record (asyn reason 67). +2022/01/21 11:34:19.450 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.diagnostic linked to record (asyn reason 68). +2022/01/21 11:34:19.452 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.plc.expression linked to record (asyn reason 69). +2022/01/21 11:34:19.453 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.diagnostic linked to record (asyn reason 70). +2022/01/21 11:34:19.455 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.plc.expression linked to record (asyn reason 71). +2022/01/21 11:34:19.456 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.error.msg linked to record (asyn reason 72). +2022/01/21 11:34:19.458 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.updated linked to record (asyn reason 73). +2022/01/21 11:34:19.459 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.command linked to record (asyn reason 74). +2022/01/21 11:34:19.463 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.command linked to record (asyn reason 75). +b",1,1) + dbLoadRecords("ecmcEc.db","P=IOC_TEST:,PORT=MC_CPU1,ADDR=0,TIMEOUT=1,MASTER_ID=0,T_SMP_MS=10,TSE=-2") +ecmcConfigOrDie "Cfg.SetAppMode(1)" +iocInit() +############################################################################ +## EPICS R7.0.5-E3-7.0.5-patch +## Rev. 2021-05-05T19:45+0200 +############################################################################ +ECATtimestamp aSubRecord: IOC_TEST:m0s006-BI01-TimeRiseTS +ECATtimestamp aSubRecord: IOC_TEST:m0s006-BI01-TimeFallTS +ECATtimestamp aSubRecord: IOC_TEST:m0s006-BI02-TimeRiseTS +ECATtimestamp aSubRecord: IOC_TEST:m0s006-BI02-TimeFallTS +2022/01/21 11:34:19.467 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s0.ONE linked to record (asyn reason 76). +2022/01/21 11:34:19.470 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s0.ZERO linked to record (asyn reason 77). +2022/01/21 11:34:19.473 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.ONE linked to record (asyn reason 78). +2022/01/21 11:34:19.475 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.ZERO linked to record (asyn reason 79). +2022/01/21 11:34:19.478 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.ONE linked to record (asyn reason 80). +2022/01/21 11:34:19.480 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.ZERO linked to record (asyn reason 81). +2022/01/21 11:34:19.482 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.ONE linked to record (asyn reason 82). +2022/01/21 11:34:19.485 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.ZERO linked to record (asyn reason 83). +2022/01/21 11:34:19.488 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.ONE linked to record (asyn reason 84). +2022/01/21 11:34:19.490 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.ZERO linked to record (asyn reason 85). +2022/01/21 11:34:19.493 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s5.ONE linked to record (asyn reason 86). +2022/01/21 11:34:19.496 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s5.ZERO linked to record (asyn reason 87). +2022/01/21 11:34:19.499 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.ONE linked to record (asyn reason 88). +2022/01/21 11:34:19.502 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.ZERO linked to record (asyn reason 89). +2022/01/21 11:34:19.505 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.ONE linked to record (asyn reason 90). +2022/01/21 11:34:19.508 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.ZERO linked to record (asyn reason 91). +2022/01/21 11:34:19.511 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.ONE linked to record (asyn reason 92). +2022/01/21 11:34:19.513 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.ZERO linked to record (asyn reason 93). +2022/01/21 11:34:19.517 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.cmddata linked to record (asyn reason 94). +2022/01/21 11:34:19.520 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.cmddata linked to record (asyn reason 95). +2022/01/21 11:34:19.523 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s0.slavestatus linked to record (asyn reason 96). +2022/01/21 11:34:19.526 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s1.slavestatus linked to record (asyn reason 97). +2022/01/21 11:34:19.529 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s2.slavestatus linked to record (asyn reason 98). +2022/01/21 11:34:19.531 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.slavestatus linked to record (asyn reason 99). +2022/01/21 11:34:19.534 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.slavestatus linked to record (asyn reason 100). +2022/01/21 11:34:19.537 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s5.slavestatus linked to record (asyn reason 101). +2022/01/21 11:34:19.540 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.slavestatus linked to record (asyn reason 102). +2022/01/21 11:34:19.543 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.slavestatus linked to record (asyn reason 103). +2022/01/21 11:34:19.546 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.slavestatus linked to record (asyn reason 104). +2022/01/21 11:34:19.548 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.status linked to record (asyn reason 105). +2022/01/21 11:34:19.551 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.errorid linked to record (asyn reason 106). +2022/01/21 11:34:19.554 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.status linked to record (asyn reason 107). +2022/01/21 11:34:19.557 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.errorid linked to record (asyn reason 108). +2022/01/21 11:34:19.560 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.masterstatus linked to record (asyn reason 109). +2022/01/21 11:34:19.563 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.slavecounter linked to record (asyn reason 110). +2022/01/21 11:34:19.566 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.memmapcounter linked to record (asyn reason 111). +2022/01/21 11:34:19.569 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.domainfailcountertotal linked to record (asyn reason 112). +2022/01/21 11:34:19.572 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.entrycounter linked to record (asyn reason 113). +2022/01/21 11:34:19.574 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000025 +2022/01/21 11:34:19.574 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000013 +2022/01/21 11:34:19.575 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.domainstatus linked to record (asyn reason 114). +2022/01/21 11:34:19.578 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.control linked to record (asyn reason 115). +2022/01/21 11:34:19.581 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.control linked to record (asyn reason 116). +2022/01/21 11:34:19.585 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s3.encoderStatus01 linked to record (asyn reason 117). +2022/01/21 11:34:19.589 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s4.encoderStatus01 linked to record (asyn reason 118). +2022/01/21 11:34:19.592 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.status01 linked to record (asyn reason 119). +2022/01/21 11:34:19.596 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s6.status02 linked to record (asyn reason 120). +2022/01/21 11:34:19.599 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.driveStatus01 linked to record (asyn reason 121). +2022/01/21 11:34:19.603 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s8.encoderStatus01 linked to record (asyn reason 122). +2022/01/21 11:34:19.607 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.driveStatus01 linked to record (asyn reason 123). +2022/01/21 11:34:19.611 ecmcAsynPortDriver:drvUserCreate: Parameter ec0.s9.encoderStatus01 linked to record (asyn reason 124). +2022/01/21 11:34:19.649 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.targpos linked to record (asyn reason 125). +2022/01/21 11:34:19.653 ecmcAsynPortDriver:drvUserCreate: Parameter ax1.targvelo linked to record (asyn reason 126). +2022/01/21 11:34:19.658 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.targpos linked to record (asyn reason 127). +2022/01/21 11:34:19.662 ecmcAsynPortDriver:drvUserCreate: Parameter ax2.targvelo linked to record (asyn reason 128). +2022/01/21 11:34:19.677 ecmcAsynPortDriver:drvUserCreate: Parameter ecmc.error.reset linked to record (asyn reason 129). +2022/01/21 11:34:19.681 ecmcMotorRecord:: setIntegerParam(1 motorUpdateStatus_)=0 +2022/01/21 11:34:19.682 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000017 +2022/01/21 11:34:19.683 ecmcMotorRecord:: setIntegerParam(2 motorUpdateStatus_)=0 +2022/01/21 11:34:19.683 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000014 +2022/01/21 11:34:19.729 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterInitDatabase (7). Allow callbacks: true. +2022/01/21 11:34:19.729 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterFinishDevSup (8). Allow callbacks: true. +2022/01/21 11:34:19.774 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000008 +2022/01/21 11:34:19.774 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000008 +2022/01/21 11:34:19.975 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000008 +2022/01/21 11:34:19.975 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:20.175 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000012 +2022/01/21 11:34:20.175 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000008 +2022/01/21 11:34:20.265 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterScanInit (9). Allow callbacks: true. +2022/01/21 11:34:20.267 ecmcMotorRecord:: setIntegerParam(1 HomProc_)=3 motorNotHomedProblem=0 +2022/01/21 11:34:20.267 ecmcMotorRecord:: setIntegerParam(2 HomProc_)=3 motorNotHomedProblem=0 +2022/01/21 11:34:20.270 ecmcMotorRecord:: setDoubleParam(1 HomPos_)=0.000000 +2022/01/21 11:34:20.270 ecmcMotorRecord:: setDoubleParam(2 HomPos_)=0.000000 +2022/01/21 11:34:20.270 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterInitialProcess (10). Allow callbacks: true. +2022/01/21 11:34:20.281 ecmcAsynPortDriver:getEpicsState: EPICS state: Unknown state (11). Allow callbacks: true. +2022/01/21 11:34:20.282 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterIocBuilt (12). Allow callbacks: true. +2022/01/21 11:34:20.336 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAtIocRun (13). Allow callbacks: true. +2022/01/21 11:34:20.336 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterDatabaseRunning (14). Allow callbacks: true. +2022/01/21 11:34:20.336 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterInterruptAccept (28). Allow callbacks: true. +2022/01/21 11:34:20.336 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterCaServerRunning (15). Allow callbacks: true. +2022/01/21 11:34:20.336 ecmcAsynPortDriver:getEpicsState: EPICS state: Unknown state (29). Allow callbacks: true. +iocRun: All initialization complete +2022/01/21 11:34:20.375 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000017 +2022/01/21 11:34:20.375 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000235 +2022/01/21 11:34:20.401 ecmcAsynPortDriver:getEpicsState: EPICS state: initHookAfterIocRunning (16). Allow callbacks: true. +2022/01/21 11:34:20.405 ../devEcmcSup/motion/ecmcDriveBase.cpp/readEntries:336: INFO (axis 1): Drive hardware warning state cleared. +2022/01/21 11:34:20.576 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000011 +2022/01/21 11:34:20.576 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:19.681 [devMotorAsyn.c:439 IOC_TEST:Axis1] init_record IOC_TEST:Axis1 position=0.000000 encoderPos=0.000000 velocity=0.000000 MSTAstatus=0x0f00 flagsValue=0x3f flagsWritten=0x3f pmr->mflg=0x0 +2022/01/21 11:34:19.681 [devMotorAsyn.c:185 IOC_TEST:Axis1] init_controller IOC_TEST:Axis1 set encoder ratio=1.000000 status=0 +2022/01/21 11:34:19.681 [devMotorAsyn.c:266 IOC_TEST:Axis1] update_soft_limits IOC_TEST:Axis1 RawHLM_RO=130.000000 RawLLM_RO=-20.000000 valid=1 DHLM_RO=130.000000 DLLM_RO=-20.000000 +2022/01/21 11:34:19.681 [motorDevSup.c:327 IOC_TEST:Axis1] PositionRestoreNeeded IOC_TEST:Axis1 rstm=2 dval=0.000000 drbv=0.000000 pmr->rdbd=0.100000 rdbd=0.100000 pmr->mres=0.030000 pmr->mflg=0x3f dval_non_zero_pos_near_zero=0 ret=0 +2022/01/21 11:34:19.681 [motorRecord.cc:782 IOC_TEST:Axis1] init_re_init start neverPolled=0 stat=17 nsta=0 +2022/01/21 11:34:19.681 [motorRecord.cc:720 IOC_TEST:Axis1] enforceMinRetryDeadband spdb=0.100000 rdbd=0.100000 mres=0.030000 +2022/01/21 11:34:19.681 [motorRecord.cc:4484 IOC_TEST:Axis1] pmr->dhlm=130 softLimitRO=130 +2022/01/21 11:34:19.681 [motorRecord.cc:4545 IOC_TEST:Axis1] pmr->dllm=-20 softLimitRO=-20 +2022/01/21 11:34:19.681 [motorRecord.cc:833 IOC_TEST:Axis1] init_re_init end dval=0.000000 drbv=0.000000 rdbd=0.100000 spdb=0.100000 +2022/01/21 11:34:19.681 [motorRecord.cc:968 IOC_TEST:Axis1] init_record process_reason="callbackdata + soft limits" dval=0.000000 drbv=0.000000 rdbd=0.100000 spdb=0.100000 stat=0 msta=0xf00 neverPolled=0 +2022/01/21 11:34:19.682 [devMotorAsyn.c:439 IOC_TEST:Axis2] init_record IOC_TEST:Axis2 position=0.000000 encoderPos=0.000000 velocity=0.000000 MSTAstatus=0x0f00 flagsValue=0x3f flagsWritten=0x3f pmr->mflg=0x0 +2022/01/21 11:34:19.683 [devMotorAsyn.c:185 IOC_TEST:Axis2] init_controller IOC_TEST:Axis2 set encoder ratio=1.000000 status=0 +2022/01/21 11:34:19.683 [devMotorAsyn.c:266 IOC_TEST:Axis2] update_soft_limits IOC_TEST:Axis2 RawHLM_RO=20.000000 RawLLM_RO=-130.000000 valid=1 DHLM_RO=20.000000 DLLM_RO=-130.000000 +2022/01/21 11:34:19.683 [motorDevSup.c:327 IOC_TEST:Axis2] PositionRestoreNeeded IOC_TEST:Axis2 rstm=2 dval=0.000000 drbv=0.000000 pmr->rdbd=0.100000 rdbd=0.100000 pmr->mres=0.030000 pmr->mflg=0x3f dval_non_zero_pos_near_zero=0 ret=0 +2022/01/21 11:34:19.683 [motorRecord.cc:782 IOC_TEST:Axis2] init_re_init start neverPolled=0 stat=17 nsta=0 +2022/01/21 11:34:19.683 [motorRecord.cc:720 IOC_TEST:Axis2] enforceMinRetryDeadband spdb=0.100000 rdbd=0.100000 mres=0.030000 +2022/01/21 11:34:19.683 [motorRecord.cc:4484 IOC_TEST:Axis2] pmr->dhlm=20 softLimitRO=20 +2022/01/21 11:34:19.683 [motorRecord.cc:4545 IOC_TEST:Axis2] pmr->dllm=-130 softLimitRO=-130 +2022/01/21 11:34:19.683 [motorRecord.cc:833 IOC_TEST:Axis2] init_re_init end dval=0.000000 drbv=0.000000 rdbd=0.100000 spdb=0.100000 +2022/01/21 11:34:19.683 [motorRecord.cc:968 IOC_TEST:Axis2] init_record process_reason="callbackdata + soft limits" dval=0.000000 drbv=0.000000 rdbd=0.100000 spdb=0.100000 stat=0 msta=0xf00 neverPolled=0 +# Set the IOC Prompt String One +epicsEnvSet IOCSH_PS1 "raspberrypi-2584 > " +# +raspberrypi-2584 > 2022/01/21 11:34:20.776 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000010 +2022/01/21 11:34:20.776 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000006 +2022/01/21 11:34:20.994 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=0 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.018135 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../ecmc_plugin_grbl/ecmcGrbl.cpp:doWriteWorker:237: Command in buffer!!! +../ecmc_plugin_grbl/ecmcGrbl.cpp:doWriteWorker:242: Command length 11!!! +../ecmc_plugin_grbl/ecmcGrbl.cpp:doWriteWorker:243: Available bytes 1024!!! +Adding G to buffer +Adding 1 to buffer G +Adding X to buffer G1 +Adding 0 to buffer G1X +Adding Y to buffer G1X0 +Adding 2 to buffer G1X0Y +Adding 0 to buffer G1X0Y2 +Adding F to buffer G1X0Y20 +Adding 2 to buffer G1X0Y20F +Adding 0 to buffer G1X0Y20F2 +Adding + to buffer G1X0Y20F20 +../ecmc_plugin_grbl/ecmcGrbl.cpp:doWriteWorker:249: Writing!! +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_gcode.c:gc_execute_line:71:G1X0Y20F20 +1 +letter=G +value=1.000000 +int_value=1 +mantissa=0 +axis_command=2 +here!! +here 2!! +here 3!! +../grbl/grbl_gcode.c:gc_execute_line:348: +1 +letter=X +value=0.000000 +int_value=0 +mantissa=0 +../grbl/grbl_gcode.c:gc_execute_line:348: +1 +letter=Y +value=20.000000 +int_value=20 +mantissa=0 +../grbl/grbl_gcode.c:gc_execute_line:348: +1 +letter=F +value=20.000000 +int_value=20 +mantissa=0 +../grbl/grbl_gcode.c:gc_execute_line:348: +../grbl/grbl_gcode.c:gc_execute_line:383:axis_words=3 +../grbl/grbl_gcode.c:gc_execute_line:384:axis_command=2 +../grbl/grbl_gcode.c:gc_execute_line:389:axis_command=2 +../grbl/grbl_gcode.c:gc_execute_line:395 +../grbl/grbl_gcode.c:gc_execute_line:410:gc_parser_flags=0 +../grbl/grbl_gcode.c:gc_execute_line:416:gc_block.modal.feed_rate=0 +../grbl/grbl_motion_control.c:mc_line:33 +../grbl/grbl_stepper.c:st_next_block_index:673 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +ok +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +2022/01/21 11:34:20.994 [motorRecord.cc:1522 IOC_TEST:Axis1] msta.Bits.EA_POSITION power on=1 +2022/01/21 11:34:20.994 [motorRecord.cc:1627 IOC_TEST:Axis1] mipSetBit EXTERNAL(Ex) old='' new=EXTERNAL(Ex) +2022/01/21 11:34:20.995 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000319 +2022/01/21 11:34:21.206 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=0 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.011517 +2022/01/21 11:34:21.233 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.026462 +2022/01/21 11:34:21.447 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=0 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.013432 +2022/01/21 11:34:21.473 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.026340 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +[X_AXIS]= 0.000000/250.000000=0.000000 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Se2022/01/21 11:34:21.685 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=0 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.012073 +2022/01/21 11:34:21.686 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000555 +2022/01/21 11:34:21.896 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=0 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.009717 +2022/01/21 11:34:21.896 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000472 +2022/01/21 11:34:22.106 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=0 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.009401 +2022/01/21 11:34:22.107 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000461 +gment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +[X_AXIS]= 0.000000/250.000000=0.000000 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X2022/01/21 11:34:22.371 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.063914 +2022/01/21 11:34:22.397 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.026366 +2022/01/21 11:34:22.610 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.012821 +2022/01/21 11:34:22.637 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.026646 +_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_2022/01/21 11:34:22.850 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.012370 +2022/01/21 11:34:22.851 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000940 +2022/01/21 11:34:23.063 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.011691 +2022/01/21 11:34:23.089 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.026514 +2022/01/21 11:34:23.302 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.012854 +2022/01/21 11:34:23.329 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.026188 +AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +../grbl/grbl_stepper.c:st_wake_up:266 +Segment buffer empty!!!!!!!!!!!!!!!!!!!!!../grbl/grbl_stepper.c:st_go_idle:297 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXI2022/01/21 11:34:23.529 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=1 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000265 +2022/01/21 11:34:23.530 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000431 +S]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 2022/01/21 11:34:23.730 ../devEcmcSup/motion/ecmcAxisBase.cpp/preExecute:261: ERROR (axis 1): State change (ECMC_AXIS_STATE_ENABLED->ECMC_AXIS_STATE_STARTUP). +2022/01/21 11:34:23.730 ../devEcmcSup/motion/ecmcAxisReal.cpp/execute:185: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315). +2022/01/21 11:34:23.730 ../devEcmcSup/motion/ecmcAxisBase.cpp/preExecute:232: ERROR (axis 2): State change (ECMC_AXIS_STATE_DISABLED->ECMC_AXIS_STATE_STARTUP). +2022/01/21 11:34:23.730 ../devEcmcSup/motion/ecmcAxisReal.cpp/execute:185: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315). +2022/01/21 11:34:23.730 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000534 +2022/01/21 11:34:23.730 ecmcMotorRecord:: poll(1) bError=1 drvlocal.statusBinData.onChangeData.error=0x14315 +2022/01/21 11:34:23.731 ecmcMotorRecord:: sErrorMessage(1)="ERROR_AXIS_HARDWARE_STATUS_NOT_OK" +2022/01/21 11:34:23.731 ecmcMotorRecord:: poll(1) callParamCallbacksUpdateError Error=1 old=4 ErrID=0x14315 old=0x0 Warn=0 nCmd=0 old=0 txt=E: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315) +0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +2022/01/21 11:34:23.731 [motorRecord.cc:1522 IOC_TEST:Axis1] msta.Bits.EA_POSITION power on=0 +2022/01/21 11:34:23.731 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000339 +2022/01/21 11:34:23.731 ecmcMotorRecord:: poll(2) bError=1 drvlocal.statusBinData.onChangeData.error=0x14315 +2022/01/21 11:34:23.731 ecmcMotorRecord:: sErrorMessage(2)="ERROR_AXIS_HARDWARE_STATUS_NOT_OK" +2022/01/21 11:34:23.731 ecmcMotorRecord:: poll(2) callParamCallbacksUpdateError Error=1 old=4 ErrID=0x14315 old=0x0 Warn=0 nCmd=0 old=0 txt=E: ERROR_AXIS_HARDWARE_STATUS_NOT_OK (0x14315) +[X_AXIS]= 0.000000/250.000000=0.000000 +2022/01/21 11:34:23.731 [motorRecord.cc:1627 IOC_TEST:Axis2] mipSetBit EXTERNAL(Ex) old='' new=EXTERNAL(Ex) +2022/01/21 11:34:23.782 ecmc:: 2 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 -0.000 0 14315 0 0 0 0 16 1 0 00 0 1 1 0 1 1 0 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X2022/01/21 11:34:23.884 ../devEcmcSup/motion/ecmcDriveBase.cpp/readEntries:328: WARNING (axis 1): Drive hardware in warning state. +_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_2022/01/21 11:34:23.932 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000521 +2022/01/21 11:34:23.932 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000462 +AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS2022/01/21 11:34:24.122 ../devEcmcSup/motion/ecmcAxisBase.cpp/preExecute:232: ERROR (axis 1): State change (ECMC_AXIS_STATE_DISABLED->ECMC_AXIS_STATE_STARTUP). +2022/01/21 11:34:24.122 ../devEcmcSup/motion/ecmcAxisBase.cpp/preExecute:232: ERROR (axis 2): State change (ECMC_AXIS_STATE_DISABLED->ECMC_AXIS_STATE_STARTUP). +2022/01/21 11:34:24.133 ecmcMotorRecord:: poll(1) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=65332 fPos=0 fActPosition=0 time=0.000504 +2022/01/21 11:34:24.133 ecmcMotorRecord:: poll(2) mvnNRdy=1 bBusy=1 bExecute=0 bEnabled=0 atTarget=1 wf=0 ENC=204 fPos=0 fActPosition=0 time=0.000451 +]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS]= 0.000000/250.000000=0.000000 +[X_AXIS] \ No newline at end of file diff --git a/iocsh/test.script b/iocsh/test.script index 457eaa8..207f992 100644 --- a/iocsh/test.script +++ b/iocsh/test.script @@ -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("$"); #