RPi4 & 7i96 XY2-100 Following Error at High Velocities

More
05 May 2021 17:38 #208004 by Limedodge
I've been working to get my laser galvo setup running. I have solved my "error finishing read" issue by switching to a different Rpi OS. now I can run a 500,000ns servo thread indefinitely without getting the read error. Success!

I've also hooked it up the hardware and can burn lines. Success!... sorta

I can only get it to function if I manually limit max velocity below 600mm/min. If I go above that, I get following errors.

I set the ini inputs per guidance of P=1/servo interval=2000
[AXIS_X]

MIN_LIMIT = -150.0
MAX_LIMIT = 150.0
MAX_VELOCITY = 2000
MAX_ACCELERATION = 20000

[JOINT_0]

TYPE =              LINEAR
MAX_VELOCITY =       2400
MAX_ACCELERATION =   240000
# Set Stepgen max 20% higher than the axis

#BACKLASH =           0.000

# scale is XXX step/mm
SCALE =           0.01

MIN_LIMIT =             -150.0
MAX_LIMIT =             150.0

FERROR =    .020
MIN_FERROR = .01

#HOME =                  0.000
#HOME_OFFSET =           0.10
#HOME_SEARCH_VEL =       0.10
#HOME_LATCH_VEL =        -0.01
#HOME_USE_INDEX =        YES
#HOME_IGNORE_LIMITS =    YES

# PID tuning params
DEADBAND =              0
P =                     2000
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.001
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0
#MAX_ERROR =		0.001

I get oscillations at P=2000



I get overshoot and ringing at P=1000



Slightly milder overshoot at P=500



Here's a scope screenshot of the following error.




A few notes:
Both X and Y axis (joints 0 and 1) are identical setups
Max velocity and accelerations are guesses. The velocity less so as I can back out a linear velocity from the galvometer spec.

I intended on figuring out the real max velocity/accelerations based on physical limitations after I get the controller hardware up and running. By running paths at different velocities and accelerations and seeing what the machine can handle

Any thoughts on the following errors?

I noticed there's no STEPGEN_MAX_VELOCITY input for XY2-100.
Attachments:

Please Log in or Create an account to join the conversation.

More
05 May 2021 19:15 - 05 May 2021 21:15 #208013 by PCW
That's really odd to get a following error at 0 velocity
Can you post your hal/ini files?

Note: you can improve the control bandwidth by not setting
the DPLL write timer (comment out any line setting this value)
If you do this, FF2 can be set smaller (say 0.00025) since
this will be the approximate time between reads and writes.

Your oscillation at the suggested P values is likely due to using
the same timer for read and write, this adds a full servo thread
period delay to the feedback loop.
Last edit: 05 May 2021 21:15 by PCW.

Please Log in or Create an account to join the conversation.

More
05 May 2021 21:16 #208024 by Limedodge
I've attached my .ini and .hal file. Please excuse the mess, I need to go back through and clean them up (including removing the unused spindle portions)

# This config file was created 2021-05-04 
    
[EMC]


# The version string for this INI file.
VERSION = 1.1

# Name of machine, for use with display, etc.
MACHINE =               HM2-Stepper

# Debug level, 0 means no messages. See src/emc/nml_int/emcglb.h for others
#DEBUG =                0x00000003
#DEBUG =                0x00000007
DEBUG = 0

[DISPLAY]


# Name of display program, e.g., tkemc
#DISPLAY =               tkemc
DISPLAY =              axis

# Cycle time, in seconds, that display will sleep between polls
CYCLE_TIME =            0.100

# Path to help file
HELP_FILE =             tkemc.txt

# Initial display setting for position, RELATIVE or MACHINE
POSITION_OFFSET =       RELATIVE

# Initial display setting for position, COMMANDED or ACTUAL
POSITION_FEEDBACK =     ACTUAL

# Highest value that will be allowed for feed override, 1.0 = 100%
MAX_FEED_OVERRIDE =     30
MAX_LINEAR_VELOCITY = 350
# Prefix to be used
PROGRAM_PREFIX = /home/pi/linuxcnc/nc_files/

# Introductory graphic
INTRO_GRAPHIC =         emc2.gif
INTRO_TIME =            5

[FILTER]


PROGRAM_EXTENSION = .png,.gif,.jpg Grayscale Depth Image
PROGRAM_EXTENSION = .py Python Script
png = image-to-gcode
gif = image-to-gcode
jpg = image-to-gcode
py = python

[RS274NGC]


# File containing interpreter variables
PARAMETER_FILE =        hm2-stepper.var
SUBROUTINE_PATH=/home/pi/linuxcnc-dev/nc_files/remap_lib/common_nc_subs

# this is important - read common_nc_subs/reset_state.ngc
# ON_ABORT_COMMAND= O <RESET_STATE> call

[EMCMOT]


EMCMOT =                motmod

# Timeout for comm to emcmot, in seconds
COMM_TIMEOUT =          1.0

# Interval between tries to emcmot, in seconds
COMM_WAIT =             0.010

# Servo task period, in nanoseconds
SERVO_PERIOD =          500000

[TASK]


# Name of task controller program, e.g., milltask
TASK =                  milltask

# Cycle time, in seconds, that task controller will sleep between polls
CYCLE_TIME =            0.010

[HAL]


# The run script first uses halcmd to execute any HALFILE
# files, and then to execute any individual HALCMD commands.

# list of hal config files to run through halcmd
# files are executed in the order in which they appear

HALFILE =		hm2-pidstepper-master-pexy100.hal

# list of halcmd commands to execute
# commands are executed in the order in which they appear
#HALCMD =               save neta

[HALUI]


#No Content

[TRAJ]


AXES =                  6
COORDINATES =           X Y Z A B C
#HOME =                 0 0 0
#JOINTS=7
LINEAR_UNITS =          mm
ANGULAR_UNITS =         degree
#CYCLE_TIME =           0.1
NO_FORCE_HOMING =	1
MAX_VELOCITY =          2000
MAX_ACCELERATION =      200000


[EMCIO]


# Name of IO controller program, e.g., io
EMCIO =                 io

# cycle time, in seconds
CYCLE_TIME =            0.100

# tool table file
TOOL_TABLE =            tool.tbl

[KINS]

KINEMATICS = trivkins
#This is a best-guess at the number of joints, it should be checked
JOINTS = 7

[AXIS_X]

MIN_LIMIT = -150.0
MAX_LIMIT = 150.0
MAX_VELOCITY = 2000
MAX_ACCELERATION = 20000

[JOINT_0]

TYPE =              LINEAR
MAX_VELOCITY =       2400
MAX_ACCELERATION =   240000
# Set Stepgen max 20% higher than the axis

#BACKLASH =           0.000

# scale is XXX step/mm
SCALE =           0.01

MIN_LIMIT =             -150.0
MAX_LIMIT =             150.0

FERROR =    .020
MIN_FERROR = .01

#HOME =                  0.000
#HOME_OFFSET =           0.10
#HOME_SEARCH_VEL =       0.10
#HOME_LATCH_VEL =        -0.01
#HOME_USE_INDEX =        YES
#HOME_IGNORE_LIMITS =    YES

# PID tuning params
DEADBAND =              0
P =                     1900
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.001
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0
#MAX_ERROR =		0.001

[AXIS_Y]
MIN_LIMIT = -150.0
MAX_LIMIT = 150.0
MAX_VELOCITY = 2000
MAX_ACCELERATION = 200000

[JOINT_1]


TYPE =              LINEAR
MAX_VELOCITY =       2400
MAX_ACCELERATION =   240000
#MAX_JERK =   2000

#BACKLASH =           0.000

SCALE = 0.01

MIN_LIMIT =             -150.0
MAX_LIMIT =             150.0

FERROR =    .020
MIN_FERROR = .01

#
# PID tuning params
DEADBAND =              0
P =                     1900
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.001
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0



[AXIS_Z]
MIN_LIMIT = -3000.0
MAX_LIMIT = 3000.0
MAX_VELOCITY = 200
MAX_ACCELERATION = 2000

[JOINT_2]


TYPE =              LINEAR
MAX_VELOCITY =      200
MAX_ACCELERATION =  2000
MAX_JERK =   2000
# Set Stepgen max 20% higher than the axis
STEPGEN_MAX_VEL =    240
STEPGEN_MAX_ACC =    2400

BACKLASH =           0.000

SCALE = 334

MIN_LIMIT =             -3000.0
MAX_LIMIT =             3000.0

FERROR =    .020
MIN_FERROR = .0005

#HOME =                  0.000
#HOME_OFFSET =           0.10
#HOME_SEARCH_VEL =       0.10
#HOME_LATCH_VEL =        -0.01
#HOME_USE_INDEX =        YES
#HOME_IGNORE_LIMITS =    YES

# these are in nanoseconds
DIRSETUP   =              3000
DIRHOLD    =              3000
STEPLEN    =              3000
STEPSPACE  =              3000

# PID tuning params
DEADBAND =              0
P =                     1000
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.00025
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0

[AXIS_A]
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
MAX_VELOCITY = 200
MAX_ACCELERATION = 2000

[JOINT_3]


TYPE =              LINEAR
MAX_VELOCITY =      200
MAX_ACCELERATION =  2000
MAX_JERK =   2000
# Set Stepgen max 20% higher than the axis
STEPGEN_MAX_VEL =    240
STEPGEN_MAX_ACC =    2400

BACKLASH =           0.000

SCALE = 334

MIN_LIMIT =             -3000.0
MAX_LIMIT =             3000.0

FERROR =    .020
MIN_FERROR = .0005

#HOME =                  0.000
#HOME_OFFSET =           0.10
#HOME_SEARCH_VEL =       0.10
#HOME_LATCH_VEL =        -0.01
#HOME_USE_INDEX =        YES
#HOME_IGNORE_LIMITS =    YES

# these are in nanoseconds
DIRSETUP   =              3000
DIRHOLD    =              3000
STEPLEN    =              3000
STEPSPACE  =              3000

# PID tuning params
DEADBAND =              0
P =                     1000
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.00025
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0

[AXIS_B]
MIN_LIMIT = -3000.0
MAX_LIMIT = 3000.0
MAX_VELOCITY = 200
MAX_ACCELERATION = 2000

[JOINT_4]


TYPE =              LINEAR
MAX_VELOCITY =      200
MAX_ACCELERATION =  2000
MAX_JERK =   2000
# Set Stepgen max 20% higher than the axis
STEPGEN_MAX_VEL =    240
STEPGEN_MAX_ACC =    2400

BACKLASH =           0.000

SCALE = 40

MIN_LIMIT =             -3000.0
MAX_LIMIT =             3000.0

FERROR =    .020
MIN_FERROR = .0005

#HOME =                  0.000
#HOME_OFFSET =           0.10
#HOME_SEARCH_VEL =       0.10
#HOME_LATCH_VEL =        -0.01
#HOME_USE_INDEX =        YES
#HOME_IGNORE_LIMITS =    YES

# these are in nanoseconds
DIRSETUP   =              2000
DIRHOLD    =              2000
STEPLEN    =              4000
STEPSPACE  =              4000

# PID tuning params
DEADBAND =              0
P =                     1000
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.00025
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0

[AXIS_C]
MIN_LIMIT = -300.0
MAX_LIMIT = 300.0
MAX_VELOCITY = 200
MAX_ACCELERATION = 2000

[JOINT_5]


TYPE =              LINEAR
MAX_VELOCITY =      200
MAX_ACCELERATION =  2000
MAX_JERK =   2000
# Set Stepgen max 20% higher than the axis
STEPGEN_MAX_VEL =    240
STEPGEN_MAX_ACC =    2400

BACKLASH =           0.000

SCALE = 40

MIN_LIMIT =             -300.0
MAX_LIMIT =             300.0

FERROR =    .020
MIN_FERROR = .0005

#HOME =                  0.000
#HOME_OFFSET =           0.10
#HOME_SEARCH_VEL =       0.10
#HOME_LATCH_VEL =        -0.01
#HOME_USE_INDEX =        YES
#HOME_IGNORE_LIMITS =    YES

# these are in nanoseconds
DIRSETUP   =              2000
DIRHOLD    =              2000
STEPLEN    =              4000
STEPSPACE  =              4000

# PID tuning params
DEADBAND =              0
P =                     1000
I =                     0
D =                     0
FF0 =                   0
FF1 =                   1
FF2 =			0.00025
BIAS =                  0
MAX_OUTPUT =		0
MAX_ERROR =		0

[HOSTMOT2]
DRIVER=hm2_eth board_ip="10.10.10.10" 
# DRIVER=hm2_eth board_ip="10.10.10.10" debug=-1
BOARD=7i96
CONFIG="num_encoders=1 num_stepgens=5 num_pwmgens=0 sserial_port_0=0000xxxx enable_raw"

[SPINDLE_9]

# PID tuning params
DEADBAND =              0
P =                     50
I =                     200
D =                     0.2
FF0 =                   0
FF1 =                   0
FF2 =							0
BIAS =                  0
MAX_OUTPUT =				0
MAX_ERROR =					50
SCALE =						6000
MINLIM =						0
MAXLIM =						6000
# #######################################
#
# HAL file for HostMot2 with 3 steppers
#
# Derived from Ted Hyde's original hm2-servo config
#
# Based up work and discussion with Seb & Peter & Jeff
# GNU license references - insert here. www.linuxcnc.org
#
#
# ########################################
# Firmware files are in /lib/firmware/hm2/7i43/
# Must symlink the hostmot2 firmware directory of sanbox to
# /lib/firmware before running EMC2...
# sudo ln -s $HOME/emc2-sandbox/src/hal/drivers/mesa-hostmot2/firmware /lib/firmware/hm2
#
# See also:
# <http://www.linuxcnc.org/docs/devel/html/man/man9/hostmot2.9.html#config%20modparam>
# and http://wiki.linuxcnc.org/cgi-bin/emcinfo.pl?HostMot2
#
# #####################################################################


# ###################################
# Core EMC/HAL Loads
# ###################################


# kinematics
loadrt [KINS]KINEMATICS
#autoconverted  trivkins

# motion controller
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS num_spindles=1

# standard components
loadrt pid num_chan=7 
loadrt mux2 count=7
loadrt oneshot count=1
loadrt and2 count=1
loadrt comp count=1

# hostmot2 driver
loadrt hostmot2

# load low-level driver
loadrt [HOSTMOT2](DRIVER) config=[HOSTMOT2](CONFIG)

setp hm2_[HOSTMOT2](BOARD).0.watchdog.timeout_ns 25000000


# ################################################
# THREADS
# ################################################

addf hm2_[HOSTMOT2](BOARD).0.read         servo-thread
addf mux2.0                               servo-thread
addf mux2.1                               servo-thread
addf mux2.2                               servo-thread
addf mux2.3                               servo-thread
addf mux2.4                               servo-thread
addf mux2.5                               servo-thread
addf mux2.6                               servo-thread
addf and2.0                               servo-thread
addf motion-command-handler               servo-thread
addf motion-controller                    servo-thread
addf pid.0.do-pid-calcs                   servo-thread
addf pid.1.do-pid-calcs                   servo-thread
addf pid.2.do-pid-calcs                   servo-thread
addf pid.3.do-pid-calcs                   servo-thread
addf pid.4.do-pid-calcs                   servo-thread
addf pid.5.do-pid-calcs                   servo-thread
addf pid.6.do-pid-calcs                   servo-thread
addf hm2_[HOSTMOT2](BOARD).0.write        servo-thread
#addf hm2_[HOSTMOT2](BOARD).0.pet_watchdog servo-thread
addf oneshot.0                            servo-thread	
addf comp.0                               servo-thread	
       

# latch 50 usec before nominal read time:
setp hm2_[HOSTMOT2](BOARD).0.dpll.01.timer-us -100
setp hm2_[HOSTMOT2](BOARD).0.stepgen.timer-number -1
## orig setp hm2_[HOSTMOT2](BOARD).0.xy2mod.timer-number 1
setp hm2_[HOSTMOT2](BOARD).0.xy2mod.read-timer-number 1
setp hm2_[HOSTMOT2](BOARD).0.xy2mod.write-timer-number 1
setp hm2_[HOSTMOT2](BOARD).0.packet-read-timeout 80
setp hm2_[HOSTMOT2](BOARD).0.packet-error-limit 50


# ######################################################
# Axis-of-motion Specific Configs (not the GUI)
# ######################################################

# switch fb data to command on packet error:
net perror  hm2_[HOSTMOT2](BOARD).0.packet-error => mux2.0.sel mux2.1.sel mux2.2.sel mux2.3.sel

# ################
# X [0] Axis
# ################

# axis enable chain
newsig emcmot.00.enable bit
sets emcmot.00.enable FALSE

net emcmot.00.enable <= joint.0.amp-enable-out 
net emcmot.00.enable => hm2_[HOSTMOT2](BOARD).0.xy2mod.00.enable pid.0.enable pid.1.enable


# position command and feedback
net emcmot.00.pos-cmd joint.0.motor-pos-cmd => pid.0.command mux2.0.in1
net fb0 mux2.0.in0 <= hm2_[HOSTMOT2](BOARD).0.xy2mod.00.posx-fb 
# feedback position to motion is forced to be commanded position if theres a packet error
net motor.00.pos-fb <= mux2.0.out joint.0.motor-pos-fb pid.0.feedback
net motor.00.command pid.0.output hm2_[HOSTMOT2](BOARD).0.xy2mod.00.velx-cmd
setp pid.0.error-previous-target true


# timing parameters

setp hm2_[HOSTMOT2](BOARD).0.xy2mod.00.posx-scale  [JOINT_0]SCALE

# set PID loop gains from inifile
setp pid.0.Pgain [JOINT_0]P
setp pid.0.Igain [JOINT_0]I
setp pid.0.Dgain [JOINT_0]D
setp pid.0.bias [JOINT_0]BIAS
setp pid.0.FF0 [JOINT_0]FF0
setp pid.0.FF1 [JOINT_0]FF1
setp pid.0.FF2 [JOINT_0]FF2
setp pid.0.deadband [JOINT_0]DEADBAND
setp pid.0.maxoutput [JOINT_0]MAX_OUTPUT
setp pid.0.maxerror [JOINT_0]MAX_ERROR

# ################
# Y [1] Axis
# ################

# position command and feedback
net emcmot.01.pos-cmd joint.1.motor-pos-cmd => pid.1.command mux2.1.in1
net fb1 mux2.1.in0 <= hm2_[HOSTMOT2](BOARD).0.xy2mod.00.posy-fb 
# feedback position to motion is forced to be commanded position if theres a packet error
net motor.01.pos-fb <= mux2.1.out joint.1.motor-pos-fb pid.1.feedback
net motor.01.command pid.1.output hm2_[HOSTMOT2](BOARD).0.xy2mod.00.vely-cmd
setp pid.1.error-previous-target true

# timing parameters
setp hm2_[HOSTMOT2](BOARD).0.xy2mod.00.posy-scale  [JOINT_1]SCALE

# set PID loop gains from inifile
setp pid.1.Pgain [JOINT_1]P
setp pid.1.Igain [JOINT_1]I
setp pid.1.Dgain [JOINT_1]D
setp pid.1.bias [JOINT_1]BIAS
setp pid.1.FF0 [JOINT_1]FF0
setp pid.1.FF1 [JOINT_1]FF1
setp pid.1.FF2 [JOINT_1]FF2
setp pid.1.deadband [JOINT_1]DEADBAND
setp pid.1.maxoutput [JOINT_1]MAX_OUTPUT
setp pid.1.maxerror [JOINT_1]MAX_ERROR



# ################
# Z [2] Axis -Build Platform
# ################

# axis enable chain
newsig emcmot.02.enable bit
sets emcmot.02.enable FALSE

net emcmot.02.enable <= joint.2.amp-enable-out 
net emcmot.02.enable => hm2_[HOSTMOT2](BOARD).0.stepgen.00.enable pid.2.enable


# position command and feedback
net emcmot.02.pos-cmd joint.2.motor-pos-cmd => pid.2.command mux2.2.in1
#net emcmot.02.vel-cmd joint.2.vel-cmd => pid.2.command-deriv
net fb2 mux2.2.in0 <= hm2_[HOSTMOT2](BOARD).0.stepgen.00.position-fb 
# feedback position to motion is forced to be commanded position if theres a packet error
net motor.02.pos-fb <= mux2.2.out joint.2.motor-pos-fb pid.2.feedback
net motor.02.command pid.2.output hm2_[HOSTMOT2](BOARD).0.stepgen.00.velocity-cmd
setp pid.2.error-previous-target true


# timing parameters
setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.dirsetup        [JOINT_2]DIRSETUP
setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.dirhold         [JOINT_2]DIRHOLD

setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.steplen         [JOINT_2]STEPLEN
setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.stepspace       [JOINT_2]STEPSPACE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.position-scale  [JOINT_2]SCALE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.maxvel          [JOINT_2]STEPGEN_MAX_VEL
setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.maxaccel        [JOINT_2]STEPGEN_MAX_ACC

setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.step_type       0
setp hm2_[HOSTMOT2](BOARD).0.stepgen.00.control-type    1

# set PID loop gains from inifile
setp pid.2.Pgain [JOINT_2]P
setp pid.2.Igain [JOINT_2]I
setp pid.2.Dgain [JOINT_2]D
setp pid.2.bias [JOINT_2]BIAS
setp pid.2.FF0 [JOINT_2]FF0
setp pid.2.FF1 [JOINT_2]FF1
setp pid.2.FF2 [JOINT_2]FF2
setp pid.2.deadband [JOINT_2]DEADBAND
setp pid.2.maxoutput [JOINT_2]MAX_OUTPUT
setp pid.2.maxerror [JOINT_2]MAX_ERROR

# ################
# A [3] Axis - Supply Platform
# ################

# axis enable chain
newsig emcmot.03.enable bit
sets emcmot.03.enable FALSE

net emcmot.03.enable <= joint.3.amp-enable-out 
net emcmot.03.enable => hm2_[HOSTMOT2](BOARD).0.stepgen.01.enable pid.3.enable


# position command and feedback
net emcmot.03.pos-cmd joint.3.motor-pos-cmd => pid.3.command mux2.3.in1
#net emcmot.03.vel-cmd joint.3.vel-cmd => pid.3.command-deriv
net fb3 mux2.3.in0 <= hm2_[HOSTMOT2](BOARD).0.stepgen.01.position-fb 
# feedback position to motion is forced to be commanded position if theres a packet error
net motor.03.pos-fb <= mux2.3.out joint.3.motor-pos-fb pid.3.feedback
net motor.03.command pid.3.output hm2_[HOSTMOT2](BOARD).0.stepgen.01.velocity-cmd
setp pid.3.error-previous-target true


# timing parameters
setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.dirsetup        [JOINT_3]DIRSETUP
setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.dirhold         [JOINT_3]DIRHOLD

setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.steplen         [JOINT_3]STEPLEN
setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.stepspace       [JOINT_3]STEPSPACE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.position-scale  [JOINT_3]SCALE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.maxvel          [JOINT_3]STEPGEN_MAX_VEL
setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.maxaccel        [JOINT_3]STEPGEN_MAX_ACC

setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.step_type       0
setp hm2_[HOSTMOT2](BOARD).0.stepgen.01.control-type    1

# set PID loop gains from inifile
setp pid.3.Pgain [JOINT_3]P
setp pid.3.Igain [JOINT_3]I
setp pid.3.Dgain [JOINT_3]D
setp pid.3.bias [JOINT_3]BIAS
setp pid.3.FF0 [JOINT_3]FF0
setp pid.3.FF1 [JOINT_3]FF1
setp pid.3.FF2 [JOINT_3]FF2
setp pid.3.deadband [JOINT_3]DEADBAND
setp pid.3.maxoutput [JOINT_3]MAX_OUTPUT
setp pid.3.maxerror [JOINT_3]MAX_ERROR

# ################
# B [4] Axis - Roller
# ################

# axis enable chain
newsig emcmot.04.enable bit
sets emcmot.04.enable FALSE

net emcmot.04.enable <= joint.4.amp-enable-out 
net emcmot.04.enable => hm2_[HOSTMOT2](BOARD).0.stepgen.02.enable pid.4.enable


# position command and feedback
net emcmot.04.pos-cmd joint.4.motor-pos-cmd => pid.4.command mux2.4.in1
#net emcmot.04.vel-cmd joint.4.vel-cmd => pid.4.command-deriv
net fb4 mux2.4.in0 <= hm2_[HOSTMOT2](BOARD).0.stepgen.02.position-fb 
# feedback position to motion is forced to be commanded position if theres a packet error
net motor.04.pos-fb <= mux2.4.out joint.4.motor-pos-fb pid.4.feedback
net motor.04.command pid.4.output hm2_[HOSTMOT2](BOARD).0.stepgen.02.velocity-cmd
setp pid.4.error-previous-target true


# timing parameters
setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.dirsetup        [JOINT_4]DIRSETUP
setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.dirhold         [JOINT_4]DIRHOLD

setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.steplen         [JOINT_4]STEPLEN
setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.stepspace       [JOINT_4]STEPSPACE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.position-scale  [JOINT_4]SCALE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.maxvel          [JOINT_4]STEPGEN_MAX_VEL
setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.maxaccel        [JOINT_4]STEPGEN_MAX_ACC

setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.step_type       0
setp hm2_[HOSTMOT2](BOARD).0.stepgen.02.control-type    1

# set PID loop gains from inifile
setp pid.4.Pgain [JOINT_4]P
setp pid.4.Igain [JOINT_4]I
setp pid.4.Dgain [JOINT_4]D
setp pid.4.bias [JOINT_4]BIAS
setp pid.4.FF0 [JOINT_4]FF0
setp pid.4.FF1 [JOINT_4]FF1
setp pid.4.FF2 [JOINT_4]FF2
setp pid.4.deadband [JOINT_4]DEADBAND
setp pid.4.maxoutput [JOINT_4]MAX_OUTPUT
setp pid.4.maxerror [JOINT_4]MAX_ERROR

# ################
# C [5] Axis - Scraper
# ################

# axis enable chain
newsig emcmot.05.enable bit
sets emcmot.05.enable FALSE

net emcmot.05.enable <= joint.5.amp-enable-out 
net emcmot.05.enable => hm2_[HOSTMOT2](BOARD).0.stepgen.03.enable pid.5.enable


# position command and feedback
net emcmot.05.pos-cmd joint.5.motor-pos-cmd => pid.5.command mux2.5.in1
#net emcmot.05.vel-cmd joint.5.vel-cmd => pid.5.command-deriv
net fb5 mux2.5.in0 <= hm2_[HOSTMOT2](BOARD).0.stepgen.03.position-fb 
# feedback position to motion is forced to be commanded position if theres a packet error
net motor.05.pos-fb <= mux2.5.out joint.5.motor-pos-fb pid.5.feedback
net motor.05.command pid.5.output hm2_[HOSTMOT2](BOARD).0.stepgen.03.velocity-cmd
setp pid.5.error-previous-target true


# timing parameters
setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.dirsetup        [JOINT_5]DIRSETUP
setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.dirhold         [JOINT_5]DIRHOLD

setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.steplen         [JOINT_5]STEPLEN
setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.stepspace       [JOINT_5]STEPSPACE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.position-scale  [JOINT_5]SCALE

setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.maxvel          [JOINT_5]STEPGEN_MAX_VEL
setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.maxaccel        [JOINT_5]STEPGEN_MAX_ACC

setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.step_type       0
setp hm2_[HOSTMOT2](BOARD).0.stepgen.03.control-type    1

# set PID loop gains from inifile
setp pid.5.Pgain [JOINT_5]P
setp pid.5.Igain [JOINT_5]I
setp pid.5.Dgain [JOINT_5]D
setp pid.5.bias [JOINT_5]BIAS
setp pid.5.FF0 [JOINT_5]FF0
setp pid.5.FF1 [JOINT_5]FF1
setp pid.5.FF2 [JOINT_5]FF2
setp pid.5.deadband [JOINT_5]DEADBAND
setp pid.5.maxoutput [JOINT_5]MAX_OUTPUT
setp pid.5.maxerror [JOINT_5]MAX_ERROR

# #############
# Laser controls
# #############

# set soft limits on frequency
setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.maxvel 600000
setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.maxaccel 0

# Set stepgen to quadrature (ie. A AB B 0)
setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.step_type 2

# set the spacing/timing small so as not to interfere when frequency gets large
setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.stepspace 10
setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.steplen 10


# set the scale.  should be 1:1 in quadrature mode 
setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.position-scale 1

# set the control type to velocity.  this should allow it to keep going

setp hm2_[HOSTMOT2](BOARD).0.stepgen.04.control-type 1

# ### signals to wire everything up

# turn on PRR when machine is enabled
net PRR_on motion.motion-enabled
net PRR_on hm2_[HOSTMOT2](BOARD).0.stepgen.04.enable

net PRR_freq hm2_[HOSTMOT2](BOARD).0.stepgen.04.velocity-cmd
# set an initial value.  to be adjusted by M102
sets PRR_freq 200000

# Set up one shot to latch power
setp oneshot.0.width .00000001
setp hm2_[HOSTMOT2](BOARD).0.gpio.048.is_output TRUE

# one shot sends signal to GPIO pin
net power_latch oneshot.0.out
net power_latch hm2_7i96.0.gpio.048.out

# set up signal to drive oneshot

net latch_trig oneshot.0.in

# setup spindle 0 as main power spindle
# ##################################

# Read laser fault codes
setp hm2_[HOSTMOT2](BOARD).0.gpio.010.is_output False
setp hm2_[HOSTMOT2](BOARD).0.gpio.009.is_output False

# connect AP laser pins

setp hm2_[HOSTMOT2](BOARD).0.gpio.049.is_output True
net Main_laser_on spindle.0.on
net Main_laser_on hm2_[HOSTMOT2](BOARD).0.gpio.049.out


# Emergency Stop safety feature
# Estop pin needs to be high for normal operation.  7i96 IO pins initalize to HIGH. During an error all pins go high and the laser turns on  
# To stop this, SSR0+ will be connected to 5V, SSR0- connect to laser Estop pin.  Thereby, the pin will be forced high as long as the board is connected

net emcmot.00.enable hm2_7i96.0.ssr.00.out-00


# MO needs to be high before laser emits.  basically laser power turned on.  If joints are not on, no reason to be powered
setp hm2_[HOSTMOT2](BOARD).0.gpio.039.is_output True

# logic to make sure red laser is off
net emcmot.00.enable and2.0.in0
net mo_in_1 and2.0.in1
sets mo_in_1 True
net mo_out and2.0.out hm2_7i96.0.ssr.00.out-01



# setup GPIO as red laser dot
# ##############################
# red laser will be called via M103 instead of spindle
# Must be turned off with M104 to return to normal

setp hm2_[HOSTMOT2](BOARD).0.gpio.050.is_output TRUE
net red_laser_on hm2_[HOSTMOT2](BOARD).0.gpio.050.out




setp pid.6.Pgain [SPINDLE_9]P
setp pid.6.Igain [SPINDLE_9]I
setp pid.6.Dgain [SPINDLE_9]D
setp pid.6.bias [SPINDLE_9]BIAS
setp pid.6.FF0 [SPINDLE_9]FF0
setp pid.6.FF1 [SPINDLE_9]FF1
setp pid.6.FF2 [SPINDLE_9]FF2
setp pid.6.deadband [SPINDLE_9]DEADBAND
setp pid.6.maxoutput [SPINDLE_9]MAX_OUTPUT
setp pid.6.maxerror [SPINDLE_9]MAX_ERROR

#setp hm2_[HOSTMOT2](BOARD).0.7i76.0.0.spinout-scalemax [SPINDLE_9]SCALE
#setp hm2_[HOSTMOT2](BOARD).0.7i76.0.0.spinout-minlim [SPINDLE_9]MINLIM
#setp hm2_[HOSTMOT2](BOARD).0.7i76.0.0.spinout-maxlim [SPINDLE_9]MAXLIM

net spindle-index-enable <=> hm2_[HOSTMOT2](BOARD).0.encoder.00.index-enable <=> spindle.0.index-enable
# ##################################################
# Standard I/O Block - EStop, Etc
# ##################################################

# create a signal for the estop loopback
net estop-loop iocontrol.0.user-enable-out => iocontrol.0.emc-enable-in

# create signals for tool loading loopback
net tool-prep-loop iocontrol.0.tool-prepare => iocontrol.0.tool-prepared
net tool-change-loop iocontrol.0.tool-change => iocontrol.0.tool-changed

# ##################################################
# 8 bit power signal to laser
# ##################################################

# set up pins for 8 bit logic
# pin 040 is bit 0, pin 047 is bit 7(128)

setp hm2_[HOSTMOT2](BOARD).0.gpio.040.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.041.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.042.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.043.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.044.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.045.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.046.is_output TRUE
setp hm2_[HOSTMOT2](BOARD).0.gpio.047.is_output TRUE

Please Log in or Create an account to join the conversation.

More
05 May 2021 21:24 #208026 by PCW
You would definitely want to remove or comment out this line:

setp hm2_[HOSTMOT2](BOARD).0.xy2mod.write-timer-number 1

and then set the FF2 values to say 0.00025 (this can be tuned with halscope)

You also might want to widen the ferror limits until everything is tuned
(say min_ferror = 0.01 and ferror =0.10)

Please Log in or Create an account to join the conversation.

More
05 May 2021 21:32 #208027 by Limedodge
OK, progress!

commented out
#setp hm2_[HOSTMOT2](BOARD).0.xy2mod.write-timer-number 1
P=2000
FF2=.00025

I can get max velocity up to 13117mm/min before it hits a following error

The galvo can mechanically/physically go faster (max rate is ~7000mm/sec), not sure whats going to be the limit of the controller?

I'll switch out the Ferror and see what it does. Will this affect the precision? Will physical errors of 0.1mm be the consequence?

Please Log in or Create an account to join the conversation.

More
05 May 2021 21:53 - 05 May 2021 21:53 #208029 by PCW
You should be able to halscope the ferror (say at .02 mm/division)
and see more clearly what is going on. The ferror limits do not
affect precision, they just determine when a following error fault is tripped.

Also note that the following error is just an apparent following error
and can be affected by residual DPLL position sample time jitter
and how well the scaling is setup to use the full 16 bit galvanometer
range.
Last edit: 05 May 2021 21:53 by PCW.

Please Log in or Create an account to join the conversation.

More
05 May 2021 22:25 #208033 by Limedodge
Here's a scope view with the gain turned up on the ferror. Value of jump on right side (at error termination) is 9.499999

P=2000
FF2 =.00025

Attachments:

Please Log in or Create an account to join the conversation.

More
05 May 2021 22:46 #208034 by PCW
OK that's a following error at 0 or near velocity
Is that an error in the command or feedback?

Have you possibly run into the galvanometer limits?
that is, are the posx or posy overrange bits set?

Please Log in or Create an account to join the conversation.

More
05 May 2021 23:09 #208037 by Limedodge
How do I tell whether the error is from command or feedback?

I don't have the galvometer connected right now. Those charts are dry running on the bench. I really don't think it hit the limits but I'll double check on the overrun bits

That said, the galvo's total scan footprint is 150mm x 150mm. I've been running a test Gcode with a 20mm square spiral. Crazy enough, a scale of .01 is almost perfect. I etched lines and measured with a caliper and they were only off by hundredths of a mm.

side note, once I get it up and running I'll need to calibrate a compensation file as the galvo is inherently angular being converted to linear. There will be a function of Cosine error, as you get further from center. Haven't gotten that far yet. That might even explain the slight error I measured

Please Log in or Create an account to join the conversation.

More
05 May 2021 23:17 #208038 by PCW
The overrange bits are set when you exceed the galvanometers range
(that is outside the 16 bit or 18 bit range) if the scale is .01,
the range would be +-100

Please Log in or Create an account to join the conversation.

Moderators: PCWjmelson
Time to create page: 1.430 seconds
Powered by Kunena Forum