Skip to content

Instantly share code, notes, and snippets.

@jepler
Created January 8, 2023 14:30
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save jepler/86390ab9be17babf0349a1a8c5198e2e to your computer and use it in GitHub Desktop.
Save jepler/86390ab9be17babf0349a1a8c5198e2e to your computer and use it in GitHub Desktop.
This file has been truncated, but you can view the full file.
diff --git a/configs/sim/axis/canterp.ini b/configs/sim/axis/canterp.ini
index 76f1194110..e5161d6740 100644
--- a/configs/sim/axis/canterp.ini
+++ b/configs/sim/axis/canterp.ini
@@ -5,7 +5,7 @@ VERSION = 1.1
[TASK]
TASK = milltask
CYCLE_TIME = 0.001
-INTERPRETER = libcanterp.so
+INTERPRETER = canterp.so
[DISPLAY]
OPEN_FILE = ./canterp_example.can
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/README b/configs/sim/axis/vismach/5axis/table-dual-rotary/README
new file mode 100644
index 0000000000..0a9f1130e4
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/README
@@ -0,0 +1,42 @@
+Switchable Table Dual Rotary (tdr) Sim config
+
+xyzab-tdr (switchable kinematics)
+
+
+Demonstrations:
+
+For a demonstration of XYZAB_TCP kinematics the user can run the preloaded demo gcode with the default offsets.
+
+In the right hand panel of the axis gui sliders are provided to
+
+- change the geometrical (x,z)-offsets as measured from the rotation-point of the A/B rotary-assembly to the
+ face center of the rotary A table. The offsets are visibly adjusted in the vismach simulation and represented by a red indicator
+ for the x-offset and a blue indicator for the z-offset.
+
+- see the effects of misconfiguring the (x,y,z)-rot-point values used in the kinematics. These values represent the
+ physical position of the rotary-assembly in the machine as measured from the machine home position to the rotation-point
+ of the assembly. The rotation-point is identical to the intersection of the two rotational axes A and B when the (x,z)-offsets
+ are zero. When (x,z)-offsets are applied the rotation-point stays on the rotational B axis. The 'rot-point' as set by
+ these values as well as the true rotation-point of the rotary-assembly are indicated in the vismach simulation by a yellow cross
+ and a red sphere respectively.
+
+NOTE:
+For proper tool-path preview RELOAD THE CGODE after startup and after changing offset values.
+
+
+
+***********************************************
+Note: IMPORTANT ini file requirements:
+
+[HAL]
+HALCMD = net :kinstype-select <= motion.analog-out-0N => motion.switchkins-type
+
+[RS274NGC]
+SUBROUTINE_PATH = ./remap_subs
+ REMAP = M428 modalgroup=10 ngc=428remap
+ REMAP = M429 modalgroup=10 ngc=429remap
+
+[HALUI]
+MDI_COMMAND = M429
+MDI_COMMAND = M428
+***********************************************
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/demos/xyzab-tdr-demo.ngc b/configs/sim/axis/vismach/5axis/table-dual-rotary/demos/xyzab-tdr-demo.ngc
new file mode 100644
index 0000000000..76b2f4c6d9
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/demos/xyzab-tdr-demo.ngc
@@ -0,0 +1,49 @@
+; -- RELOAD GCODE FOR PROPER TOOL-PATH PREVIEW --
+g21 g90 g49 g54
+; switch to identity mode
+m429
+; clear g54
+g10 l2 p0 x0 y0 z0 a0 b0
+; go to machine origin
+g53 g0 x0 y0 z0 a0 b0
+; set g54 for face center of rotary
+g10 l20 p0 x-[#<_hal[xyzab_tdr_kins.x-rot-point]>+#<_hal[xyzab_tdr_kins.x-offset]>] y-#<_hal[xyzab_tdr_kins.x-rot-point]> z-[#<_hal[xyzab_tdr_kins.z-rot-point]>+#<_hal[xyzab_tdr_kins.z-offset]>] a0 b0
+; load a tool
+M61 Q2 G43 H2
+; switch to tcp mode
+m428
+g0 b30
+; go to face center of rotary a
+g0 x0 y0 z0
+; show basic tcp functionality
+g0 x30 a180
+g0 x0 a0
+g0 b100
+g0 y-50
+g0 a90
+g0 b120
+g0 y0
+g0 a0 b30
+g0 x1
+; start with square
+f1000
+g0 y-30 z-30
+g1 z30
+g1 a45
+g1 y30
+g1 a90 b45
+g1 z-30
+g1 a180 b100
+g1 y30
+g1 a90 b120
+g1 y-30
+g1 a0 b30
+g0 x5
+g1 y-30 z-30 a90
+g1 z30 a45 b60
+g1 y30 a90 b90
+g1 z-30 a135 b120
+g1 y-30 a0 b30
+; go to machine origin
+g53 g0 x0 y0 z0 a0 b0
+m2
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/remap_subs/428remap.ngc b/configs/sim/axis/vismach/5axis/table-dual-rotary/remap_subs/428remap.ngc
new file mode 100644
index 0000000000..46e2d01ba5
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/remap_subs/428remap.ngc
@@ -0,0 +1,24 @@
+;M428 by remap: kinstype==1 (xyzac,xyzbc) (note: sparm=identityfirst)
+o<428remap>sub
+ #<kinstype> = 1 ; xyzac,xyzbc
+ #<SWITCHKINS_PIN> = 3 ; set N as required: motion.analog-out-0N
+
+o1 if [exists [#<_hal[motion.switchkins-type]>]]
+o1 else
+ (debug,M428:Missing [RS274NGC]HAL_PIN_VARS=1)
+ (debug,STOP)
+ M2
+o1 endif
+
+ M68 E#<SWITCHKINS_PIN> Q#<kinstype> ; set kinstype value
+ M66 E0 L0 ; force synch
+
+o2 if [[#<_task> EQ 1] AND [#<_hal[motion.switchkins-type]> NE #<kinstype>]]
+ (debug,M428: Wrong motion.switchkins-type)
+ (debug,or missing hal net to analog-out-0x)
+ (debug,STOP)
+ M2
+o2 else
+o2 endif
+
+o<428remap>endsub
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/remap_subs/429remap.ngc b/configs/sim/axis/vismach/5axis/table-dual-rotary/remap_subs/429remap.ngc
new file mode 100644
index 0000000000..3fa610c8ee
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/remap_subs/429remap.ngc
@@ -0,0 +1,24 @@
+;M429 by remap: kinstype==0 Identity kinematics
+o<429remap>sub
+ #<kinstype> = 0
+ #<SWITCHKINS_PIN> = 3 ; set N as required: motion.analog-out-0N
+
+o1 if [exists [#<_hal[motion.switchkins-type]>]]
+o1 else
+ (debug,M429:Missing [RS274NGC]HAL_PIN_VARS=1)
+ (debug,STOP)
+ M2
+o1 endif
+
+ M68 E#<SWITCHKINS_PIN> Q#<kinstype> ; set kinstype value
+ M66 E0 L0 ; force synch
+
+o2 if [[#<_task> EQ 1] AND [#<_hal[motion.switchkins-type]> NE #<kinstype>]]
+ (debug,M429:Wrong motion.switchkins-type)
+ (debug,or missing hal net to analog-out-0x)
+ (debug,STOP)
+ M2
+o2 else
+o2 endif
+
+o<429remap>endsub
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr-postgui.hal b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr-postgui.hal
new file mode 100644
index 0000000000..ac96e95a8d
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr-postgui.hal
@@ -0,0 +1,23 @@
+# switchkins pyvcp connections for:
+# xyzab-tdr-kins.ini
+
+net :kinstype.is-0 <= kinstype.is-0 => pyvcp.multilabel.0.legend0
+net :kinstype.is-1 <= kinstype.is-1 => pyvcp.multilabel.0.legend1
+
+net :vismach-clear <= pyvcp.vismach-clear => vismach.plotclear
+
+net :type0-button <= pyvcp.type0-button => halui.mdi-command-00
+net :type1-button <= pyvcp.type1-button => halui.mdi-command-01
+
+net :axis-x => pyvcp.joint0
+net :axis-y => pyvcp.joint1
+net :axis-z => pyvcp.joint2
+net :rotary-a => pyvcp.joint3
+net :rotary-b => pyvcp.joint4
+
+net :x-offset => pyvcp.x-offset-f
+net :z-offset => pyvcp.z-offset-f
+net :x-rot-point => pyvcp.x-rot-point-f
+net :y-rot-point => pyvcp.y-rot-point-f
+net :z-rot-point => pyvcp.z-rot-point-f
+
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.ini b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.ini
new file mode 100644
index 0000000000..f882535976
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.ini
@@ -0,0 +1,185 @@
+[EMC]
+VERSION = 1.1
+MACHINE = sim-xyzab-tdr-kins (switchkins)
+
+[DISPLAY]
+ GEOMETRY = XYZA-B
+ OPEN_FILE = ./demos/xyzab-tdr-demo.ngc
+ PYVCP = ./xyzab-tdr.xml
+ DISPLAY = axis
+MAX_ANGULAR_VELOCITY = 360
+ MAX_LINEAR_VELOCITY = 1000
+ POSITION_OFFSET = RELATIVE
+ POSITION_FEEDBACK = ACTUAL
+ MAX_FEED_OVERRIDE = 2
+ PROGRAM_PREFIX = ../../nc_files
+ INTRO_GRAPHIC = emc2.gif
+ INTRO_TIME = 1
+ TOOL_EDITOR = tooledit z diam
+
+[RS274NGC]
+SUBROUTINE_PATH = ./remap_subs
+ REMAP = M428 modalgroup=10 ngc=428remap
+ REMAP = M429 modalgroup=10 ngc=429remap
+ PARAMETER_FILE = xyzab-tdr.var
+
+[KINS]
+#NOTE:
+# switchkins-type == 0 is identity kins
+# switchkins-type == 1 is xyzab-tdr-kins
+
+KINEMATICS = xyzab_tdr_kins
+ JOINTS = 5
+
+[HAL]
+ HALUI = halui
+ HALFILE = LIB:basic_sim.tcl
+POSTGUI_HALFILE = xyzab-tdr-postgui.hal
+
+# net for control of motion.switchkins-type
+HALCMD = net :kinstype-select <= motion.analog-out-03 => motion.switchkins-type
+
+# Values '(x,z)-offsets' for geometric offset of the rotary-assembly and the
+# values '(x,y,z)-rot-point' that describe the position of the
+# rotation-point of the rotary-assembly can be changed using the sliders
+# in the axis-gui.
+# Default values (initval) and ranges (min,max) are set
+# in the corresponding 'scale' sections in the file 'xyzab-tdr.xml'
+
+# vismach xyzab-tdr-gui items
+HALCMD = loadusr -W xyzab-tdr-gui
+HALCMD = net :axis-x joint.0.pos-fb xyzab-tdr-gui.axis-x
+HALCMD = net :axis-y joint.1.pos-fb xyzab-tdr-gui.axis-y
+HALCMD = net :axis-z joint.2.pos-fb xyzab-tdr-gui.axis-z
+HALCMD = net :rotary-a joint.3.pos-fb xyzab-tdr-gui.rotary-a
+HALCMD = net :rotary-b joint.4.pos-fb xyzab-tdr-gui.rotary-b
+HALCMD = net :tool-offset motion.tooloffset.z xyzab-tdr-gui.tool_length
+HALCMD = net :tool-diam halui.tool.diameter xyzab-tdr-gui.tool_diameter
+HALCMD = net :x-offset xyzab-tdr-gui.x_offset
+HALCMD = net :z-offset xyzab-tdr-gui.z_offset
+HALCMD = net :x-rot-point xyzab-tdr-gui.x-rot-point
+HALCMD = net :y-rot-point xyzab-tdr-gui.y-rot-point
+HALCMD = net :z-rot-point xyzab-tdr-gui.z-rot-point
+
+# xyzab_tdr_kins items
+HALCMD = net :tool-offset xyzab_tdr_kins.tool-offset-z
+HALCMD = net :x-offset xyzab_tdr_kins.x-offset
+HALCMD = net :z-offset xyzab_tdr_kins.z-offset
+HALCMD = net :x-rot-point xyzab_tdr_kins.x-rot-point
+HALCMD = net :y-rot-point xyzab_tdr_kins.y-rot-point
+HALCMD = net :z-rot-point xyzab_tdr_kins.z-rot-point
+
+# This is only used to preset the vismach model to the default values as set
+# in the xml scale widgets
+# These will be overwritten by the values in the xml
+HALCMD = sets :x-offset -20
+HALCMD = sets :z-offset -10
+
+[HALUI]
+# M429:identity kins (motion.switchkins-type==0 startupDEFAULT)
+# M428:xyzab-tdr kins (motion.switchkins-type==1)
+MDI_COMMAND = M429
+MDI_COMMAND = M428
+
+[TRAJ]
+ COORDINATES = XYZAB
+ LINEAR_UNITS = mm
+ ANGULAR_UNITS = deg
+ DEFAULT_LINEAR_VELOCITY = 20
+ MAX_LINEAR_VELOCITY = 35
+ MAX_LINEAR_ACCELERATION = 400
+DEFAULT_LINEAR_ACCELERATION = 300
+
+[EMCMOT]
+ EMCMOT = motmod
+SERVO_PERIOD = 1000000
+COMM_TIMEOUT = 1
+
+[TASK]
+ TASK = milltask
+CYCLE_TIME = 0.010
+
+[EMCIO]
+ EMCIO = io
+CYCLE_TIME = 0.100
+TOOL_TABLE = xyzab-tdr.tbl
+
+[AXIS_X]
+ MIN_LIMIT = -200
+ MAX_LIMIT = 200
+ MAX_VELOCITY = 20
+MAX_ACCELERATION = 300
+
+[AXIS_Y]
+ MIN_LIMIT = -200
+ MAX_LIMIT = 200
+ MAX_VELOCITY = 20
+MAX_ACCELERATION = 300
+
+[AXIS_Z]
+ MIN_LIMIT = -300
+ MAX_LIMIT = 300
+ MAX_VELOCITY = 20
+MAX_ACCELERATION = 300
+
+[AXIS_A]
+ MIN_LIMIT = -3600
+ MAX_LIMIT = 3600
+ MAX_VELOCITY = 30
+MAX_ACCELERATION = 300
+
+[AXIS_B]
+ MIN_LIMIT = -180
+ MAX_LIMIT = 180
+ MAX_VELOCITY = 30
+MAX_ACCELERATION = 300
+
+[JOINT_0]
+ TYPE = LINEAR
+ HOME = 0
+ MAX_VELOCITY = 20
+ MAX_ACCELERATION = 300
+ MIN_LIMIT = -200
+ MAX_LIMIT = 200
+ HOME_SEARCH_VEL = 0
+ HOME_SEQUENCE = 0
+
+[JOINT_1]
+ TYPE = LINEAR
+ HOME = 0
+ MAX_VELOCITY = 20
+ MAX_ACCELERATION = 300
+ MIN_LIMIT = -200
+ MAX_LIMIT = 200
+ HOME_SEARCH_VEL = 0
+ HOME_SEQUENCE = 0
+
+[JOINT_2]
+ TYPE = LINEAR
+ HOME = 0
+ MAX_VELOCITY = 20
+ MAX_ACCELERATION = 300
+ MIN_LIMIT = -300
+ MAX_LIMIT = 300
+ HOME_SEARCH_VEL = 0
+ HOME_SEQUENCE = 0
+
+[JOINT_3]
+ TYPE = ANGULAR
+ HOME = 0
+ MAX_VELOCITY = 30
+MAX_ACCELERATION = 300
+ MIN_LIMIT = -3600
+ MAX_LIMIT = 3600
+ HOME_SEARCH_VEL = 0
+ HOME_SEQUENCE = 0
+
+[JOINT_4]
+ TYPE = ANGULAR
+ HOME = 0
+ MAX_VELOCITY = 30
+MAX_ACCELERATION = 300
+ MIN_LIMIT = -180
+ MAX_LIMIT = 180
+ HOME_SEARCH_VEL = 0
+ HOME_SEQUENCE = 0
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.tbl b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.tbl
new file mode 100644
index 0000000000..3ed6a2152c
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.tbl
@@ -0,0 +1,4 @@
+T1 P1 D1
+T2 P2 Z30 D3
+T3 P3 Z40 D4
+T4 P4 Z50 D5
diff --git a/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.xml b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.xml
new file mode 100644
index 0000000000..9998d501bd
--- /dev/null
+++ b/configs/sim/axis/vismach/5axis/table-dual-rotary/xyzab-tdr.xml
@@ -0,0 +1,325 @@
+<?xml version='1.0' encoding='UTF-8'?>
+<pyvcp>
+
+ <vbox>
+ <relief>"ridge"</relief>
+ <bd>5</bd>
+ <multilabel>
+ <legends>["0:IDENTITY", "1: XYZAB ", "2: USERK "]</legends>
+ <font>("Helvetica",16)</font>
+ <bg>"black"</bg>
+ <fg>"yellow"</fg>
+ </multilabel>
+ <button>
+ <halpin>"type0-button"</halpin>
+ <text>"IDENTITY"</text>
+ <bd>3</bd>
+ </button>
+ <button>
+ <halpin>"type1-button"</halpin>
+ <text>"TCP:XYZAB"</text>
+ <bd>3</bd>
+ </button>
+ </vbox>
+
+<!-- create a space to the next element -->
+ <vbox>
+ <hbox>
+ <label>
+ <text>" "</text>
+ <font>("Helvetica",4)</font>
+ </label>
+ </hbox>
+ </vbox>
+
+ <vbox>
+ <labelframe text="Joint position">
+ <font>("Helvetica",14)</font>
+ <hbox>
+ <vbox>
+ <hbox>
+ <label>
+ <text>"0: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <number>
+ <halpin>"joint0"</halpin>
+ <font>("Helvetica",10)</font>
+ <format>"4.4f"</format>
+ </number>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"1: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <number>
+ <halpin>"joint1"</halpin>
+ <font>("Helvetica",10)</font>
+ <format>"4.4f"</format>
+ </number>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"2: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <number>
+ <halpin>"joint2"</halpin>
+ <font>("Helvetica",10)</font>
+ <format>"4.4f"</format>
+ </number>
+ </hbox>
+ </vbox>
+ <vbox>
+ <label>
+ <text>" "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ </vbox>
+ <vbox>
+ <hbox>
+ <label>
+ <text>"3: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <number>
+ <halpin>"joint3"</halpin>
+ <font>("Helvetica",10)</font>
+ <format>"4.4f"</format>
+ </number>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"4: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <number>
+ <halpin>"joint4"</halpin>
+ <font>("Helvetica",10)</font>
+ <format>"4.4f"</format>
+ </number>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"5: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <number>
+ <halpin>"joint5"</halpin>
+ <font>("Helvetica",10)</font>
+ <format>"4.4f"</format>
+ </number>
+ </hbox>
+ </vbox>
+ </hbox>
+ </labelframe>
+ </vbox>
+<!-- create a space to the next element -->
+ <vbox>
+ <hbox>
+ <label>
+ <text>" "</text>
+ <font>("Helvetica",4)</font>
+ </label>
+ </hbox>
+ </vbox>
+
+ <vbox>
+ <relief>"ridge"</relief>
+ <bd>5</bd>
+ <button>
+ <halpin>"vismach-clear"</halpin>
+ <text>"vismach-clear"</text>
+ <bd>3</bd>
+ </button>
+ </vbox>
+<!-- create a space to the next element -->
+ <vbox>
+ <hbox>
+ <label>
+ <text>" "</text>
+ <font>("Helvetica",4)</font>
+ </label>
+ </hbox>
+ </vbox>
+
+ <vbox>
+ <labelframe text="Rotary Assembly Offset">
+ <font>("Helvetica",14)</font>
+ <hbox>
+ <label>
+ <text>"x-offset: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <scale>
+ <font>("Helvetica",10)</font>
+ <width>"15"</width>
+ <halpin>"x-offset"</halpin>
+ <resolution>1</resolution>
+ <orient>HORIZONTAL</orient>
+ <initval>-20</initval>
+ <min_>-50</min_>
+ <max_>50</max_>
+ </scale>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"z-offset: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <scale>
+ <font>("Helvetica",10)</font>
+ <width>"15"</width>
+ <halpin>"z-offset"</halpin>
+ <resolution>1</resolution>
+ <orient>HORIZONTAL</orient>
+ <initval>-10</initval>
+ <min_>-50</min_>
+ <max_>50</max_>
+ </scale>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>" "</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"Use hover + mouse wheel to change values"</text>
+ <font>("Helvetica",6)</font>
+ </label>
+ </hbox>
+ </labelframe>
+ </vbox>
+<!-- create a space to the next element -->
+ <vbox>
+ <hbox>
+ <label>
+ <text>" "</text>
+ <font>("Helvetica",4)</font>
+ </label>
+ </hbox>
+ </vbox>
+
+ <vbox>
+ <labelframe text="Rotation Point Offset">
+ <font>("Helvetica",14)</font>
+ <hbox>
+ <label>
+ <text>" This should demonstrate that TCP kinematics\n require the 'rot-point' settings (yellow)\n to match the physical location\n of the rotation-point (red)."</text>
+ <font>("Helvetica",8)</font>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>" "</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>"Physical location of rotation-point in the model\n in absolute machine coordinates:"</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>" x: -50\n y: -50\n z: -100"</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>" "</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>"these are also the correct 'rot-point' settings\n for this model"</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"x-rot-point: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <scale>
+ <font>("Helvetica",10)</font>
+ <width>"15"</width>
+ <halpin>"x-rot-point"</halpin>
+ <resolution>1</resolution>
+ <orient>HORIZONTAL</orient>
+ <initval>-50</initval>
+ <min_>-55</min_>
+ <max_>-45</max_>
+ </scale>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"y-rot-point: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <scale>
+ <font>("Helvetica",10)</font>
+ <width>"15"</width>
+ <halpin>"y-rot-point"</halpin>
+ <resolution>1</resolution>
+ <orient>HORIZONTAL</orient>
+ <initval>-50</initval>
+ <min_>-55</min_>
+ <max_>-45</max_>
+ </scale>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"z-rot-point: "</text>
+ <font>("Helvetica",10)</font>
+ </label>
+ <scale>
+ <font>("Helvetica",10)</font>
+ <width>"15"</width>
+ <halpin>"z-rot-point"</halpin>
+ <resolution>1</resolution>
+ <orient>HORIZONTAL</orient>
+ <initval>-100</initval>
+ <min_>-105</min_>
+ <max_>-95</max_>
+ </scale>
+ </hbox>
+ <hbox>
+ <label>
+ <font>("Helvetica",8)</font>
+ <text>" "</text>
+ </label>
+ </hbox>
+ <hbox>
+ <label>
+ <text>"Use hover + mouse wheel to change values"</text>
+ <font>("Helvetica",6)</font>
+ </label>
+ </hbox>
+ </labelframe>
+ </vbox>
+<!-- create a space to the next element -->
+ <vbox>
+ <hbox>
+ <label>
+ <text>" "</text>
+ <font>("Helvetica",4)</font>
+ </label>
+ </hbox>
+ </vbox>
+ <vbox>
+ <hbox>
+ <label>
+ <text>" FOR PROPER TOOL-PATH PREVIEW \n RELOAD AND RESTART THE\n GCODE AFTER STARTUP AND\n AFTER CHANGING OFFSETS!"</text>
+ <font>("Helvetica",9)</font>
+ </label>
+ </hbox>
+ </vbox>
+
+</pyvcp>
diff --git a/debian/changelog b/debian/changelog
index fc1d964cee..8765a60980 100644
--- a/debian/changelog
+++ b/debian/changelog
@@ -14,7 +14,7 @@ linuxcnc (1:2.9.0~pre1) UNRELEASED; urgency=medium
* qtvcp -versaprobe: improve help dialog layout/use
* qtvcp -panels: fix details of cam_align controls
* qtvcp -docs: cam_align controls, loading options
- * qtvcp -axis embeded cam_align: add size and rotation increment
+ * qtvcp -axis embedded cam_align: add size and rotation increment
* qtvcp -cam_align panel: add ability to set rotation increment
* qtvcp -camview_widget: add the rotation increment display
* qtvcp -cam_align panel: add window size setting option
diff --git a/debian/linuxcnc.lintian-overrides.in b/debian/linuxcnc.lintian-overrides.in
index 860dad61eb..0e7862bfe5 100644
--- a/debian/linuxcnc.lintian-overrides.in
+++ b/debian/linuxcnc.lintian-overrides.in
@@ -9,7 +9,7 @@ linuxcnc-uspace: elevated-privileges 4755 root/root [usr/bin/linuxcnc_module_hel
linuxcnc-uspace: elevated-privileges 4755 root/root [usr/bin/rtapi_app]
# that is intentional - for now
-linuxcnc-uspace: package-name-doesnt-match-sonames libcanterp0 liblinuxcnchal0 liblinuxcncini0 libnml0 libposemath0 libpyplugin0 librs274-0 libtooldata0
+linuxcnc-uspace: package-name-doesnt-match-sonames liblinuxcnchal0 liblinuxcncini0 libnml0 libposemath0 libpyplugin0 librs274-0 libtooldata0
# The man pages / documentation is likely to see an overhaul in a not too far future, prefer no to distract ourselves with these
linuxcnc-uspace: groff-message 19: can't open '../man/images/toggle.ps': No such file or directory [usr/share/man/man9/toggle.9.gz:1]
diff --git a/docs/man/man1/axis.1 b/docs/man/man1/axis.1
index 3678913509..556cf822fc 100644
--- a/docs/man/man1/axis.1
+++ b/docs/man/man1/axis.1
@@ -30,17 +30,16 @@ axis \- AXIS LinuxCNC Graphical User Interface
.B axis
\fI\-ini\fR \fIINIFILE\fR
.SH DESCRIPTION
-\fBaxis\fR is one of the Graphical User Interfaces (GUI) for LinuxCNC
+\fBaxis\fR is one of the Graphical User Interfaces (GUI) for LinuxCNC.
It gets run by the runscript usually.
.SH OPTIONS
.TP
\fBINIFILE\fR
-The ini file is the main piece of an LinuxCNC configuration. It is not the
-entire configuration; there are various other files that go with it
-(NML files, HAL files, TBL files, VAR files). It is, however, the most
-important one, because it is the file that holds the configuration
-together. It can adjust a lot of parameters itself, but it also tells
-\fBLinuxCNC\fR which other files to load and use.
+The INI file is the main piece of an LinuxCNC configuration.
+It is not the entire configuration; there are various other files that go with it
+(NML files, HAL files, TBL files, VAR files). It is, however, the most important one,
+because it is the file that holds the configuration together.
+It can adjust a lot of parameters itself, but it also tells \fBLinuxCNC\fR which other files to load and use.
.SH "SEE ALSO"
\fBLinuxCNC(1)\fR
@@ -54,7 +53,7 @@ None known at this time.
.SH AUTHOR
This man page written by Alex Joni, as part of the LinuxCNC project.
.SH REPORTING BUGS
-Report bugs to alex_joni AT users DOT sourceforge DOT net
+Report bugs to alex_joni AT users DOT sourceforge DOT net.
.SH COPYRIGHT
Copyright \(co 2007 Alex Joni.
.br
diff --git a/docs/man/man1/linuxcncrsh.1 b/docs/man/man1/linuxcncrsh.1
index 97040de413..eba24039ac 100644
--- a/docs/man/man1/linuxcncrsh.1
+++ b/docs/man/man1/linuxcncrsh.1
@@ -9,8 +9,7 @@ linuxcncrsh [OPTIONS] [\-\- LINUXCNC_OPTIONS]
\fBlinuxcncrsh\fP is a user interface for LinuxCNC.
Instead of popping up a GUI window like AXIS(1) and Touchy(1) do,
it processes text-mode commands that it receives via the network.
-A human (or a program) can interface with \fBlinuxcncrsh\fP using
-telnet(1), nc(1) or similar programs.
+A human (or a program) can interface with \fBlinuxcncrsh\fP using telnet(1), nc(1) or similar programs.
.P
All features of LinuxCNC are available via the \fBlinuxcncrsh\fP interface.
.SH OPTIONS
@@ -24,48 +23,43 @@ Specify the port for linuxcncrsh to listen on. Defaults to 5007 if omitted.
.B
\-n,\-\-name SERVER_NAME
.RS
-Sets the server name that linuxcncrsh will use to identify itself during
-handshaking with a new client. Defaults to EMCNETSVR if omitted.
+Sets the server name that linuxcncrsh will use to identify itself during handshaking with a new client.
+Defaults to EMCNETSVR if omitted.
.RE
.P
.B
\-w,\-\-connectpw PASSWORD
.RS
-Specify the connection password to use during handshaking with a new
-client. Note that the password is sent in the clear, so it can be read
-by anyone who can read packets on the network between the server and
-the client. Defaults to EMC if omitted.
+Specify the connection password to use during handshaking with a new client.
+Note that the password is sent in the clear, so it can be read by anyone who can read packets on the network between the server and the client.
+Defaults to EMC if omitted.
.RE
.P
.B
\-e,\-\-enablepw PASSWORD
.RS
-Specify the password required to enable LinuxCNC via linuxcncrsh. Note that the
-password is sent in the clear, so it can be read by anyone who can read
-packets on the network between the server and the client. Defaults to
-EMCTOO if omitted.
+Specify the password required to enable LinuxCNC via linuxcncrsh.
+Note that the password is sent in the clear, so it can be read by anyone who can read packets on the network between the server and the client.
+Defaults to EMCTOO if omitted.
.RE
.P
.B
\-s,\-\-sessions MAX_SESSIONS
.RS
-Specify the maximum number of simultaneous connections. Defaults to \-1
-(no limit) if not specified.
+Specify the maximum number of simultaneous connections. Defaults to \-1 (no limit) if not specified.
.RE
.P
-In addition to the options listed above, linuxcncrsh accepts an optional
-special LINUXCNC_OPTION at the end:
+In addition to the options listed above, linuxcncrsh accepts an optional special LINUXCNC_OPTION at the end:
.P
.B
\-ini LINUXCNC_INI_FILE
.RS
-LinuxCNC INI file to use. The \-ini option \fBmust\fP be preceded by two
-dashes: "\-\-". Defaults to emc.ini if omitted.
+LinuxCNC INI file to use. The \-ini option \fBmust\fP be preceded by two dashes: "\-\-".
+Defaults to emc.ini if omitted.
.RE
.SH Starting linuxcncrsh
.P
-To use linuxcncrsh instead of a normal LinuxCNC GUI like AXIS or Touchy, specify
-it in your INI file like this:
+To use linuxcncrsh instead of a normal LinuxCNC GUI like AXIS or Touchy, specify it in your INI file like this:
.RS
.P
.B [DISPLAY]
@@ -73,8 +67,7 @@ it in your INI file like this:
.B DISPLAY=linuxcncrsh
.RE
.P
-To use linuxcncrsh in addition to a normal GUI, you can either start it
-at the end of your HAL file, or run it by hand in a terminal window.
+To use linuxcncrsh in addition to a normal GUI, you can either start it at the end of your HAL file, or run it by hand in a terminal window.
.P
To start it from HAL, add a line like this to the end of your HAL file:
.RS
@@ -89,44 +82,39 @@ To start it from the terminal, run linuxcncrsh manually like this:
.RE
.SH Connecting
.P
-Once LinuxCNC is up and linuxcncrsh is running, you can connect to it using
-\fBtelnet\fP or \fBnc\fP or similar:
+Once LinuxCNC is up and linuxcncrsh is running, you can connect to it using \fBtelnet\fP or \fBnc\fP or similar:
.RS
.P
.B telnet HOST PORT
.RS
-HOST is the hostname or IP address of the computer running linuxcncrsh, and
-PORT is the port it's listening on (5007 if you did not give linuxcncrsh the
-\-\-port option).
+HOST is the hostname or IP address of the computer running linuxcncrsh,
+and PORT is the port it's listening on (5007 if you did not give linuxcncrsh the \-\-port option).
.RE
.SH Network protocol
.P
-linuxcncrsh accepts TCP connections on the port specified by the \-\-port option,
-or 5007 if not specified.
+linuxcncrsh accepts TCP connections on the port specified by the \-\-port option, or 5007 if not specified.
.P
The client sends requests, and the linuxcncrsh server returns replies.
-Requests consist of a command word followed by optional command-specific
-parameters. Requests and most request parameters are case
-insensitive. The exceptions are passwords, file paths and text strings.
+Requests consist of a command word followed by optional command-specific parameters.
+Requests and most request parameters are case insensitive.
+The exceptions are passwords, file paths and text strings.
.P
-Requests to linuxcncrsh are terminated with line endings, any combination of
-one or more '\\r' and '\\n' characters. Replies from linuxcncrsh are terminated
-with the sequence '\\r\\n'.
+Requests to linuxcncrsh are terminated with line endings, any combination of one or more '\\r' and '\\n' characters.
+Replies from linuxcncrsh are terminated with the sequence '\\r\\n'.
.P
The supported commands are as follows:
.P
\fBhello <password> <client> <version>\fR
.RS
-<password> must match linuxcncrsh's connect password, or "EMC" if no
-\-\-connectpw was supplied. The three arguments may not contain whitespace.
+<password> must match linuxcncrsh's connect password, or "EMC" if no \-\-connectpw was supplied.
+The three arguments may not contain whitespace.
If a valid password was entered the server will respond with:
.RS
\fIHELLO ACK <ServerName> <ServerVersion>\fR
.RE
.P
-If an invalid password or any other syntax error occurs then the server
-responds with:
+If an invalid password or any other syntax error occurs then the server responds with:
.RS
\fIHELLO NAK\fR
.RE
@@ -134,16 +122,12 @@ responds with:
.P
\fBget <subcommand> [<parameters>]\fR
.RS
-The get command takes one of the LinuxCNC sub-commands (described in the
-section \fBLinuxCNC Subcommands\fR, below) and zero or more additional
-subcommand-specific parameters.
+The get command takes one of the LinuxCNC sub-commands (described in the section \fBLinuxCNC Subcommands\fR, below) and zero or more additional subcommand-specific parameters.
.RE
.P
\fBset <subcommand> <parameters>\fR
.RS
-The set command takes one of the LinuxCNC sub-commands (described in the
-section \fBLinuxCNC Subcommands\fR, below) and one or more additional
-parameters.
+The set command takes one of the LinuxCNC sub-commands (described in the section \fBLinuxCNC Subcommands\fR, below) and one or more additional parameters.
.RE
.P
\fBquit\fR
@@ -153,19 +137,16 @@ The quit command disconnects the associated socket connection.
.P
\fBshutdown\fR
.RS
-The shutdown command tells LinuxCNC to shutdown and disconnect the
-session. This command may only be issued if the Hello has been
-successfully negotiated and the connection has control of the CNC (see
-\fBenable\fR subcommand in the \fBLinuxCNC Subcommands\fR section, below).
+The shutdown command tells LinuxCNC to shutdown and disconnect the session.
+This command may only be issued if the Hello has been successfully negotiated and the connection has control of the CNC (see \fBenable\fR subcommand in the \fBLinuxCNC Subcommands\fR section, below).
.RE
.P
\fBhelp\fR
.RS
-The help command will return help information in text format over the
-connection. If no parameters are specified, it will itemize the available
-commands. If a command is specified, it will provide usage information
-for the specified command. Help will respond regardless of whether a
-"Hello" has been successfully negotiated.
+The help command will return help information in text format over the connection.
+If no parameters are specified, it will itemize the available commands.
+If a command is specified, it will provide usage information for the specified command.
+Help will respond regardless of whether a "Hello" has been successfully negotiated.
.RE
.SH "LinuxCNC Subcommands"
.P
@@ -173,30 +154,29 @@ Subcommands for \fBget\fR and \fBset\fR are:
.P
\fBecho {on|off}\fR
.RS
-With get, any on/off parameter is ignored and the current echo state is
-returned. With set, sets the echo state as specified. Echo defaults to
-on when the connection is first established. When echo is on, all commands
-will be echoed upon receipt. This state is local to each connection.
+With get, any on/off parameter is ignored and the current echo state is returned.
+With set, sets the echo state as specified.
+Echo defaults to on when the connection is first established.
+When echo is on, all commands will be echoed upon receipt.
+This state is local to each connection.
.RE
.P
\fBverbose {on|off}\fR
.RS
-With get, any on/off parameter is ignored and the current verbose state
-is returned. With set, sets the verbose state as specified. When verbose
-mode is on, all set commands return positive acknowledgement in the form
-SET <COMMAND> ACK, and text error messages will be issued (FIXME: I don't
-know what this means). The verbose state is local to each connection,
-and starts out OFF on new connections.
+With get, any on/off parameter is ignored and the current verbose state is returned.
+With set, sets the verbose state as specified.
+When verbose mode is on, all set commands return positive acknowledgement in the form SET <COMMAND> ACK, and text error messages will be issued
+(FIXME: I don't know what this means).
+The verbose state is local to each connection, and starts out OFF on new connections.
.RE
.P
\fBenable {<passwd>|off}\fR
.RS
-The session's enable state indicates whether the current connection is
-enabled to perform control functions. With get, any parameter is ignored,
-and the current enable state is returned. With set and a valid password
-matching linuxcncrsh's \-\-enablepw (EMCTOO if not specified), the current
-connection is enabled for control functions. "OFF" may not be used as
-a password and disables control functions for this connection.
+The session's enable state indicates whether the current connection is enabled to perform control functions.
+With get, any parameter is ignored, and the current enable state is returned.
+With set and a valid password matching linuxcncrsh's \-\-enablepw (EMCTOO if not specified),
+the current connection is enabled for control functions.
+"OFF" may not be used as a password and disables control functions for this connection.
.RE
.P
\fBconfig [TBD]\fR
@@ -206,25 +186,23 @@ Unused, ignore for now.
.P
\fBcomm_mode {ascii|binary}\fR
.RS
-With get, any parameter is ignored and the current communications
-mode is returned. With set, will set the communications mode to the
-specified mode. The ascii mode is the text request/reply mode, the
-binary protocol is not currently designed or implemented.
+With get, any parameter is ignored and the current communications mode is returned.
+With set, will set the communications mode to the specified mode.
+The ASCII mode is the text request/reply mode, the binary protocol is not currently designed or implemented.
.RE
.P
\fBcomm_prot <version>\fR
.RS
-With get, any parameter is ignored and the current protocol version
-used by the server is returned. With set, sets the server to use the
-specified protocol version, provided it is lower than or equal to the
-highest version number supported by the server implementation.
+With get, any parameter is ignored and the current protocol version used by the server is returned.
+With set, sets the server to use the specified protocol version,
+provided it is lower than or equal to the highest version number supported by the server implementation.
.RE
.P
\fBinifile\fR
.RS
Not currently implemented! With get, returns the string "emc.ini".
-Should return the full path and file name of the current configuration
-inifile. Setting this does nothing.
+Should return the full path and file name of the current configuration INI file.
+Setting this does nothing.
.RE
.P
\fBplat\fR
@@ -234,48 +212,45 @@ With get, returns the string "Linux".
.P
\fBini <var> <section>\fR
.RS
-Not currently implemented, do not use! Should return the string value
-of <var> in section <section> of the INI file.
+Not currently implemented, do not use!
+Should return the string value of <var> in section <section> of the INI file.
.RE
.P
\fBdebug <value>\fR
.RS
-With get, any parameter is ignored and the current integer value of
-EMC_DEBUG is returned. Note that the value of EMC_DEBUG returned is
-the from the UI's ini file, which may be different than emc's ini file.
-With set, sends a command to the EMC to set the new debug level, and
-sets the EMC_DEBUG global here to the same value. This will make the
-two values the same, since they really ought to be the same.
+With get, any parameter is ignored and the current integer value of EMC_DEBUG is returned.
+Note that the value of EMC_DEBUG returned is the from the UI's INI file,
+which may be different than emc's INI file.
+With set, sends a command to the EMC to set the new debug level, and sets the EMC_DEBUG global here to the same value.
+This will make the two values the same, since they really ought to be the same.
.RE
.P
\fBset_wait {received|done}\fR
.RS
The set_wait setting controls the wait after receiving a command.
-It can be "received" (after the command was sent and received) or "done"
-(after the command was done). With get, any parameter is ignored and the
-current set_wait setting is returned. With set, set the set_wait setting
-to the specified value.
+It can be "received" (after the command was sent and received) or "done" (after the command was done).
+With get, any parameter is ignored and the current set_wait setting is returned.
+With set, set the set_wait setting to the specified value.
.RE
.P
\fBwait {received|done}\fR
.RS
-With set, force a wait for the previous command to be received, or
-done.
+With set, force a wait for the previous command to be received, or done.
.RE
.P
\fBset_timeout <timeout>\fR
.RS
-With set, set the timeout for commands to return to <timeout>
-seconds. Timeout is a real number. If it's <= 0.0, it means wait forever.
+With set, set the timeout for commands to return to <timeout> seconds.
+Timeout is a real number. If it's <= 0.0, it means wait forever.
Default is 0.0, wait forever.
.RE
.P
\fBupdate {none|auto}\fR
.RS
-The update mode controls whether to return fresh or stale values for
-"get" requests. When the update mode is "none" it returns stale values,
-when it's "auto" it returns fresh values. Defaults to "auto" for new
-connections. Set this to "none" if you like to be confused.
+The update mode controls whether to return fresh or stale values for "get" requests.
+When the update mode is "none" it returns stale values, when it's "auto" it returns fresh values.
+Defaults to "auto" for new connections.
+Set this to "none" if you like to be confused.
.RE
.P
\fBerror\fR
@@ -295,22 +270,21 @@ With get, returns the current operator text string, or "ok" if none.
.P
\fBtime\fR
.RS
-With get, returns the time, in seconds, from the start of the epoch. This
-starting time depends on the platform.
+With get, returns the time, in seconds, from the start of the epoch.
+This starting time depends on the platform.
.RE
.P
\fBestop {on|off}\fR
.RS
-With get, ignores any parameters and returns the current estop setting
-as "on" or "off". With set, sets the estop as specified. E-stop "on"
-means the machine is in the estop state and won't run.
+With get, ignores any parameters and returns the current estop setting as "on" or "off".
+With set, sets the estop as specified.
+E-stop "on" means the machine is in the estop state and won't run.
.RE
.P
\fBmachine {on|off}\fR
.RS
-With get, ignores any parameters and returns the current machine power
-setting as "on" or "off". With set, sets the machine on or off as
-specified.
+With get, ignores any parameters and returns the current machine power setting as "on" or "off".
+With set, sets the machine on or off as specified.
.RE
.P
\fBmode {manual|auto|mdi}\fR
@@ -321,20 +295,20 @@ With set, sets the machine mode as specified.
.P
\fBmist {on|off}\fR
.RS
-With get, ignores any parameters and returns the current mist coolant
-setting. With set, sets the mist setting as specified.
+With get, ignores any parameters and returns the current mist coolant setting.
+With set, sets the mist setting as specified.
.RE
.P
\fBflood {on|off}\fR
.RS
-With get, ignores any parameters and returns the current flood coolant
-setting. With set, sets the flood setting as specified.
+With get, ignores any parameters and returns the current flood coolant setting.
+With set, sets the flood setting as specified.
.RE
.P
\fBlube {on|off}\fR
.RS
-With get, ignores any parameters and returns the current lube pump
-setting. With set, sets the lube pump setting as specified.
+With get, ignores any parameters and returns the current lube pump setting.
+With set, sets the lube pump setting as specified.
.RE
.P
\fBlube_level\fR
@@ -346,16 +320,16 @@ With set, mocks you for wishful thinking.
\fBspindle {forward|reverse|increase|decrease|constant|off}\fR
.RS
With get, any parameter is ignored and the current spindle state is
-returned as "forward", "reverse", "increase", "decrease", or "off". With
-set, sets the spindle as specified. Note that "increase" and "decrease"
-will cause a speed change in the corresponding direction until a
-"constant" command is sent.
+returned as "forward", "reverse", "increase", "decrease", or "off".
+With set, sets the spindle as specified.
+Note that "increase" and "decrease" will cause a speed change in the corresponding direction
+until a "constant" command is sent.
.RE
.P
\fBbrake {on|off}\fR
.RS
-With get, any parameter is ignored and the current brake setting is
-returned. With set, the brake is set as specified.
+With get, any parameter is ignored and the current brake setting is returned.
+With set, the brake is set as specified.
.RE
.P
\fBtool\fR
@@ -375,7 +349,7 @@ With set, loads the tool table specified by <file>.
.P
\fBhome {0|1|2|...} | -1\fR
.RS
-With set, homes the indicated joint or if -1, Home All joints
+With set, homes the indicated joint or, if -1, homes all joints.
.RE
.P
\fBjog_stop joint_number|axis_letter\fR
@@ -394,86 +368,74 @@ If TELEOP_ENABLE is YES, use axis_letter.
.P
\fBjog_incr jog_number|axis_letter <speed> <incr>\fR
.RS
-With set, jog the indicated joint or axis by increment <incr> at the <speed>; sign of
-speed is direction.
+With set, jog the indicated joint or axis by increment <incr> at the <speed>; sign of speed is direction.
If TELEOP_ENABLE is NO, use joint_number;
If TELEOP_ENABLE is YES, use axis_letter.
.RE
.P
\fBfeed_override <percent>\fR
.RS
-With get, any parameter is ignored and the current feed override is
-returns (as a percentage of commanded feed). With set, sets the feed
-override as specified.
+With get, any parameter is ignored and the current feed override is returned (as a percentage of commanded feed).
+With set, sets the feed override as specified.
.RE
.P
\fBspindle_override <percent>\fR
.RS
-With get, any parameter is ignored and the current spindle override
-is returned (as a percentage of commanded speed). With set, sets the
-spindle override as specified.
+With get, any parameter is ignored and the current spindle override is returned (as a percentage of commanded speed).
+With set, sets the spindle override as specified.
.RE
.P
\fBabs_cmd_pos [{0|1|...}]\fR
.RS
-With get, returns the specified axis' commanded position in absolute
-coordinates. If no axis is specified, returns all axes' commanded
-absolute position.
+With get, returns the specified axis' commanded position in absolute coordinates.
+If no axis is specified, returns all axes' commanded absolute position.
.RE
.P
\fBabs_act_pos [{0|1|...}]\fR
.RS
-With get, returns the specified axis' actual position in absolute
-coordinates. If no axis is specified, returns all axes' actual absolute
-position.
+With get, returns the specified axis' actual position in absolute coordinates.
+If no axis is specified, returns all axes' actual absolute position.
.RE
.P
\fBrel_cmd_pos [{0|1|...}]\fR
.RS
-With get, returns the specified axis' commanded position in relative
-coordinates, including tool length offset. If no axis is specified,
-returns all axes' commanded relative position.
+With get, returns the specified axis' commanded position in relative coordinates, including tool length offset.
+If no axis is specified, returns all axes' commanded relative position.
.RE
.P
\fBrel_act_pos [{0|1|...}]\fR
.RS
-With get, returns the specified axis' actual position in relative
-coordinates, including tool length offset. If no axis is specified,
-returns all axes' actual relative position.
+With get, returns the specified axis' actual position in relative coordinates, including tool length offset.
+If no axis is specified, returns all axes' actual relative position.
.RE
.P
\fBjoint_pos [{0|1|...}]\fR
.RS
-With get, returns the specified joint's actual position in absolute
-coordinates, excluding tool length offset. If no joint is specified,
-returns all joints' actual absolute position.
+With get, returns the specified joint's actual position in absolute coordinates, excluding tool length offset.
+If no joint is specified, returns all joints' actual absolute position.
.RE
.P
\fBpos_offset [{X|Y|Z|R|P|W}]\fR
.RS
-With get, returns the position offset associated with the world coordinate
-provided.
+With get, returns the position offset associated with the world coordinate provided.
.RE
.P
\fBjoint_limit [{0|1|...}]\fR
.RS
-With get, returns limit status of the specified joint as "ok", "minsoft",
-"minhard", "maxsoft", or "maxhard". If no joint number is specified,
-returns the limit status of all joints.
+With get, returns limit status of the specified joint as "ok", "minsoft", "minhard", "maxsoft", or "maxhard".
+If no joint number is specified, returns the limit status of all joints.
.RE
.P
\fBjoint_fault [{0|1|...}]\fR
.RS
-With get, returns the fault status of the specified joint as "ok" or
-"fault". If no joint number is specified, returns the fault status of
-all joints.
+With get, returns the fault status of the specified joint as "ok" or "fault".
+If no joint number is specified, returns the fault status of all joints.
.RE
.P
\fBjoint_homed [{0|1|...}]\fR
.RS
-With get, returns the homed status of the specified joint as "homed"
-or "not". If no joint number is specified, returns the homed status of
-all joints.
+With get, returns the homed status of the specified joint as "homed" or "not".
+If no joint number is specified, returns the homed status of all joints.
.RE
.P
\fBmdi <string>\fR
@@ -488,16 +450,14 @@ With set, initializes the program interpreter.
.P
\fBopen <filename>\fR
.RS
-With set, opens the named file. The <filename> is opened by linuxcnc,
-so it should either be an absolute path or a relative path starting in
-the LinuxCNC working directory (the directory of the active INI file).
+With set, opens the named file.
+The <filename> is opened by linuxcnc, so it should either be an absolute path or a relative path starting in the LinuxCNC working directory (the directory of the active INI file).
.RE
.P
\fBrun [<StartLine>]\fR
.RS
-With set, runs the opened program. If no StartLine is specified, runs
-from the beginning. If a StartLine is specified, start line, runs from
-that line. A start line of \-1 runs in verify mode.
+With set, runs the opened program. If no StartLine is specified, runs from the beginning.
+If a StartLine is specified, start line, runs from that line. A start line of \-1 runs in verify mode.
.RE
.P
\fBpause\fR
@@ -548,15 +508,11 @@ specified joint (or for all joints if none is specified).
.P
\fBjoint_units [<joint>]\fR
.RS
-With get, returns "inch", "mm", "cm", or "deg", "rad", "grad", or
-"custom", for the corresponding native units of the specified joint (or
-for all joints if none is specified). The type of the axis (linear or
-angular) is used to resolve which type of units are returned. The units
-are obtained heuristically, based on the EMC_AXIS_STAT::units numerical
-value of user units per mm or deg. For linear joints, something close
-to 0.03937 is deemed "inch", 1.000 is "mm", 0.1 is "cm", otherwise it's
-"custom". For angular joints, something close to 1.000 is deemed "deg",
-PI/180 is "rad", 100/90 is "grad", otherwise it's "custom".
+With get, returns "inch", "mm", "cm", or "deg", "rad", "grad", or "custom", for the corresponding native units of the specified joint (or for all joints if none is specified).
+The type of the axis (linear or angular) is used to resolve which type of units are returned.
+The units are obtained heuristically, based on the EMC_AXIS_STAT::units numerical value of user units per mm or deg.
+For linear joints, something close to 0.03937 is deemed "inch", 1.000 is "mm", 0.1 is "cm", otherwise it's "custom".
+For angular joints, something close to 1.000 is deemed "deg", PI/180 is "rad", 100/90 is "grad", otherwise it's "custom".
.RE
.P
\fBprogram_units\fR
@@ -566,57 +522,49 @@ Synonym for program_linear_units.
.P
\fBprogram_linear_units\fR
.RS
-With get, returns "inch", "mm", "cm", or "none", for the corresponding
-linear units that are active in the program interpreter.
+With get, returns "inch", "mm", "cm", or "none", for the corresponding linear units that are active in the program interpreter.
.RE
.P
\fBprogram_angular_units\fR
.RS
-With get, returns "deg", "rad", "grad", or "none" for the corresponding
-angular units that are active in the program interpreter.
+With get, returns "deg", "rad", "grad", or "none" for the corresponding angular units that are active in the program interpreter.
.RE
.P
\fBuser_linear_units\fR
.RS
-With get, returns "inch", "mm", "cm", or "custom", for the corresponding
-native user linear units of the LinuxCNC trajectory level. This is obtained
-heuristically, based on the EMC_TRAJ_STAT::linearUnits numerical value
-of user units per mm. Something close to 0.03937 is deemed "inch",
-1.000 is "mm", 0.1 is "cm", otherwise it's "custom".
+With get, returns "inch", "mm", "cm", or "custom", for the corresponding native user linear units of the LinuxCNC trajectory level.
+This is obtained heuristically, based on the EMC_TRAJ_STAT::linearUnits numerical value of user units per mm.
+Something close to 0.03937 is deemed "inch", 1.000 is "mm", 0.1 is "cm", otherwise it's "custom".
.RE
.P
\fBuser_angular_units\fR
.RS
-Returns "deg", "rad", "grad", or "custom" for the corresponding native
-user angular units of the LinuxCNC trajectory level. Like with linear units,
-this is obtained heuristically.
+Returns "deg", "rad", "grad", or "custom" for the corresponding native user angular units of the LinuxCNC trajectory level.
+Like with linear units, this is obtained heuristically.
.RE
.P
\fBdisplay_linear_units\fR
.RS
-With get, returns "inch", "mm", "cm", or "custom", for the linear
-units that are active in the display. This is effectively the value
-of linearUnitConversion.
+With get, returns "inch", "mm", "cm", or "custom", for the linear units that are active in the display.
+This is effectively the value of linearUnitConversion.
.RE
\fBdisplay_angular_units\fR
.RS
-With get, returns "deg", "rad", "grad", or "custom", for the angular
-units that are active in the display. This is effectively the value
-of angularUnitConversion.
+With get, returns "deg", "rad", "grad", or "custom", for the angular units that are active in the display.
+This is effectively the value of angularUnitConversion.
.RE
.P
\fBlinear_unit_conversion {inch|mm|cm|auto}\fR
.RS
-With get, any parameter is ignored and the active unit conversion is
-returned. With set, sets the unit to be displayed. If it's "auto",
-the units to be displayed match the program units.
+With get, any parameter is ignored and the active unit conversion is returned.
+With set, sets the unit to be displayed.
+If it's "auto", the units to be displayed match the program units.
.RE
.P
\fBangular_unit_conversion {deg|rad|grad|auto}\fR
.RS
-With get, any parameter is ignored and the active unit conversion is
-returned. With set, sets the units to be displayed. If it's "auto",
-the units to be displayed match the program units.
+With get, any parameter is ignored and the active unit conversion is returned.
+With set, sets the units to be displayed. If it's "auto", the units to be displayed match the program units.
.RE
.P
\fBprobe_clear\fR
@@ -636,47 +584,44 @@ With get, return the current value of the probe signal.
.P
\fBprobe\fR
.RS
-With set, move toward a certain location. If the probe is tripped on
-the way stop motion, record the position and raise the probe tripped flag.
+With set, move toward a certain location.
+If the probe is tripped on the way stop motion, record the position and raise the probe tripped flag.
.RE
.P
\fBteleop_enable [on|off]\fR
.RS
-With get, any parameter is ignored and the current teleop mode is
-returned. With set, sets the teleop mode as specified.
+With get, any parameter is ignored and the current teleop mode is returned.
+With set, sets the teleop mode as specified.
.RE
.P
\fBkinematics_type\fR
.RS
-With get, returns the type of kinematics functions used (identity=1,
-serial=2, parallel=3, custom=4).
+With get, returns the type of kinematics functions used (identity=1, serial=2, parallel=3, custom=4).
.RE
.P
\fBoverride_limits {on|off}\fR
.RS
-With get, any parameter is ignored and the override_limits setting is
-returned. With set, the override_limits parameter is set as specified.
-If override_limits is on, disables end of travel hardware limits to
-allow jogging off of a limit. If parameters is off, then hardware limits
-are enabled.
+With get, any parameter is ignored and the override_limits setting is returned.
+With set, the override_limits parameter is set as specified.
+If override_limits is on, disables end of travel hardware limits to allow jogging off of a limit.
+If parameters is off, then hardware limits are enabled.
.RE
.P
\fBoptional_stop {0|1}\fR
.RS
-With get, any parameter is ignored and the current "optional stop on M1"
-setting is returned. With set, the setting is set as specified.
+With get, any parameter is ignored and the current "optional stop on M1" setting is returned.
+With set, the setting is set as specified.
.RE
.SH Example Session
.P
This section shows an example session to the local machine (\fBlocalhost\fR).
-Bold items are typed by you, non-bold is machine output. Default values are shown for
---port PORT_NUMBER (\fB5007\fR), --conectpw PASSWORD (\fBEMC\fR), and
---enablepw PASSWORD (\fBEMCTOO\fR).
-.P
-The user connects to linuxcncrsh, handshakes with the server (hello), enables
-machine commanding from this session (set enable), brings the machine
-out of E-stop (set estop off) and turns it on (set machine on), homes all
-the axes, switches the machine to mdi mode, sends an MDI G-code command,
+Bold items are typed by you, non-bold is machine output.
+Default values are shown for --port PORT_NUMBER (\fB5007\fR), --conectpw PASSWORD (\fBEMC\fR), and --enablepw PASSWORD (\fBEMCTOO\fR).
+.P
+The user connects to linuxcncrsh, handshakes with the server (hello),
+enables machine commanding from this session (set enable),
+brings the machine out of E-stop (set estop off) and turns it on (set machine on),
+homes all the axes, switches the machine to mdi mode, sends an MDI G-code command,
then disconnects and shuts down LinuxCNC.
.P
> \fBtelnet localhost 5007\fR
diff --git a/docs/man/man1/mitsub_vfd.1 b/docs/man/man1/mitsub_vfd.1
index 557ac70506..5e5ee8da0f 100644
--- a/docs/man/man1/mitsub_vfd.1
+++ b/docs/man/man1/mitsub_vfd.1
@@ -11,37 +11,29 @@ The connection is made through the PU connector.
.B loadrt mitsub_vfd [--baud 4800] [--port /dev/ttyUSB0] name1=number1[,name2=numer2...]
.br
-\fBname1\fR is user selectable (usually a description of the
-controlled device).
+\fBname1\fR is user selectable (usually a description of the controlled device).
.br
-\fBnumber1\fR is the slave number that was set on the VFD.
-must be two digits (Parameter 117)
+\fBnumber1\fR is the slave number that was set on the VFD. Must be two digits (Parameter 117).
.br
-\fBname=number\fR can be repeated for multiple VFD's
-connected together
+\fBname=number\fR can be repeated for multiple VFD's connected together.
.br
-\fB--baud\fR is optional as it defaults to 9600
- all networked vfds must be set to the same baudrate
+\fB--baud\fR is optional as it defaults to 9600, all networked vfds must be set to the same baudrate.
.br
-\fB--port\fR is optional as it defaults to ttyS0
+\fB--port\fR is optional as it defaults to ttyS0.
.SH DESCRIPTION
-The mitsub_vfd component interfaces a Mitsubishi VFD to
-LinuxCNC. The VFD is connected via RS-485 serial to the
-computer's USB or serial port using a RS-232/RS-485 converter
+The mitsub_vfd component interfaces a Mitsubishi VFD to LinuxCNC.
+The VFD is connected via RS-485 serial to the computer's USB or serial port using a RS-232/RS-485 converter.
.SH HARDWARE SETUP
-reference manual 'communication option reference manual'
-and A500 technical manual for 500 series.
-Fr-A700 F700 E700 D700 technical manual for the 700 series
+reference manual 'communication option reference manual' and A500 technical manual for 500 series.
+Fr-A700 F700 E700 D700 technical manual for the 700 series.
.br
-The inverter must be set manually for communication
+The inverter must be set manually for communication (you may have to set PR 77 to 1 to unlock PR modification).
.br
-( you may have to set PR 77 to 1 to unlock PR modification )
-.br
-You must power cycle the inverter for some of these. (eg 79)
+You must power cycle the inverter for some of these, e.g. 79.
.TP
\fBVFD INTERNAL PARAMETERS: \fR
@@ -66,16 +58,15 @@ You must power cycle the inverter for some of these. (eg 79)
\fBPARAMETER 121\fR COM tries - 10
.br
-(if maximuim 10 COM errors then inverter faults- can change)
+(if maximuim 10 COM errors then inverter faults- can change.)
\fBPARAMETER 122\fR COM check time interval 9999
.br
-(never check - if communication is lost inverter will
-not know (can change)
+(never check - if communication is lost inverter will not know (can change))
\fBPARAMETER 123\fR wait time - 9999
.br
-no wait time is added to the serial data frame (don't change)
+No wait time is added to the serial data frame (don't change).
\fBPARAMETER 124\fR CR selection - 0
.br
@@ -88,7 +79,7 @@ computer link protocol - don't change - (not all VFDs have this)
.SH
This driver assumes certain other VFD settings:
--That the motor frequency status is set to show herts.
+-That the motor frequency status is set to show Hertz.
.br
-That the status bit 3 is up to speed
.br
@@ -115,15 +106,12 @@ amps, alarm and status bits are not useful.
.br
\fB[VFD NAME].monitor\fR (bit, in)::
set monitor mode pin
- If false request-status command will not be sent to VFD.
- Status, amps, power, motor-feedback, and alarm would then not
- be useful.
+ If false request-status command will not be sent to VFD. Status, amps, power, motor-feedback, and alarm would then not be useful.
.br
\fB[VFD NAME].estop\fR (bit, in)::
set E-stop mode pin
.br
- This will stop the VFD.
- Restarting requires the run pin to cycle.
+ This will stop the VFD. Restarting requires the run pin to cycle.
\fB[VFD NAME].fwd\fR (bit, out)::
up-to-speed status pin
diff --git a/docs/man/man1/moveoff_gui.1 b/docs/man/man1/moveoff_gui.1
index da20779087..fc9a81f51c 100644
--- a/docs/man/man1/moveoff_gui.1
+++ b/docs/man/man1/moveoff_gui.1
@@ -53,7 +53,7 @@ Show options and exit
.TP
\fB\-mode\fR \fBonpause\fR | always
.br
-onpause: popup GU to control offsets when program paused
+onpause: popup GUI to control offsets when program paused
.br
always: show GUI to control offsets always
.br
diff --git a/docs/man/man1/shuttle.1 b/docs/man/man1/shuttle.1
index a575e1ac2e..7fa2372f97 100644
--- a/docs/man/man1/shuttle.1
+++ b/docs/man/man1/shuttle.1
@@ -4,34 +4,29 @@ shuttle \- control HAL pins with the ShuttleXpress, ShuttlePRO, and ShuttlePRO2
.SH SYNOPSIS
\fIloadusr\fR \fBshuttle\fR \fI[DEVICE ...]\fR
.SH DESCRIPTION
-shuttle is a non-realtime HAL component that interfaces Contour
-Design's ShuttleXpress, ShuttlePRO, and ShuttlePRO2 devices with LinuxCNC's HAL.
+shuttle is a non-realtime HAL component that interfaces
+Contour Design's ShuttleXpress, ShuttlePRO, and ShuttlePRO2 devices with LinuxCNC's HAL.
.PP
-If the driver is started without command-line arguments, it will probe all
-/dev/hidraw* device files for Shuttle devices, and use all devices found.
-If it is started with command-line arguments, it will only probe the
-devices specified.
+If the driver is started without command-line arguments,
+it will probe all /dev/hidraw* device files for Shuttle devices, and use all devices found.
+If it is started with command-line arguments, it will only probe the devices specified.
.PP
-The ShuttleXpress has five momentary buttons, a 10 counts/revolution
-jog wheel with detents, and a 15-position spring-loaded outer wheel that
-returns to center when released.
+The ShuttleXpress has five momentary buttons, a 10 counts/revolution jog wheel with detents,
+and a 15-position spring-loaded outer wheel that returns to center when released.
.PP
-The ShuttlePRO has 13 momentary buttons, a 10 counts/revolution
-jog wheel with detents, and a 15-position spring-loaded outer wheel that
-returns to center when released.
+The ShuttlePRO has 13 momentary buttons, a 10 counts/revolution jog wheel with detents,
+and a 15-position spring-loaded outer wheel that returns to center when released.
.PP
-The ShuttlePRO2 has 15 momentary buttons, a 10 counts/revolution
-jog wheel with detents, and a 15-position spring-loaded outer wheel that
-returns to center when released.
+The ShuttlePRO2 has 15 momentary buttons, a 10 counts/revolution jog wheel with detents,
+and a 15-position spring-loaded outer wheel that returns to center when released.
.SH UDEV
-The shuttle driver needs read permission to the Shuttle devices'
-/dev/hidraw* device files. This can be accomplished by adding a file
-\fB/etc/udev/rules.d/99-shuttle.rules\fR, with the following contents:
+The shuttle driver needs read permission to the Shuttle devices' /dev/hidraw* device files.
+This can be accomplished by adding a file \fB/etc/udev/rules.d/99-shuttle.rules\fR, with the following contents:
SUBSYSTEM=="hidraw", ATTRS{idVendor}=="0b33", ATTRS{idProduct}=="0020", MODE="0444"
@@ -39,26 +34,25 @@ SUBSYSTEM=="hidraw", ATTRS{idVendor}=="05f3", ATTRS{idProduct}=="0240", MODE="04
SUBSYSTEM=="hidraw", ATTRS{idVendor}=="0b33", ATTRS{idProduct}=="0030", MODE="0444"
-The LinuxCNC Debian package installs an appropriate udev file
-automatically, but if you are building LinuxCNC from source and are not
-using the Debian packaging, you'll need to install this file by hand.
-If you install the file by hand you'll need to tell udev to reload its
-rules files by running `udevadm control --reload-rules`.
+The LinuxCNC Debian package installs an appropriate udev file automatically,
+but if you are building LinuxCNC from source and are not using the Debian packaging,
+you'll need to install this file by hand.
+If you install the file by hand
+you'll need to tell udev to reload its rules files by running `udevadm control --reload-rules`.
.SH A warning about the Jog Wheel
-The Shuttle devices have an internal 8-bit counter for the current
-jog-wheel position. The shuttle driver can not know this value
-until the Shuttle device sends its first event. When the first
-event comes into the driver, the driver uses the device's reported
-jog-wheel position to initialize counts to 0.
+The Shuttle devices have an internal 8-bit counter for the current jog-wheel position.
+The shuttle driver can not know this value until the Shuttle device sends its first event.
+When the first event comes into the driver,
+the driver uses the device's reported jog-wheel position to initialize counts to 0.
This means that if the first event is generated by a jog-wheel move,
that first move will be lost.
Any user interaction with the Shuttle device will generate an event,
-informing the driver of the jog-wheel position. So if you (for example)
-push one of the buttons at startup, the jog-wheel will work fine and
-notice the first click.
+informing the driver of the jog-wheel position.
+So if you (for example) push one of the buttons at startup,
+the jog-wheel will work fine and notice the first click.
.SH Pins
@@ -71,10 +65,9 @@ of the device (the order in which the driver found them), for example
.TP
(bit out) \fI(prefix).button-(number)-not\fR
- The momentary buttons. "(number)" identifies which button corresponds
- to the HAL pin. The "button-(number)" pins are True when the button
- is pushed, the "button-(number)-not" pins are True when the button
- is not pushed.
+ The momentary buttons. "(number)" identifies which button corresponds to the HAL pin.
+ The "button-(number)" pins are True when the button is pushed,
+ the "button-(number)-not" pins are True when the button is not pushed.
.TP
(s32 out) \fI(prefix).counts\fR
@@ -85,15 +78,13 @@ of the device (the order in which the driver found them), for example
(s32 out) \fI(prefix).spring-wheel-s32\fR
The current deflection of the spring-wheel (the outer wheel).
- It's 0 at rest, and ranges from -7 at the counter-clockwise
- extreme to +7 at the clockwise extreme.
+ It's 0 at rest, and ranges from -7 at the counter-clockwise extreme to +7 at the clockwise extreme.
.TP
(float out) \fI(prefix).spring-wheel-f\fR
The current deflection of the spring-wheel (the outer wheel).
- It's 0.0 at rest, -1.0 at the counter-clockwise extreme, and +1.0 at
- the clockwise extreme. (The Shuttle devices report the spring-wheel
- position as an integer from -7 to +7, so this pin reports only 15
- discrete values in its range.)
+ It's 0.0 at rest, -1.0 at the counter-clockwise extreme, and +1.0 at the clockwise extreme.
+ (The Shuttle devices report the spring-wheel position as an integer from -7 to +7,
+ so this pin reports only 15 discrete values in its range.)
diff --git a/docs/man/man1/touchy.1 b/docs/man/man1/touchy.1
index 6542b36a87..a638c54337 100644
--- a/docs/man/man1/touchy.1
+++ b/docs/man/man1/touchy.1
@@ -29,23 +29,20 @@ axis \- TOUCHY LinuxCNC Graphical User Interface
.B touchy
\fI\-ini\fR \fI<INI file>\fR
.SH DESCRIPTION
-\fBtouchy\fR is one of the Graphical User Interfaces (GUI) for LinuxCNC
+\fBtouchy\fR is one of the Graphical User Interfaces (GUI) for LinuxCNC.
It gets run by the runscript usually.
.SH OPTIONS
.TP
\fBINI file\fR
-The INI file is the main piece of an LinuxCNC configuration. It is not the
-entire configuration; there are various other files that go with it
-(NML files, HAL files, TBL files, VAR files). It is, however, the most
-important one, because it is the file that holds the configuration
-together. It can adjust a lot of parameters itself, but it also tells
-\fBLinuxCNC\fR which other files to load and use.
+The INI file is the main piece of an LinuxCNC configuration.
+It is not the entire configuration; there are various other files that go with it (NML files, HAL files, TBL files, VAR files).
+It is, however, the most important one, because it is the file that holds the configuration together.
+It can adjust a lot of parameters itself, but it also tells \fBLinuxCNC\fR which other files to load and use.
.SH "SEE ALSO"
\fBLinuxCNC(1)\fR
-Much more information about LinuxCNC and HAL is available in the LinuxCNC
-and HAL User Manuals, found at /usr/share/doc/LinuxCNC/.
+Much more information about LinuxCNC and HAL is available in the LinuxCNC and HAL User Manuals, found at /usr/share/doc/LinuxCNC/.
.SH BUGS
None known at this time.
@@ -57,5 +54,5 @@ Report bugs at https://github.com/LinuxCNC/linuxcnc/issues
.SH COPYRIGHT
Copyright \(co 2020 andypugh.
.br
-This is free software; see the source for copying conditions. There is NO
-warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+This is free software; see the source for copying conditions.
+There is NO warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
diff --git a/docs/man/man1/xhc-hb04.1 b/docs/man/man1/xhc-hb04.1
index 69ffd4cb58..e33281b66b 100644
--- a/docs/man/man1/xhc-hb04.1
+++ b/docs/man/man1/xhc-hb04.1
@@ -107,8 +107,8 @@ A 1 pulse on this pin changes the stepsize to the next lower stepsize in the ste
(float in) \fIxhc\-hb04.[xyza].pos\-absolute\fR
Absolute position display.
The LCD display for pos\-absolute is fixed format with a sign, 4 number digits and 3 fraction digits (+XXXX.XXX),
-require: \-9999.999 <= value <= 9999.999.
-(typically connect to: halui.axis.N.pos\-feedback)
+require: \-9999.999 <= value <= 9999.999
+(typically connect to: halui.axis.N.pos\-feedback).
.TP
(float in) \fIxhc\-hb04.[xyza].pos\-relative\fR
Relative position display
@@ -120,25 +120,26 @@ require: \-9999.999 <= value <= 9999.999.
(float in) \fIxhc\-hb04.feed\-override\fR
Feed\-override value.
The float value is converted to a 16 bit integer and multiplied by 100 in order to display as percent, require: 0 <= pinvalue <= 655
-(typically connect to: halui.feed\-override.value)
+(typically connect to: halui.feed\-override.value).
.TP
(float in) \fIxhc\-hb04.feed\-value\fR
Current Feed-value (units/sec).
The float value is converted to a 16 bit integer and multiplied by 60 in order to display as units-per-minute, require: 0 <= pinvalue <= 1092
-(65520 units-per-minute) (typically connect to: motion.current\-vel)
+(65520 units-per-minute) (typically connect to: motion.current\-vel).
.TP
(float in) \fIxhc\-hb04.spindle\-override\fR
Spindle\-override value.
The float value is converted to a 16 bit integer and multiplied by 100 in order to display as percent, require: 0 <= pinvalue <= 655)
-(typically connect to: halui.spindle\-override.value)
+(typically connect to: halui.spindle\-override.value).
.TP
(float in) \fIxhc\-hb04.spindle\-rps\fR
Spindle speed in RPS (revolutions per second).
The float value is converted to a 16 bit integer and multiplied by 60 in order to display as RPMs, require: 0 <= pinvalue <= 1092 (65520 RPM)
-(typically connect to: spindle.N.speed\-out\-rps\-abs)
+(typically connect to: spindle.N.speed\-out\-rps\-abs).
.TP
-(bit in) \fIxhc\-hb04.inch\-icon\fR Use inch icon (default is mm)
+(bit in) \fIxhc\-hb04.inch\-icon\fR
+Use inch icon (default is mm):
.SH Output Pins (Status)
.TP
@@ -170,7 +171,7 @@ Current stepsize in the stepsize sequence as controlled by the stepsize\-up and/
.SH Output Pins (for jogging using axis.N.jog\-counts)
.TP
-(s32 out) \fIxhc\-hb04.jog.counts\fR
+(s32 out) \fIxhc\-hb04.jog.counts\fR
Number of counts of the wheel since start\-up (50 counts per wheel revolution)
(typically connect to axis.N.jog\-counts (lowpass filtering may be helpful)).
.TP
@@ -178,26 +179,25 @@ Number of counts of the wheel since start\-up (50 counts per wheel revolution)
The value of the xhc\-hb04.jog.counts multiplied by \-1.
.TP
(float out) \fIxhc\-hb04.jog.scale\fR
-Value is the current stepsize multiplied by 0.001
-(typically connect to axis.N.jog\-scale).
+Value is the current stepsize multiplied by 0.001 (typically connect to axis.N.jog\-scale).
-.SH Experimental: Pins for halui plus/minus jogging
+.SH Experimental: Pins for halui plus/minus jogging.
These pins provide some support for non\-trivkins, world mode jogging.
.TP
(float in) \fIxhc\-hb04.jog.max\-velocity\fR
-Connect to halui.max\-velocity.value
+Connect to halui.max\-velocity.value.
.TP
(float out) \fIxhc\-hb04.jog.velocity\fR
-Connect to halui.jog\-speed
+Connect to halui.jog\-speed.
.TP
(bit out) \fIxhc\-hb04.jog.plus\-[xyza]\fR
-Connect to halui.jog.N.plus
+Connect to halui.jog.N.plus.
.TP
(bit out) \fIxhc\-hb04.jog.minus\-[xyza]\fR
-Connect to halui.jog.N.minus
+Connect to halui.jog.N.minus.
.TP
(float out) \fIxhc\-hb04.jog.increment\fR
-Debug pin -- abs(delta_pos)
+Debug pin -- abs(delta_pos).
.SH Button output pins (for the 18 button, layout2 pendant)
The output bit type pins are TRUE when the button is pressed.
diff --git a/docs/man/man3/hm2_allocate_bspi_tram.3hm2 b/docs/man/man3/hm2_allocate_bspi_tram.3hm2
index 98eeda4cb1..2b7020fdca 100644
--- a/docs/man/man3/hm2_allocate_bspi_tram.3hm2
+++ b/docs/man/man3/hm2_allocate_bspi_tram.3hm2
@@ -15,13 +15,11 @@ hm2_allocate_bspi_tram(char* name)
.SH DESCRIPTION
\fBhm2_allocate_bspi_tram\fR Allocate the TRAM memory for bspi instance "name".
"name" is a unique string given to each bspi channel during hostmot2 setup.
-The names of the available channels are printed to standard output during the
-driver loading process and take the form:
-hm2_<board name>.<board index>.bspi.<index> For example hm2_5i23.0.bspi.0
+The names of the available channels are printed to standard output during the driver loading process and take the form:
+hm2_<board name>.<board index>.bspi.<index>, for example: hm2_5i23.0.bspi.0 .
This function allocates the TRAM memory and sets up the regular data transfers.
-It should be called only when all the frames have been defined by calls to
-hm2_tram_add_bspi_frame().
+It should be called only when all the frames have been defined by calls to hm2_tram_add_bspi_frame().
.SH REALTIME CONSIDERATIONS
Call only from realtime init code, not from user space or realtime code.
diff --git a/docs/man/man3/hm2_bspi_setup_chan.3hm2 b/docs/man/man3/hm2_bspi_setup_chan.3hm2
index ff5bf89209..98d36e4b53 100644
--- a/docs/man/man3/hm2_bspi_setup_chan.3hm2
+++ b/docs/man/man3/hm2_bspi_setup_chan.3hm2
@@ -35,7 +35,7 @@ The maximum supported length is 64 bits but this will span two read FIFO entries
.IP mhz
sets the chip communication rate.
-The maximum value for this is half the FPGA base frequency, so for example with a 48 MHz 5i23 the max SPI frequency is 24 MHz.
+The maximum value for this is half the FPGA base frequency, so for example with a 48 MHz 5I23 the max SPI frequency is 24 MHz.
Values in excess of the max supported will be silently rounded down.
.IP delay
diff --git a/docs/man/man3/hm2_uart_setup.3hm2 b/docs/man/man3/hm2_uart_setup.3hm2
index a9a18c56f5..b59a226a5c 100644
--- a/docs/man/man3/hm2_uart_setup.3hm2
+++ b/docs/man/man3/hm2_uart_setup.3hm2
@@ -12,50 +12,35 @@ int hm2_uart_setup(char *name, int bitrate, s32 tx_mode, s32 rx_mode){
.SH DESCRIPTION
\fBhm2_uart_setup\fR Setup the bitrate for the UART named "name".
-"name" is a unique string given to each UART during hostmot2
-setup. The names of the available UARTs are printed to standard output during
-the driver loading process and take the form:
-hm2_<board name>.<board index>.uart.<index> For example hm2_5i23.0.uart.0
-The minimum bitrate is approximately 50bps, and the maximum around the FPGA
-frequency, 48 MHz for a 5i23.
-The UART function allows different RX and TX bitrates, but that is not currently
-supported by this driver
+"name" is a unique string given to each UART during hostmot2 setup.
+The names of the available UARTs are printed to standard output during the driver loading process and take the form:
+hm2_<board name>.<board index>.uart.<index>, for example hm2_5i23.0.uart.0.
+The minimum bitrate is approximately 50 bps, and the maximum around the FPGA frequency, 48 MHz for a 5I23.
+The UART function allows different RX and TX bitrates, but that is not currently supported by this driver
tx_mode is bit mask defined in the Hostmot2 regmap:
-Bit 0..3 = TXEnable delay. TXEnable delay specifies the transmit data
- holdoff time from the TXenable signal valid state. This is used for
- RS-485 (half duplex) operation, to delay transmit data until the driver
- is enabled, allowing for driver enable delays, isolation barrier delays
- etc. Delay is in units of ClockLow period.
-Bit 4 = FIFOError, it indicates that a host push has overflowed the FIFO
- (Mainly for driver debugging)
-Bit 5 = DriveEnableAuto, When set, enables Drive when any data is in FIFO or
- Xmit Shift register,removes drive when FIFO and Xmit shift register
- are empty.
-Bit 6 = DriveEnableBit, If DriveEnableAuto is 0, controls Drive (
- for software control of Xmit drive)
+Bit 0..3 = TXEnable delay. TXEnable delay specifies the transmit data holdoff time from the TXenable signal valid state. This is used for RS-485 (half duplex) operation, to delay transmit data until the driver is enabled, allowing for driver enable delays, isolation barrier delays, etc. Delay is in units of ClockLow period.
+Bit 4 = FIFOError, it indicates that a host push has overflowed the FIFO (Mainly for driver debugging).
+Bit 5 = DriveEnableAuto, When set, enables Drive when any data is in FIFO or Xmit Shift register,removes drive when FIFO and Xmit shift register are empty.
+Bit 6 = DriveEnableBit, If DriveEnableAuto is 0, controls Drive (for software control of Xmit drive).
rx_mode is bit mask defined in the Hostmot2 regmap:
Bit 0 = FalseStart bit Status, 1 = false start bit detected
Bit 1 = OverRun Status, 1 = overrun condition detected (no valid stop bit)
-Bit 2 = RXMaskEnable, 1= enable RXMask for half duplex operation,
- 0 = ignore RXMask
-Bit 4 = FIFOError, indicates that a host read has attempted to read more
- data than available. (mainly for driver debugging)
-Bit 5 = LostDataError, indicates that data was received with no room in FIFO,
- therefore lost
+Bit 2 = RXMaskEnable, 1= enable RXMask for half duplex operation, 0 = ignore RXMask
+Bit 4 = FIFOError, indicates that a host read has attempted to read more data than available. (mainly for driver debugging)
+Bit 5 = LostDataError, indicates that data was received with no room in FIFO, therefore lost
Bit 6 = RXMask, RO RXMASK status
Bit 7 = FIFO Has Data
-rx_mode and tx_mode registers are currently write-only. There should possibly be
-a get-status function.
+rx_mode and tx_mode registers are currently write-only.
+There should possibly be a get-status function.
-To write only to the tx_mode DriveEnable bit call this function with the bitrate
-unchanged and \-1 as the rx_mode
+To write only to the tx_mode DriveEnable bit call this function with the bitrate unchanged and \-1 as the rx_mode.
To change bitrate without altering mode settings send \-1 to both modes.
.SH RETURN VALUE
-Returns0 on success and \-1 on failure
+Returns 0 on success and \-1 on failure.
.SH SEE ALSO
\fBhm2_uart_send\fR(3hm2), \fBhm2_uart_read\fR(3hm2)
diff --git a/docs/man/man3/intro.3hal b/docs/man/man3/intro.3hal
index 1faef6e654..0a22feddb0 100644
--- a/docs/man/man3/intro.3hal
+++ b/docs/man/man3/intro.3hal
@@ -68,7 +68,7 @@ For an explanation of realtime considerations, see \fBintro(3rtapi)\fR.
.SH HAL STATUS CODES
Except as noted in specific manual pages, HAL returns negative errno values
-for errors, and nonnegative values for success.
+for errors, and non-negative values for success.
.SH SEE ALSO
\fBintro(3rtapi)\fR
diff --git a/docs/man/man9/gladevcp.9 b/docs/man/man9/gladevcp.9
index 08ea5bd46b..9f83736bb5 100644
--- a/docs/man/man9/gladevcp.9
+++ b/docs/man/man9/gladevcp.9
@@ -15,7 +15,7 @@ The \-x option directs GladeVCP to reparent itself under this X window id instea
The \-H option passes an input file for halcmd to be run after the GladeVCP component is initialized. This is used in Axis when
running GladeVCP under a tab with the EMBED_TAB_NAME/EMBED_TAB_COMMAND INI file feature.
-GladeVCP supports GtkBuilder or libglade files though some widgets that are not fully supported in GtkBuilder yet.
+GladeVCP supports GtkBuilder or libglade files though some widgets are not fully supported in GtkBuilder yet.
.SH ISSUES
For now, system links need to be added in the glade library folders to point to our new widgets and catalog files. Look in lib/python/gladevcp/READ_ME for details.
diff --git a/docs/man/man9/hm2_eth.9 b/docs/man/man9/hm2_eth.9
index d79fb04a15..0ad23bd9dc 100644
--- a/docs/man/man9/hm2_eth.9
+++ b/docs/man/man9/hm2_eth.9
@@ -34,50 +34,40 @@ hm2_eth \- LinuxCNC HAL driver for the Mesa Electronics Ethernet Anything IO boa
HostMot2 config strings, described in the hostmot2(9) manpage.
.TP
\fBboard_ip\fR [default: ""]
-The IP address of the board(s), separated by commas. As shipped, the board address is 192.168.1.121.
-.SH DESCRIPTION
+The IP address of the board(s), separated by commas.
+As shipped, the board address is 192.168.1.121.
-hm2_eth is a device driver that interfaces Mesa's ethernet
-based Anything I/O boards (with the HostMot2 firmware) to the LinuxCNC
-HAL.
+.SH DESCRIPTION
+hm2_eth is a device driver that interfaces Mesa's ethernet based Anything I/O boards (with the HostMot2 firmware) to the LinuxCNC HAL.
The supported boards are: 7I76E, 7I80DB, 7I80HD, 7I92, 7I93, 7I94, 7I95, 7I96, 7I96S, 7I97, 7I98.
-
The board must have its firmware loaded on the board by the mesaflash(1) program.
hm2_eth is only available when LinuxCNC is configured with "uspace" realtime.
.SH INTERFACE CONFIGURATION
-hm2_eth should be used on a dedicated network interface, with only a cable
-between the PC and the board. Wireless and USB network interfaces are not
-suitable.
-
-These instructions assume your dedicated network interface is "eth1",
-192.168.1/24 is an unused private network, that the hostmot2 board is using the
-default address of 192.168.1.121, that you are using Debian 7 or similar, and
-that you do not otherwise use iptables. If any of these are false, you will
-need to modify the instructions accordingly. After following all the
-instructions, reboot so that the changes take effect.
-
-It is particularly important to check that the network 192.168.1/24 is not
-already the private network used by your internet router, because this is a
-commonly-used value. If you use another network, you will also need to
-reconfigure the hostmot2 card to use an IP address on that network by using the
-mesaflash(1) utility and change jumper settings. Typically, you will choose
-one of the networks in the
+hm2_eth should be used on a dedicated network interface, with only a cable between the PC and the board.
+Wireless and USB network interfaces are not suitable.
+
+These instructions assume your dedicated network interface is "eth1", 192.168.1/24 is an unused private network,
+that the hostmot2 board is using the default address of 192.168.1.121, that you are using Debian 7 or similar, and that you do not otherwise use iptables.
+If any of these are false, you will need to modify the instructions accordingly.
+After following all the instructions, reboot so that the changes take effect.
+
+It is particularly important to check that the network 192.168.1/24 is not already the private network used by your internet router, because this is a commonly-used value.
+If you use another network, you will also need to reconfigure the hostmot2 card to use an IP address on that network by using the mesaflash(1) utility and change jumper settings.
+Typically, you will choose one of the networks in the
.UR http://en.wikipedia.org/wiki/IPv4#Private_networks
Private IPv4 address space.
.UE
One common alternative is PC address 10.10.10.1, hostmot2 address 10.10.10.10.
-Use of the dedicated ethernet interface while LinuxCNC is running can cause
-violation of realtime guarantees. hm2_eth will automatically mitigate most
-accidental causes of interference.
+Use of the dedicated ethernet interface while LinuxCNC is running can cause violation of realtime guarantees.
+hm2_eth will automatically mitigate most accidental causes of interference.
.SS Configure network with static address
-Add these lines to the file /etc/network/interfaces to configure eth1 with a
-static address:
+Add these lines to the file /etc/network/interfaces to configure eth1 with a static address:
.EX
auto eth1
@@ -87,30 +77,24 @@ iface eth1 inet static
.EE
.SH PACKET LOSS
-While ethernet is fairly resistant to electrical noise, many systems will not
-have 100% perfect packet reception.
-The hm2_eth driver has a limited ability to deal with lost packets. Packet
-loss is detected by transmitting an expected read or write packet count with
-each request, and checking the value with each read response. When a lost
-packet is detected, the
+While ethernet is fairly resistant to electrical noise, many systems will not have 100% perfect packet reception.
+The hm2_eth driver has a limited ability to deal with lost packets.
+Packet loss is detected by transmitting an expected read or write packet count with each request, and checking the value with each read response.
+When a lost packet is detected, the
.B packet\-error
pin is asserted in that cycle, the
.B packet\-error\-level
pin is increased, and if it reaches a threshold then a permanent low-level
I/O error is signaled.
-However, not all hm2 special functions know how to properly recover from lost
-packets. For instance, the encoder special function does not properly manage
-the index feature when packets are lost. The author believes that this can
-lead to rare failures in home-to-index, which can have severe consequences.
-
-On the other hand, pid-stepper systems will run properly for extended periods
-of time with packet loss on the order of .01%, as long as following error is
-increased enough that having stale position feedback does not trigger a
-following error. Altering the HAL configuration so that during transient
-packet loss the pid and motion feedback value is equal to the command value,
-instead of the stale feedback value, appears to improve tuning. This can be
-accomplished with a
+However, not all hm2 special functions know how to properly recover from lost packets.
+For instance, the encoder special function does not properly manage the index feature when packets are lost.
+The author believes that this can lead to rare failures in home-to-index, which can have severe consequences.
+
+On the other hand, pid-stepper systems will run properly for extended periods of time with packet loss on the order of .01%,
+as long as following error is increased enough that having stale position feedback does not trigger a following error.
+Altering the HAL configuration so that during transient packet loss the pid and motion feedback value is equal to the command value,
+instead of the stale feedback value, appears to improve tuning. This can be accomplished with a
.B mux2(9)
component for each feedback signal, using
.B packet\-error
@@ -125,17 +109,14 @@ creates additional pins:
.TP
(bit, out) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-error
-This pin is TRUE when the most recent cycle detected a read or write error,
-and FALSE at other times.
+This pin is TRUE when the most recent cycle detected a read or write error, and FALSE at other times.
.TP
(s32, out) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-error\-level
-This pin shows the current error level, with higher numbers indicating
-a greater number of recent detected errors. The error level is always in
-the range from 0 to packet\-error\-limit, inclusive.
+This pin shows the current error level, with higher numbers indicating a greater number of recent detected errors.
+The error level is always in the range from 0 to packet\-error\-limit, inclusive.
.TP
(bit, out) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-error\-exceeded
-This pin is TRUE when the current error level is equal to the maximum,
-and FALSE at other times.
+This pin is TRUE when the current error level is equal to the maximum, and FALSE at other times.
.SH PARAMETERS
In addition to the parameters documented in
@@ -144,65 +125,57 @@ creates additional parameters:
.TP
(s32, rw) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-error\-decrement
-The amount deducted from \fIpacket\-error\-level\fR in a cycle without
-detected read or write errors, without going below zero.
+The amount deducted from \fIpacket\-error\-level\fR in a cycle without detected read or write errors, without going below zero.
.TP
(s32, rw) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-error\-increment
-The amount added to \fIpacket\-error\-level\fR in a cycle without
-detected read or write errors, without going above packet\-error\-limit.
+The amount added to \fIpacket\-error\-level\fR in a cycle without detected read or write errors, without going above packet\-error\-limit.
.TP
(s32, rw) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-error\-limit
-The level at which a detected read or write error is treated as a permanent
-error. When this error level is reached, the board's \fIio\-error\fR pin
-becomes TRUE and the condition must be manually reset.
+The level at which a detected read or write error is treated as a permanent error.
+When this error level is reached, the board's \fIio\-error\fR pin becomes TRUE and the condition must be manually reset.
.TP
(s32, rw) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.packet\-read\-timeout
The length of time that must pass before a read request times out.
-If the value is less than or equal to 0, it is interpreted as 80% of the thread
-period. If the value is less than 100, it is interpreted as a percentage of
-the thread period. Otherwise, it is interpreted as a time in nanoseconds. In
-any case, the timeout is never less than 100 microseconds.
+If the value is less than or equal to 0, it is interpreted as 80% of the thread period.
+If the value is less than 100, it is interpreted as a percentage of the thread period.
+Otherwise, it is interpreted as a time in nanoseconds.
+In any case, the timeout is never less than 100 microseconds.
-Setting this value too low can cause spurious read errors. Setting it too
-high can cause realtime delay errors.
+Setting this value too low can cause spurious read errors.
+Setting it too high can cause realtime delay errors.
.SH NOTES
-hm2_eth uses an iptables chain called "hm2\-eth\-rules\-output" to control access
-to the network interface while HAL is running. The chain is created if it does
-not exist, and a jump to it is inserted at the beginning of the OUTPUT chain if
-it is not there already. If you have an existing iptables setup, you can insert
-a direct jump from OUTPUT to hm2\-eth\-rules\-output in an order appropriate to
-your local network.
-
-At (normal) exit, hm2_eth will remove the rules. After a crash, you can
-manually clear the rules with \fBsudo iptables \-F hm2\-eth\-rules\-output\fR;
-the rules are also removed by a reboot.
-
-"hardware\-irq\-coalesce\-rx\-usecs" decreases time waiting to receive a packet
-on most systems, but on at least some Marvel-chipset NICs it is harmful.
-If the line does not improve system performance, then remove it. A reboot
-is required for the value to be set back to its power-on default. This
-requires the ethtool package to be installed.
+hm2_eth uses an iptables chain called "hm2\-eth\-rules\-output.
+That technology is common to control network access to (INPUT chain), through (FORWARD chain) or from (OUTPUT chain) your computer.
+Someone who has configured a firewall on Linux has encountered iptables and is familiar with that technology.
+This chain contains addtional rules to control network interface while HAL is running.
+The chain is created if it does not exist, and a jump to it is inserted at the beginning of the OUTPUT chain if it is not there already.
+If you have an existing iptables setup, you can insert a direct jump from OUTPUT to hm2\-eth\-rules\-output in an order appropriate to your local network.
+
+At (normal) exit, hm2_eth will remove the rules.
+After a crash, you can manually clear the rules with \fBsudo iptables \-F hm2\-eth\-rules\-output\fR; the rules are also removed by a reboot.
+
+"hardware\-irq\-coalesce\-rx\-usecs" decreases time waiting to receive a packet on most systems, but on at least some Marvel-chipset NICs it is harmful.
+If the line does not improve system performance, then remove it.
+A reboot is required for the value to be set back to its power-on default.
+This requires the ethtool package to be installed.
.SH BUGS
-Some hostmot2 functions such uart are coded in a way that causes additional
-latency when used with hm2_eth.
+Some hostmot2 functions such uart are coded in a way that causes additional latency when used with hm2_eth.
-On the 7i92, the HAL pins for the LEDs are called CR01..CR04, but the
-silkscreens are CR3..CR6. Depending on the FPGA firmware, the LEDs may
-initially be under control of the ethernet engine. This can be changed until
-power cycle with
+On the 7i92, the HAL pins for the LEDs are called CR01..CR04, but the silkscreens are CR3..CR6.
+Depending on the FPGA firmware, the LEDs may initially be under control of the ethernet engine.
+This can be changed until power cycle with
.EX
elbpcom 01D914000000
.EE
-Depending on firmware version, this driver may cause the hardware error
-LED to light even though the driver and hardware are functioning normally.
+Depending on firmware version, this driver may cause the hardware error LED to light even though the driver and hardware are functioning normally.
This will reportedly be fixed in future bitfile updates from Mesa.
.SH SEE ALSO
diff --git a/docs/man/man9/hostmot2.9 b/docs/man/man9/hostmot2.9
index c280c68cf3..48cb1e59ef 100644
--- a/docs/man/man9/hostmot2.9
+++ b/docs/man/man9/hostmot2.9
@@ -3,8 +3,8 @@
.SH NAME
hostmot2 \- LinuxCNC HAL driver for the Mesa Electronics HostMot2 firmware.
.SH SYNOPSIS
-See the config modparam section below for Mesa card configuration. Typically
-hostmot2 is loaded with no parameters unless debugging is required.
+See the config modparam section below for Mesa card configuration.
+Typically hostmot2 is loaded with no parameters unless debugging is required.
.HP
.B loadrt hostmot2 [debug_idrom=\fIN\fB] [debug_module_descriptors=\fIN\fB] [debug_pin_descriptors=\fIN\fB] [debug_modules=\fIN\fB]
.TP
@@ -21,79 +21,60 @@ Developer/debug use only! Enables debug logging of the HostMot2 Pin Descriptors
Developer/debug use only! Enables debug logging of the HostMot2 Modules used.
.TP
\fBuse_serial_numbers\fR [default: 0]
-When creating HAL pins for smart-serial devices name the pins by the board serial
-number rather than which board and port they are connected to.
-With this option set to 1 pins will have names like \fBhm2_8i20.1234.current\fR rather than
-\fBhm2_5i23.0.8i20.0.1.current\fR. The identifier consists of the last 4 digits of the board
-serial number, which is normally on a sticker on the board.
-This will make configs less portable, but does mean that boards can be re-connected less
-carefully.
+When creating HAL pins for smart-serial devices name the pins by the board serial number
+rather than which board and port they are connected to.
+With this option set to 1 pins will have names like \fBhm2_8i20.1234.current\fR rather than \fBhm2_5i23.0.8i20.0.1.current\fR.
+The identifier consists of the last 4 digits of the board serial number, which is normally on a sticker on the board.
+This will make configs less portable, but does mean that boards can be re-connected less carefully.
.SH DESCRIPTION
-hostmot2 is a device driver that interfaces the Mesa HostMot2 firmware
-to the LinuxCNC HAL. This driver by itself does nothing, the boards
-that actually run the firmware require their own drivers before anything
-can happen. Currently drivers are available for PCI, Ethernet, SPI
-and EPP interfaced cards.
-
-The HostMot2 firmware provides modules such as encoders, PWM generators,
-step/dir generators, and general purpose I/O pins (GPIOs). These things are
-called "Modules". The firmware is configured, at firmware compile time,
-to provide zero or more instances of each of these Modules.
+hostmot2 is a device driver that interfaces the Mesa HostMot2 firmware to the LinuxCNC HAL.
+This driver by itself does nothing, the boards that actually run the firmware require their own drivers before anything can happen.
+Currently drivers are available for PCI, Ethernet, SPI and EPP interfaced cards.
+
+The HostMot2 firmware provides modules such as encoders, PWM generators, step/dir generators, and general purpose I/O pins (GPIOs).
+These things are called "Modules".
+The firmware is configured, at firmware compile time, to provide zero or more instances of each of these Modules.
+
.SS Board I/O Pins
+The HostMot2 firmware runs on an FPGA board.
+The board interfaces with the computer via PCI, Ethernet, SPI, or EPP, and interfaces with motion control hardware,
+such as servos and stepper motors via I/O pins on the board.
-The HostMot2 firmware runs on an FPGA board. The board interfaces with
-the computer via PCI, Ethernet, SPI, or EPP, and interfaces with motion
-control hardware such as servos and stepper motors via I/O pins on
-the board.
-
-Each I/O pin can be configured, at board-driver load time, to serve
-one of two purposes: either as a particular I/O pin of a particular
-Module instance (encoder, pwmgen, stepgen etc), or as a general purpose
-digital I/O pin. By default all Module instances are enabled, and all the
-board's pins are used by the Module instances.
-
-The user can disable Module instances at board-driver load time, by
-specifying a hostmot2 config string modparam. Any pins which belong to
-Module instances that have been disabled automatically become GPIOs.
-
-All IO pins have some HAL presence, whether they belong to an active
-module instance or are full GPIOs. GPIOs can be changed (at run-time)
-between inputs, normal outputs, and open drains, and have a flexible
-HAL interface. IO pins that belong to active Module instances are
-constrained by the requirements of the owning Module, and have a more
-limited interface in HAL. This is described in the General Purpose
-I/O section below.
-.SS config modparam
+Each I/O pin can be configured, at board-driver load time, to serve one of two purposes:
+either as a particular I/O pin of a particular Module instance (encoder, pwmgen, stepgen etc),
+Either as a particular I/O pin of a particular Module instance (encoder, pwmgen, stepgen etc), or as a general purpose digital I/O pin.
+By default all Module instances are enabled, and all the board's pins are used by the Module instances.
-All the board-driver modules (hm2_pci, hm2_eth etc) accept a load-time
-modparam of type string array, named "config". This array has one config
-string for each board the driver should use. Each board's config string
-is passed to and parsed by the hostmot2 driver when the board-driver
-registers the board.
+The user can disable Module instances at board-driver load time, by specifying a hostmot2 config string modparam.
+Any pins which belong to Module instances that have been disabled automatically become GPIOs.
+
+All IO pins have some HAL presence, whether they belong to an active module instance or are full GPIOs.
+GPIOs can be changed (at run-time) between inputs, normal outputs, and open drains, and have a flexible HAL interface.
+IO pins that belong to active Module instances are constrained by the requirements of the owning Module, and have a more limited interface in HAL.
+This is described in the General Purpose I/O section below.
+
+.SS config modparam
+All the board-driver modules (hm2_pci, hm2_eth etc) accept a load-time modparam of type string array, named "config".
+This array has one config string for each board the driver should use.
+Each board's config string is passed to and parsed by the hostmot2 driver when the board-driver registers the board.
-The config string can contain spaces, so it is usually a good idea to
-wrap the whole thing in double-quotes (the " character).
+The config string can contain spaces, so it is usually a good idea to wrap the whole thing in double-quotes (the " character).
-The comma character (,) separates members of the config array from
-each other.
+The comma character (,) separates members of the config array from each other.
-For example, if your control computer has one 5I20 and one 5I23 you
-might load the hm2_pci driver with a HAL command (in halcmd) something
-like this:
+For example, if your control computer has one 5I20 and one 5I23 you might load the hm2_pci driver with a HAL command (in halcmd) something like this:
.nf
.B
loadrt hm2_pci config="firmware=hm2/5i20/SVST8_4.BIT num_encoders=3 num_pwmgens=3 num_stepgens=3,firmware=hm2/5i23/SVSS8_8.BIT sserial_port_0=0000 num_encoders=4"
.fi
-Note: this assumes that the hm2_pci driver detects the 5I20 first and
-the 5I23 second. If the detection order does not match the order
-of the config strings, the hostmot2 driver will refuse to load the
-firmware and the board-driver (hm2_pci etc) will fail to load.
-To the best of my knowledge, there is no way to predict the order in
-which PCI boards will be detected by the driver, but the detection
-order will be consistent as long as PCI boards are not moved around.
+Note: this assumes that the hm2_pci driver detects the 5I20 first and the 5I23 second.
+If the detection order does not match the order of the config strings,
+the hostmot2 driver will refuse to load the firmware and the board-driver (hm2_pci etc) will fail to load.
+To the best of my knowledge, there is no way to predict the order in which PCI boards will be detected by the driver,
+but the detection order will be consistent as long as PCI boards are not moved around.
Best to try loading it and see what the detection order is.
The valid entries in the format string are:
@@ -124,186 +105,154 @@ The valid entries in the format string are:
.TP
\fBfirmware\fR [optional]
-Load the firmware specified by F into the FPGA on this board. If no
-"\fBfirmware=\fIF\fR" string is specified, the FPGA will not be
-re-programmed but may continue to run a previously downloaded firmware.
-
-The requested firmware F is fetched by udev. udev searches for the
-firmware in the system's firmware search path, usually /lib/firmware.
-F typically has the form "hm2/<BoardType>/file.bit"; a typical value
-for F might be "hm2/5i20/SVST8_4.BIT". The hostmot2 firmware files are
-supplied by the hostmot2\-firmware packages, available from linuxcnc.org and can
-normally be installed by entering the command "sudo apt\-get install
-hostmot2\-firmware\-5i23" to install the support files for the 5I23 for example.
-
-Newer FPGA cards come pre-programmed with firmware and no "firmware=" string
-should be used with these cards. To change the firmware on these cards the
-"mesaflash" utility should be used. It is perfectly
-valid and reasonable to load these cards with no config string at all.
+Load the firmware specified by F into the FPGA on this board.
+If no "\fBfirmware=\fIF\fR" string is specified, the FPGA will not be re-programmed but may continue to run a previously downloaded firmware.
+
+The requested firmware F is fetched by udev, which searches for the firmware in the system's firmware search path, usually /lib/firmware.
+F typically has the form "hm2/<BoardType>/file.bit"; a typical value for F might be "hm2/5i20/SVST8_4.BIT".
+The hostmot2 firmware files are supplied by the hostmot2\-firmware packages, available from linuxcnc.org
+and can normally be installed by entering the command "sudo apt\-get install hostmot2\-firmware\-5i23" to install the support files for the 5I23 for example.
+
+Newer FPGA cards come pre-programmed with firmware and no "firmware=" string should be used with these cards.
+To change the firmware on these cards the "mesaflash" utility should be used.
+It is perfectly valid and reasonable to load these cards with no config string at all.
.TP
\fBnum_dplls\fR [optional, default: \-1]
-The hm2dpll is a phase-locked loop timer module which may be used to reduce
-sample and write time jitter for some hm2 modules. This parameter can be used to
-disable the hm2dpll by setting the number to 0. There is only ever one module of this type,
-with 4 timer channels, so the other valid numbers are \-1 (enable all) and 1, both of
-which end up meaning the same thing.
+The hm2dpll is a phase-locked loop timer module which may be used to reduce sample and write time jitter for some hm2 modules.
+This parameter can be used to disable the hm2dpll by setting the number to 0.
+There is only ever one module of this type, with 4 timer channels, so the other valid numbers are \-1 (enable all) and 1, both of which end up meaning the same thing.
.TP
\fBnum_encoders\fR [optional, default: \-1]
Only enable the first N encoders. If N is \-1, all encoders are enabled.
-If N is 0, no encoders are enabled. If N is greater than the number of
-encoders available in the firmware, the board will fail to register.
+If N is 0, no encoders are enabled.
+If N is greater than the number of encoders available in the firmware, the board will fail to register.
.TP
\fBssi_chan_N\fR [optional, default: ""]
-Specifies how the bit stream from a Synchronous Serial Interface device will be
-interpreted. There should be an entry for each device connected. Only channels
-with a format specifier will be enabled. (as the software can not guess data
-rates and bit lengths)
+Specifies how the bit stream from a Synchronous Serial Interface device will be interpreted.
+There should be an entry for each device connected.
+Only channels with a format specifier will be enabled (as the software can not guess data rates and bit lengths).
.TP
\fBbiss_chan_N\fR [optional, default: ""]
-As for ssi_chan_N, but for BiSS devices
+As for ssi_chan_N, but for BiSS devices.
.TP
\fBfanuc_chan_N\fR [optional, default: ""]
-Specifies how the bit stream from a Fanuc absolute encoder will be
-interpreted. There should be an entry for each device connected. Only channels
-with a format specifier will be enabled. (as the software can not guess data
-rates and bit lengths)
+Specifies how the bit stream from a Fanuc absolute encoder will be interpreted.
+There should be an entry for each device connected.
+Only channels with a format specifier will be enabled (as the software can not guess data rates and bit lengths).
.TP
\fBnum_resolvers\fR [optional, default: \-1]
Only enable the first N resolvers. If N = \-1 then all resolvers are enabled.
-This module does not work with generic resolvers (unlike the encoder module
-which works with any encoder). At the time of writing this Hostmot2 Resolver
-function only works with the Mesa 7I49 card.
+This module does not work with generic resolvers (unlike the encoder module which works with any encoder).
+At the time of writing this Hostmot2 Resolver function only works with the Mesa 7I49 card.
.TP
\fBnum_pwmgens\fR [optional, default: \-1]
Only enable the first N pwmgens. If N is \-1, all pwmgens are enabled.
-If N is 0, no pwmgens are enabled. If N is greater than the number of
-pwmgens available in the firmware, the board will fail to register.
+If N is 0, no pwmgens are enabled.
+If N is greater than the number of pwmgens available in the firmware, the board will fail to register.
.TP
\fBnum_3pwmgens\fR [optional, default: \-1]
-Only enable the first N Three-phase pwmgens. If N is \-1, all 3pwmgens
-are enabled. If N is 0, no pwmgens are enabled. If N is greater than the
-number of pwmgens available in the firmware, the board will fail to register.
+Only enable the first N Three-phase pwmgens.
+If N is \-1, all 3pwmgens are enabled. If N is 0, no pwmgens are enabled.
+If N is greater than the number of pwmgens available in the firmware, the board will fail to register.
.TP
\fBnum_rcpwmgens\fR [optional, default: \-1]
-Only enable the first N RC pwmgens. If N is \-1, all rcpwmgens
-are enabled. If N is 0, no rcpwmgens are enabled. If N is greater than the
-number of rcpwmgens available in the firmware, the board will fail to register.
+Only enable the first N RC pwmgens.
+If N is \-1, all rcpwmgens are enabled. If N is 0, no rcpwmgens are enabled.
+If N is greater than the number of rcpwmgens available in the firmware, the board will fail to register.
.TP
\fBnum_stepgens\fR [optional, default: \-1]
-Only enable the first N stepgens. If N is \-1, all stepgens are enabled.
-If N is 0, no stepgens are enabled. If N is greater than the number of
-stepgens available in the firmware, the board will fail to register.
+Only enable the first N stepgens. If N is \-1, all stepgens are enabled. If N is 0, no stepgens are enabled.
+If N is greater than the number of stepgens available in the firmware, the board will fail to register.
.TP
\fBnum_xy2mods\fR [optional, default: \-1]
-Only enable the first N xy2mods. If N is \-1, all xy2mods are enabled.
-If N is 0, no xy2mods are enabled. If N is greater than the number of
-xy2mods available in the firmware, the board will fail to register.
+Only enable the first N xy2mods. If N is \-1, all xy2mods are enabled. If N is 0, no xy2mods are enabled.
+If N is greater than the number of xy2mods available in the firmware, the board will fail to register.
.TP
.TP
\fBstepgen_width\fR [optional, default: 2]
-Used to mask extra, unwanted, stepgen pins. Stepper drives typically require
-only two pins (step and dir) but the Hostmot2 stepgen can drive up to 8 output
-pins for specialised applications (depending on firmware). This parameter
-applies to all stepgen instances. Unused, masked pins will be available as GPIO.
+Used to mask extra, unwanted, stepgen pins.
+Stepper drives typically require only two pins (step and dir) but the Hostmot2 stepgen can drive up to 8 output pins for specialised applications (depending on firmware).
+This parameter applies to all stepgen instances. Unused, masked pins will be available as GPIO.
.TP
\fBsserial_port_\fIN\fR (\fIN\fR = 0 .. 3)\fR [optional, default: 00000000 for all ports]
-Up to 32 Smart Serial devices can be connected to a Mesa Anything IO board
-depending on the firmware used and the number of physical connections on the
-board. These are arranged in 1-4 ports (N) of 1 to 8 channels.
- Some Smart Serial (SSLBP) cards offer more than one load-time configuration,
-for example all inputs, or all outputs, or offering additional analogue input on
-some digital pins.
- To set the modes for port 0 use for example \fBsserial_port_0=0120xxxx\fR.
- A "0" in the string sets the corresponding channel to mode 0, a "1" to mode 1, and so
-on up to mode 9. An "x" in any position disables that channel and makes the
-corresponding FPGA pins available as GPIO.
- The string can be up to 8 characters long, and if it defines more
-modes than there are channels on the port then the extras are ignored. Channel
-numbering is left to right so the example above would set sserial device 0.0
-to mode 0, 0.1 to mode 1, 0.2 to mode 2, 0.3 to mode 0 and disables channels 0.4 onwards.
- The sserial driver will auto-detect connected devices, no further configuration
-should be needed. Unconnected channels will default to GPIO, but the pin values
-will vary semi-randomly during boot when card-detection runs, to it is best to
-actively disable any channel that is to be used for GPIO.
+Up to 32 Smart Serial devices can be connected to a Mesa Anything IO board,
+depending on the firmware used and the number of physical connections on the board.
+These are arranged in 1-4 ports (N) of 1 to 8 channels.
+Some Smart Serial (SSLBP) cards offer more than one load-time configuration,
+for example all inputs, or all outputs, or offering additional analogue input on some digital pins.
+To set the modes for port 0 use for example \fBsserial_port_0=0120xxxx\fR.
+A "0" in the string sets the corresponding channel to mode 0, a "1" to mode 1, and so on up to mode 9.
+An "x" in any position disables that channel and makes the corresponding FPGA pins available as GPIO.
+The string can be up to 8 characters long, and if it defines more modes than there are channels on the port then the extras are ignored.
+Channel numbering is left to right so the example above would set sserial device 0.0 to mode 0, 0.1 to mode 1, 0.2 to mode 2, 0.3 to mode 0 and disables channels 0.4 onwards.
+The sserial driver will auto-detect connected devices, no further configuration should be needed.
+Unconnected channels will default to GPIO, but the pin values will vary semi-randomly during boot when card-detection runs,
+to it is best to actively disable any channel that is to be used for GPIO.
See SSERIAL(9) for more information.
.TP
\fBnum_bspis\fR [optional, default: \-1]
-Only enable the first N Buffered SPI drivers. If N is \-1 then all the drivers
-are enabled. Each BSPI driver can address 16 devices.
+Only enable the first N Buffered SPI drivers. If N is \-1 then all the drivers are enabled.
+Each BSPI driver can address 16 devices.
.TP
\fBnum_leds\fR [optional, default: \-1]
-Only enable the first N of the LEDs on the FPGA board. If N is \-1, then HAL
-pins for all the LEDs will be created. If N=0 then no pins will be added.
+Only enable the first N of the LEDs on the FPGA board. If N is \-1, then HAL pins for all the LEDs will be created.
+If N=0 then no pins will be added.
.TP
\fBnum_ssrs\fR [optional, default: -1]
-Only enable the first N of the SSR modules on the FPGA board. If N is
-\-1, then HAL pins for all the SSR outputs will be created. If N=0 then
-no pins will be added.
+Only enable the first N of the SSR modules on the FPGA board.
+If N is \-1, then HAL pins for all the SSR outputs will be created.
+If N=0 then no pins will be added.
.TP
\fBenable_raw\fR [optional]
-If specified, this turns on a raw access mode, whereby a user can peek and
-poke the firmware from HAL. See Raw Mode below.
+If specified, this turns on a raw access mode, whereby a user can peek and poke the firmware from HAL. See Raw Mode below.
.SS dpll
The hm2dpll module has pins like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll\fR"
-It is likely that the pin-count will decrease in the future and that some pins
-will become parameters.
-This module is a phase-locked loop that will synchronise itself with the thread
-in which the hostmot2 "read" function is installed and will trigger other
-functions that are allocated to it at a specified time before or after the
-"read" function runs. This can be applied to the three absolute
-encoder types, quadrature encoder, stepgen, and xy2mod. In the case of the absolute
-encoders this allows the system to trigger a data transmission just prior to
-the time when the HAL driver reads the data. In the case of stepgens,
-quadrature encoders, and the xy2mod, the timers can be used to reduce position sampling
-jitter. This is especially valuable with the ethernet-interfaced cards.
+It is likely that the pin-count will decrease in the future and that some pins will become parameters.
+This module is a phase-locked loop that will synchronise itself with the thread in which the hostmot2 "read" function is installed
+and will trigger other functions that are allocated to it at a specified time before or after the "read" function runs.
+This can be applied to the three absolute encoder types, quadrature encoder, stepgen, and xy2mod.
+In the case of the absolute encoders this allows the system to trigger a data transmission just prior to the time when the HAL driver reads the data.
+In the case of stepgens, quadrature encoders, and the xy2mod, the timers can be used to reduce position sampling jitter.
+This is especially valuable with the ethernet-interfaced cards.
Pins:
.TP
(float, in) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll.NN.timer\-us
-This pin sets the triggering offset of the associated timer. There are 4 timers
-numbered 01 to 04, represented by the NN digits in the pin name. The units are
-microseconds (µs). Generally the value for reads will be negative, and positive for
-writes so that input data is sampled prior to the main hostmot read and output data
-is written some time after the main hostmot2 read.
-.
+This pin sets the triggering offset of the associated timer.
+There are 4 timers numbered 01 to 04, represented by the NN digits in the pin name.
+The units are microseconds (µs).
+Generally the value for reads will be negative, and positive for writes,
+so that input data is sampled prior to the main hostmot read and output data is written some time after the main hostmot2 read.
-For stepgen and quadrature encoders, the value needs to be more than the
-maximum variation between read times. \-100 will suffice for most systems, and
-\-50 will work on systems with good performance and latency.
+For stepgen and quadrature encoders, the value needs to be more than the maximum variation between read times.
+\-100 will suffice for most systems, and \-50 will work on systems with good performance and latency.
-For serial encoders, the value also needs to include the time it takes to
-transfer the absolute encoder position. For instance, if 50 bits must be read
-at 500 kHz then subtract an additional 50/500 kHz = 100 µs to get a starting value
-of \-200.
+For serial encoders, the value also needs to include the time it takes to transfer the absolute encoder position.
+For instance, if 50 bits must be read at 500 kHz then subtract an additional 50/500 kHz = 100 µs to get a starting value of \-200.
-The xy2mod uses 2 DPLL timers, one for read and one for write. The read timer value
-can be the same as used by the stepgen and quadrature encoders so the same timer channel
-can be shared. The write timer is typically set to a time after the main hostmot2 write
-this may take some experimentation.
+The xy2mod uses 2 DPLL timers, one for read and one for write.
+The read timer value can be the same as used by the stepgen and quadrature encoders so the same timer channel can be shared.
+The write timer is typically set to a time after the main hostmot2 write this may take some experimentation.
.TP
(float, in) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll.base\-freq\-khz
-This pin sets the base frequency of the phase-locked loop. by default it will
-be set to the nominal frequency of the thread in which the PLL is running and
-will not normally need to be changed.
+This pin sets the base frequency of the phase-locked loop.
+By default it will be set to the nominal frequency of the thread in which the PLL is running and will not normally need to be changed.
.TP
(float, out) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll.phase\-error\-us
-Indicates the phase error of the DPLL. If the number cycles by a large amount
-it is likely that the PLL has failed to achieve lock and adjustments will need
-to be made.
+Indicates the phase error of the DPLL.
+If the number cycles by a large amount it is likely that the PLL has failed to achieve lock and adjustments will need to be made.
.TP
(u32, in) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll.time\-const
-The filter time-constant for the PLL. The default value is a compromise
-between insensitivity to single-cycle variations and being resilient to changes
-to the Linux CLOCK_MONOTONIC timescale, which can instantly change by up to
-±500ppm from its nominal value, usually by timekeeping software like ntpd and
-ntpdate. Default 2000 (0x7d0)
+The filter time-constant for the PLL.
+The default value is a compromise between insensitivity to single-cycle variations and being resilient to changes to the Linux CLOCK_MONOTONIC timescale,
+which can instantly change by up to ±500ppm from its nominal value, usually by timekeeping software like ntpd and ntpdate. Default 2000 (0x7d0).
.TP
(u32, in) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll.plimit
-Sets the phase adjustment limit of the PLL. If the value is zero then the PLL
-will free-run at the base frequency independent of the servo thread rate. This
-is probably not what you want. Default 4194304 (0x400000) Units not known...
+Sets the phase adjustment limit of the PLL.
+If the value is zero then the PLL will free-run at the base frequency independent of the servo thread rate.
+This is probably not what you want. Default 4194304 (0x400000) Units not known...
.TP
(u32, out) hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.dpll.ddsize
Used internally by the driver, likely to disappear.
@@ -312,26 +261,23 @@ Used internally by the driver, likely to disappear.
Prescale factor for the rate generator. Default 1.
-.SS encoder
+.SS Encoder
Encoders have names like
""hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.encoder.\fI<Instance>\fR".".
-"Instance" is a two-digit number that corresponds to the HostMot2 encoder
-instance number. There are "num_encoders" instances, starting with 00.
+"Instance" is a two-digit number that corresponds to the HostMot2 encoder instance number.
+There are "num_encoders" instances, starting with 00.
-So, for example, the HAL pin that has the current position of the second
-encoder of the first 5I25 board is: hm2_5i25.0.encoder.01.position (this
-assumes that the firmware in that board is configured so that this HAL
-object is available)
+So, for example, the HAL pin that has the current position of the second encoder of the first 5I25 board is:
+hm2_5i25.0.encoder.01.position (this assumes that the firmware in that board is configured so that this HAL object is available).
-Each encoder uses three or four input IO pins, depending on how the
-firmware was compiled. Three-pin encoders use A, B, and Index (sometimes
-also known as Z). Four-pin encoders use A, B, Index, and Index-mask.
+Each encoder uses three or four input IO pins, depending on how the firmware was compiled.
+Three-pin encoders use A, B, and Index (sometimes also known as Z).
+Four-pin encoders use A, B, Index, and Index-mask.
-The hm2 encoder representation is similar to the one described by the
-Canonical Device Interface (in the HAL General Reference document),
-and to the software encoder component. Each encoder instance has the
-following pins and parameters:
+The hm2 encoder representation is similar to the one described by the Canonical Device Interface (in the HAL General Reference document),
+and to the software encoder component.
+Each encoder instance has the following pins and parameters:
Pins:
@@ -349,45 +295,35 @@ Encoder latched position in position units (count / scale).
.TP
(float out) velocity
-Estimated encoder velocity in position units
-per second.
+Estimated encoder velocity in position units per second.
.TP
(float out) velocity-rpm
-Estimated encoder velocity in position units
-per minute.
+Estimated encoder velocity in position units per minute.
.TP
(bit in) reset
-When this pin is True, the count and position pins are
-set to 0. (The value of the velocity pin is not affected by this.)
-The driver does not reset this pin to FALSE after resetting the count
-to 0, that is the user's job.
+When this pin is True, the count and position pins are set to 0 (the value of the velocity pin is not affected by this).
+The driver does not reset this pin to FALSE after resetting the count to 0, that is the user's job.
.TP
(bit in/out) index\-enable
-When this pin is set to True, the count
-(and therefore also position) are reset to zero on the next Index
-(Phase\-Z) pulse. At the same time, index\-enable is reset to zero to
-indicate that the pulse has occurred.
+When this pin is set to True, the count (and therefore also position) are reset to zero on the next Index (Phase\-Z) pulse.
+At the same time, index\-enable is reset to zero to indicate that the pulse has occurred.
.TP
(bit in/out) probe\-enable
-When this pin is set to True, the encoder count
-(and therefore also position) are latched on the the next probe
-active edge. At the same time, probe\-enable is reset to zero to
-indicate that latch event has occurred.
+When this pin is set to True, the encoder count (and therefore also position) are latched on the the next probe active edge.
+At the same time, probe\-enable is reset to zero to indicate that latch event has occurred.
.TP
(bit r/w) probe\-invert
-If set to True, the rising edge of the probe
-input pin triggers the latch event (if probe\-enable is True). If set
-to False, the falling edge triggers.
+If set to True, the rising edge of the probe input pin triggers the latch event (if probe\-enable is True).
+If set to False, the falling edge triggers.
.TP
(s32 out) rawcounts
-Total number of encoder counts since the start,
-not adjusted for index or reset.
+Total number of encoder counts since the start, not adjusted for index or reset.
.TP
(bit out) input-a, input-b, input-index
@@ -405,27 +341,23 @@ It can only be set if the corresponding quad-error-enable bit is True.
.TP
(u32 in) hm2_XXXX.N.encoder.sample-frequency
-This is the sample frequency that determines all standard encoder
-channels digital filter time constant (see filter parameter).
+This is the sample frequency that determines all standard encoder channels digital filter time constant (see filter parameter).
.TP
(u32 in) hm2_XXXX.N.encoder.muxed-sample-frequency
-This is the sample frequency that determines all muxed encoder
-channels digital filter time constant (see filter parameter).
+This is the sample frequency that determines all muxed encoder channels digital filter time constant (see filter parameter).
This also sets the encoder multiplexing frequency.
.TP
(float in) hm2_XXXX.N.encoder.muxed-skew
This sets the muxed encoder sample time delay (in ns) from the multiplex signal.
-Setting this properly can increase the usable multiplex frequency and compensate
-for cable delays (suggested value is 3* cable length in feet +20).
+Setting this properly can increase the usable multiplex frequency and compensate for cable delays (suggested value is 3* cable length in feet +20).
.TP
(bit in) hm2_XXXX.N.encoder.hires-timestamp
-When this pin is True the encoder timestamp counter frequency is ~10 MHz
-when False the timestamp counter frequency is ~2 MHz. This should be set True
-for frequency counting applications to improve the resolution. It should be
-set False when servo thread periods longer than 1 ms are used.
+When this pin is True the encoder timestamp counter frequency is ~10 MHz when False the timestamp counter frequency is ~2 MHz.
+This should be set True for frequency counting applications to improve the resolution.
+It should be set False when servo thread periods longer than 1 ms are used.
Parameters:
@@ -435,91 +367,72 @@ Converts from "count" units to "position" units.
.TP
(bit r/w) index\-invert
-If set to True, the rising edge of the Index
-input pin triggers the Index event (if index\-enable is True). If set
-to False, the falling edge triggers.
+If set to True, the rising edge of the Index input pin triggers the Index event (if index\-enable is True).
+If set to False, the falling edge triggers.
.TP
(bit r/w) index\-mask
-If set to True, the Index input pin only has an
-effect if the Index\-Mask input pin is True (or False, depending on the
-index\-mask\-invert pin below).
+If set to True, the Index input pin only has an effect if the Index\-Mask input pin is True (or False, depending on the index\-mask\-invert pin below).
.TP
(bit r/w) index\-mask\-invert
-If set to True, Index\-Mask must be False
-for Index to have an effect. If set to False, the Index\-Mask pin must
-be True.
+If set to True, Index\-Mask must be False for Index to have an effect.
+If set to False, the Index\-Mask pin must be True.
.TP
(bit r/w) counter\-mode
Set to False (the default) for Quadrature.
-Set to True for Step/Dir (in which case Step is on the A pin and Dir is
-on the B pin).
+Set to True for Step/Dir (in which case Step is on the A pin and Dir is on the B pin).
.TP
(bit r/w) filter
-If set to True (the default), the quadrature counter
-needs 15 sample clocks to register a change on any of the three input lines
-(any pulse shorter than this is rejected as noise). If set to False, the
-quadrature counter needs only 3 clocks to register a change. The default encoder
-sample clock runs at approximately 25 to 33 MHz but can be changed globally
-with the sample-frequency or muxed-sample-frequency pin.
+If set to True (the default), the quadrature counter needs 15 sample clocks to register a change on any of the three input lines
+(any pulse shorter than this is rejected as noise).
+If set to False, the quadrature counter needs only 3 clocks to register a change.
+The default encoder sample clock runs at approximately 25 to 33 MHz but can be changed globally with the sample-frequency or muxed-sample-frequency pin.
.TP
(float r/w) vel\-timeout
-When the encoder is moving slower than one
-pulse for each time that the driver reads the count from the FPGA (in
-the hm2_read() function), the velocity is harder to estimate. The driver
-can wait several iterations for the next pulse to arrive, all the while
-reporting the upper bound of the encoder velocity, which can be accurately
-guessed. This parameter specifies how long to wait for the next pulse,
-before reporting the encoder stopped. This parameter is in seconds.
+When the encoder is moving slower than one pulse for each time that the driver reads the count from the FPGA (in the hm2_read() function), the velocity is harder to estimate.
+The driver can wait several iterations for the next pulse to arrive, all the while reporting the upper bound of the encoder velocity,
+which can be accurately guessed.
+This parameter specifies how long to wait for the next pulse, before reporting the encoder stopped.
+This parameter is in seconds.
.TP
(s32 r/w) hm2_XXXX.N.encoder.timer\-number (default: \-1)
-Sets the hm2dpll timer instance to be used to latch encoder counts. A setting
-of \-1 does not latch encoder counts. A setting of 0 latches at the same time
-as the main hostmot2 read. A setting of 1..4 uses a time offset from the main
-hostmot2 read according to the dpll's timer\-us setting.
+Sets the hm2dpll timer instance to be used to latch encoder counts.
+A setting of \-1 does not latch encoder counts.
+A setting of 0 latches at the same time as the main hostmot2 read.
+A setting of 1..4 uses a time offset from the main hostmot2 read according to the dpll's timer\-us setting.
-Typically, timer\-us should be a negative number with a magnitude larger than
-the largest latency (e.g., \-100 for a system with mediocre latency, \-50 for a
-system with good latency). A negative number specifies latching the specified
-time before the nominal hostmot2 read time.
+Typically, timer\-us should be a negative number with a magnitude larger than the largest latency
+(e.g., \-100 for a system with mediocre latency, \-50 for a system with good latency).
+A negative number specifies latching the specified time before the nominal hostmot2 read time.
-If no DPLL module is present in the FPGA firmware, or if the encoder module
-does not support DPLL, then this pin is not created.
+If no DPLL module is present in the FPGA firmware, or if the encoder module does not support DPLL, then this pin is not created.
-When available, this feature should typically be enabled. Doing so generally
-reduces following errors.
+When available, this feature should typically be enabled. Doing so generally reduces following errors.
.SS Synchronous Serial Interface (SSI)
(Not to be confused with the Smart Serial Interface)
-One pin is created for each SSI instance regardless of data format:
-(bit, in) hm2_XXXX.NN.ssi.MM.data\-incomplete
-This pin will be set "True" if the module was still transferring data when the
-value was read. When this problem exists there will also be a limited number of
-error messages printed to the UI. This pin should be used to monitor whether
-the problem has been addressed by config changes.
-Solutions to the problem dpend on whether the encoder read is being triggered by
-the hm2dpll phase-locked-loop timer (described above) or by the trigger\-encoders
-function (described below).
-
-The names of the pins created by the SSI module will depend entirely on the
-format string for each channel specified in the loadrt command line.
-A typical format string might be
- \fBssi_chan_0=error%1bposition%24g\fR.
+One pin is created for each SSI instance regardless of data format: (bit, in) hm2_XXXX.NN.ssi.MM.data\-incomplete.
+This pin will be set "True" if the module was still transferring data when the value was read.
+When this problem exists there will also be a limited number of error messages printed to the UI.
+This pin should be used to monitor whether the problem has been addressed by config changes.
+Solutions to the problem dpend on whether the encoder read is being triggered by the hm2dpll phase-locked-loop timer (described above) or by the trigger\-encoders function (described below).
+
+The names of the pins created by the SSI module will depend entirely on the format string for each channel specified in the loadrt command line.
+A typical format string might be \fBssi_chan_0=error%1bposition%24g\fR.
This would interpret the LSB of the bit-stream as a bit-type pin named "error" and the next 24 bits as a Gray-coded encoder counter.
The encoder-related HAL pins would all begin with "position".
There should be no spaces in the format string, as this is used as a delimiter by the low-level code.
-The format consists of a string of alphanumeric characters that will form the
-HAL pin names, followed by a % symbol, a bit-count and a data type. All bits
-in the packet must be defined, even if they are not used.
+The format consists of a string of alphanumeric characters that will form the HAL pin names, followed by a % symbol, a bit-count and a data type.
+All bits in the packet must be defined, even if they are not used.
There is a limit of 64 bits in total.
The valid format characters and the pins they create are:
@@ -527,53 +440,30 @@ The valid format characters and the pins they create are:
p: (Pad). Does not create any pins, used to ignore sections of the bit stream that are not required.
.TP
b: (Boolean).
- (bit, out) hm2_XXXX.N.ssi.MM.<name>. If any bits in the designated field width
-are non-zero then the HAL pin will be "True".
- (bit, out) hm2_XXXX.N.ssi.MM.<name>\-not. An inverted version of the above, the
-HAL pin will be "True" if all bits in the field are zero.
+ (bit, out) hm2_XXXX.N.ssi.MM.<name>. If any bits in the designated field width are non-zero then the HAL pin will be "True".
+ (bit, out) hm2_XXXX.N.ssi.MM.<name>\-not. An inverted version of the above, the HAL pin will be "True" if all bits in the field are zero.
.TP
u: (Unsigned)
- (float, out) hm2_XXXX.N.ssi.MM.<name>. The value of the bits interpreted as an
-unsigned integer then scaled such that the pin value will equal the scalemax
-parameter value when all bits are high. (for example if the field is 8 bits
-wide and the scalmax parameter was 20 then a value of 255 would return 20, and
-0 would return 0.
+ (float, out) hm2_XXXX.N.ssi.MM.<name>. The value of the bits interpreted as an unsigned integer then scaled such that the pin value will equal the scalemax parameter value when all bits are high. (for example if the field is 8 bits wide and the scalmax parameter was 20 then a value of 255 would return 20, and 0 would return 0.
.TP
s: (Signed)
- (float, out) hm2_XXXX.N.ssi.MM.<name>. The value of the bits interpreted as a
-2s complement signed number then scaled similarly to the unsigned variant,
-except symmetrical around zero.
+ (float, out) hm2_XXXX.N.ssi.MM.<name>. The value of the bits interpreted as a 2s complement signed number then scaled similarly to the unsigned variant, except symmetrical around zero.
.TP
f: (bitField)
- (bit, out) hm2_XXXX.N.ssi.MM.<name>\-NN. The value of each individual bit in the
-data field. NN starts at 00 up to the number of bits in the field.
- (bit, out) hm2_XXXX.N.ssi.MM.<name>\-NN\-not. An inverted version of the individual
-bit values.
+ (bit, out) hm2_XXXX.N.ssi.MM.<name>\-NN. The value of each individual bit in the data field. NN starts at 00 up to the number of bits in the field.
+ (bit, out) hm2_XXXX.N.ssi.MM.<name>\-NN\-not. An inverted version of the individual bit values.
.TP
e: (Encoder)
- (s32, out) hm2_XXXX.N.ssi.MM.<name>.count. The lower 32 bits of the
-total encoder counts. This value is reset both by the ...reset and the ...index\-enable
-pins.
- (s32, out) hm2_XXXX.N.ssi.MM.<name>.rawcounts. The lower 32 bits of
-the total encoder counts. The pin is not affected by reset and index.
- (float, out) hm2_XXXX.N.ssi.MM.<name>.position. The encoder position
-in machine units. This is calculated from the full 64-bit buffers so will show
-a True value even after the counts pins have wrapped. It is zeroed by reset and
-index enable.
- (bit, IO) hm2_XXXX.N.ssi.MM.<name>.index\-enable. When this pin is set
-"True" the module will wait until the raw encoder counts next passes through an
-integer multiple of the number of counts specified by counts\-per\-rev parameter
-and then it will zero the counts and position pins, and set the index\-enable
-pin back to "False" as a signal to the system that "index" has been passed.
-this pin is used for spindle-synchronised motion and index-homing.
- (bit, in) (bit, out) hm2_XXXX.N.ssi.MM.<name>.reset. When this pin is set high
-the counts and position pins are zeroed.
+ (s32, out) hm2_XXXX.N.ssi.MM.<name>.count. The lower 32 bits of the total encoder counts. This value is reset both by the ...reset and the ...index\-enable pins.
+ (s32, out) hm2_XXXX.N.ssi.MM.<name>.rawcounts. The lower 32 bits of the total encoder counts. The pin is not affected by reset and index.
+ (float, out) hm2_XXXX.N.ssi.MM.<name>.position. The encoder position in machine units. This is calculated from the full 64-bit buffers so will show a True value even after the counts pins have wrapped. It is zeroed by reset and index enable.
+ (bit, IO) hm2_XXXX.N.ssi.MM.<name>.index\-enable. When this pin is set "True" the module will wait until the raw encoder counts next passes through an integer multiple of the number of counts specified by counts\-per\-rev parameter and then it will zero the counts and position pins, and set the index\-enable pin back to "False" as a signal to the system that "index" has been passed. this pin is used for spindle-synchronised motion and index-homing.
+ (bit, in) (bit, out) hm2_XXXX.N.ssi.MM.<name>.reset. When this pin is set high the counts and position pins are zeroed.
.TP
h: (Split encoder, high-order bits)
-Some encoders (Including Fanuc) place the encoder part-turn counts and full-turn
-counts in separate, non-contiguous fields. This tag defines the high-order bits
-of such an encoder module. There can be only one h and one l tag per channel,
-the behaviour with multiple such channels will be undefined.
+Some encoders (Including Fanuc) place the encoder part-turn counts and full-turn counts in separate, non-contiguous fields.
+This tag defines the high-order bits of such an encoder module.
+There can be only one h and one l tag per channel, the behaviour with multiple such channels will be undefined.
.TP
l: (Split encoder, low-order bits)
Low order bits (see "h")
@@ -583,10 +473,9 @@ This is only valid for encoders (e, h l) and unsigned (u) data types.
.TP
m: (Multi-turn). This is a modifier that indicates that the following
format string is a multi-turn encoder. This is only valid for encoders (e, h l).
-A jump in encoder position of more than half the full scale is interpreted as a
-full turn and the counts are wrapped. With a multi-turn encoder this is only
-likely to be a data glitch and will lead to a permanent offset. This flag
-endures that such encoders will never wrap.
+A jump in encoder position of more than half the full scale is interpreted as a full turn and the counts are wrapped.
+With a multi-turn encoder this is only likely to be a data glitch and will lead to a permanent offset.
+This flag endures that such encoders will never wrap.
.TP
Parameters:
@@ -594,16 +483,13 @@ Two parameters is universally created for all SSI instances
.TP
(float r/w) hm2_XXXX.N.ssi.MM.frequency\-khz
-This parameter sets the SSI clock frequency. The units are kHz, so 500 will give
-a clock frequency of 500,000 Hz.
+This parameter sets the SSI clock frequency. The units are kHz, so 500 will give a clock frequency of 500,000 Hz.
.TP
(s32 r/w) hm2_XXXX.N.ssi.timer-number\-num
This parameter allocates the SSI module to a specific hm2dpll timer instance.
-This pin is only of use in firmwares which contain a hm2dpll function and will
-default to 1 in cases where there is such a function, and 0 if there is not.
-The pin can be used to disable reads of the encoder, by setting to a
-nonexistent timer number, or to 0.
+This pin is only of use in firmwares which contain a hm2dpll function and will default to 1 in cases where there is such a function, and 0 if there is not.
+The pin can be used to disable reads of the encoder, by setting to a nonexistent timer number, or to 0.
Other parameters depend on the data types specified in the config string.
.TP
@@ -612,12 +498,10 @@ p: (Pad) No Parameters.
b: (Boolean) No Parameters.
.TP
u: (Unsigned)
-(float, r/w) hm2_XXXX.N.ssi.MM.<name>-scalemax. The scaling factor for the
- channel.
+(float, r/w) hm2_XXXX.N.ssi.MM.<name>-scalemax. The scaling factor for the channel.
.TP
s: (Signed)
-(float, r/w) hm2_XXXX.N.ssi.MM.<name>-scalemax. The scaling factor for the
-channel.
+(float, r/w) hm2_XXXX.N.ssi.MM.<name>-scalemax. The scaling factor for the channel.
.TP
f: (bitField): No parameters.
.TP
@@ -626,41 +510,29 @@ e: (Encoder):
The encoder scale in counts per machine unit.
(u32, r/w) hm2_XXXX.N.ssi.MM.<name>.counts\-per\-rev (u32, r/w)
Used to emulate the index behaviour of an incremental+index encoder.
-This would normally be set to the actual counts per rev of the encoder,
-but can be any whole number of revs.
+This would normally be set to the actual counts per rev of the encoder, but can be any whole number of revs.
Integer divisors or multipliers of the true PPR might be useful for index-homing.
-Non-integer factors might be appropriate where there is a synchronous drive ratio
-between the encoder and the spindle or ballscrew.
+Non-integer factors might be appropriate where there is a synchronous drive ratio between the encoder and the spindle or ballscrew.
.SS BiSS
-BiSS is a bidirectional variant of SSI. Currently only a single direction is
-supported by LinuxCNC (encoder to PC).
+BiSS is a bidirectional variant of SSI. Currently only a single direction is supported by LinuxCNC (encoder to PC).
One pin is created for each BiSS instance regardless of data format:
(bit, in) hm2_XXXX.NN.biss.MM.data\-incomplete
-This pin will be set "True" if the module was still transferring data when the
-value was read. When this problem exists there will also be a limited number of
-error messages printed to the UI. This pin should be used to monitor whether
-the problem has been addressed by config changes.
-Solutions to the problem dpend on whether the encoder read is being triggered by
-the hm2dpll phase-locked-loop timer (described above) or by the trigger\-encoders
-function (described below).
-
-The names of the pins created by the BiSS module will depend entirely on the
-format string for each channel specified in the loadrt command line and follow
-closely the format defined above for SSI.
-Currently data packets of up to 96 bits are supported by the LinuxCNC driver,
-although the Mesa Hostmot2 module can handle 512 bit packets. It should be
-possible to extend the number of packets supported by the driver if there is a
-requirement to do so.
+This pin will be set "True" if the module was still transferring data when the value was read.
+When this problem exists there will also be a limited number of error messages printed to the UI.
+This pin should be used to monitor whether the problem has been addressed by config changes.
+Solutions to the problem dpend on whether the encoder read is being triggered by the hm2dpll phase-locked-loop timer (described above) or by the trigger\-encoders function (described below).
+
+The names of the pins created by the BiSS module will depend entirely on the format string for each channel specified in the loadrt command line and follow closely the format defined above for SSI.
+Currently data packets of up to 96 bits are supported by the LinuxCNC driver, although the Mesa Hostmot2 module can handle 512 bit packets.
+It should be possible to extend the number of packets supported by the driver if there is a requirement to do so.
.SS Fanuc encoder
-The pins and format specifier for this module are identical to the SSI module
-described above, except that at least one pre-configured format is provided.
-A modparam of fanuc_chan_N=AA64 (case sensitive) will configure the channel for
-a Fanuc Aa64 encoder. The pins created are:
+The pins and format specifier for this module are identical to the SSI module described above, except that at least one pre-configured format is provided.
+A modparam of fanuc_chan_N=AA64 (case sensitive) will configure the channel for a Fanuc Aa64 encoder. The pins created are:
hm2_XXXX.N.fanuc.MM.batt indicates battery state
hm2_XXXX.N.fanuc.MM.batt\-not inverted version of above
hm2_XXXX.N.fanuc.MM.comm The 0-1023 absolute output for motor commutation
@@ -674,48 +546,38 @@ a Fanuc Aa64 encoder. The pins created are:
hm2_XXXX.N.fanuc.MM.valid\-not Inverted version
.SS resolver
-Resolvers have names like
-hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.resolver.\fI<Instance>\fR.
-<Instance> is a 2-digit number, which for the 7I49 board will be between 00 and
-05. This function only works with the Mesa Resolver interface boards (of which
-the 7I49 is the only example at the time of writing). This board uses an SPI
-interface to the FPGA card, and will only work with the correct firmware.
-The pins allocated will be listed in the dmesg output, but are unlikely to be
-usefully probed with HAL tools.
+Resolvers have names like hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.resolver.\fI<Instance>\fR.
+<Instance> is a 2-digit number, which for the 7I49 board will be between 00 and 05.
+This function only works with the Mesa Resolver interface boards (of which the 7I49 is the only example at the time of writing).
+This board uses an SPI interface to the FPGA card, and will only work with the correct firmware.
+The pins allocated will be listed in the dmesg output, but are unlikely to be usefully probed with HAL tools.
Pins:
.TP
(float, out) angle
-This pin indicates the angular position of the resolver. It
-is a number between 0 and 1 for each electrical rotation.
+This pin indicates the angular position of the resolver. It is a number between 0 and 1 for each electrical rotation.
.TP
(float, out) position
-Calculated from the number of complete and partial
-revolutions since startup, reset, or index\-reset multiplied by the scale
-parameter.
+Calculated from the number of complete and partial revolutions since startup, reset, or index\-reset multiplied by the scale parameter.
.TP
(float, out) velocity
-Calculated from the rotational velocity and the
-velocity\-scale parameter. The default scale is electrical rotations per second.
+Calculated from the rotational velocity and the velocity\-scale parameter. The default scale is electrical rotations per second.
.TP
(float, out) velocity-rpm
Simply velocity scaled by a factor of 60 for convenience.
-
.TP
(s32, out) count
-This pins outputs a simulated encoder count at 2^24
-counts per rev (16777216 counts).
+This pins outputs a simulated encoder count at 2^24 counts per rev (16777216 counts).
.TP
(s32, out) rawcounts
-This is identical to the counts pin, except it is not
-reset by the "index" or "reset" pins. This is the pin which would be linked to
-the bldc HAL component if the resolver was being used to commutate a motor.
+This is identical to the counts pin, except it is not reset by the "index" or "reset" pins.
+This is the pin which would be linked to the bldc HAL component if the resolver was being used to commutate a motor.
.TP
(bit, in) reset
@@ -723,89 +585,71 @@ Resets the position and counts pins to zero immediately.
.TP
(bit, in) joint-pos-fb
-The Mesa resolver driver has the capability of emulating an absolute
-encoder using a position file (see the INI-config section of the manual)
+The Mesa resolver driver has the capability of emulating an absolute encoder using a position file (see the INI-config section of the manual)
and the single-turn absolute operation of resolvers.
-At startup, and only if the \fBuse-position-file\fR parameter is set to "True"
-the resolver driver will wait for a value to be written by the system to
-the axis.N.joint-pos-fb pin (which must be netted to this resolver pin)
-and will calculate the number of full turns that best matches the
-current reolver position. It will then pre-load the driver output with this
-offset. This should only be used on systems where axis movement in the
-unpowered state is unlikely. This feature will only work properly if the
-machine is initially homed to "index" and if the axis home positions are
-exactly zero.
+At startup, and only if the \fBuse-position-file\fR parameter is set to "True",
+the resolver driver will wait for a value to be written by the system to the axis.N.joint-pos-fb pin (which must be netted to this resolver pin)
+and will calculate the number of full turns that best matches the current reolver position.
+It will then pre-load the driver output with this offset.
+This should only be used on systems where axis movement in the unpowered state is unlikely.
+This feature will only work properly if the machine is initially homed to "index" and if the axis home positions are exactly zero.
.TP
(bit, in/out) index\-enable
-When this pin is set high the position and counts
-pins will be reset the next time the resolver passes through the zero position.
-At the same time the pin is driven low to indicate to connected modules that the
-index has been seen, and that the counters have been reset.
+When this pin is set high the position and counts pins will be reset the next time the resolver passes through the zero position.
+At the same time the pin is driven low to indicate to connected modules that the index has been seen, and that the counters have been reset.
.TP
(bit, out) error
-Indicates an error in the particular channel. If this value is
-"True" then the reported position and velocity are invalid.
+Indicates an error in the particular channel. If this value is "True" then the reported position and velocity are invalid.
Parameters:
.TP
(float, read/write) scale
-The position scale, in machine units per resolver
-electrical revolution.
+The position scale, in machine units per resolver electrical revolution.
.TP
(float, read/write) velocity\-scale
-The conversion factor between resolver
-rotation speed and machine velocity. A value of 1 will typically give motor
-speed in rps, a value of 0.01666667 will give (approximate) RPM.
+The conversion factor between resolver rotation speed and machine velocity.
+A value of 1 will typically give motor speed in RPS, a value of 0.01666667 will give (approximate) RPM.
.TP
(u32, read/write) index\-divisor (default 1)
The resolver component emulates an index at a fixed point in the sin/cos cycle.
-Some resolvers have multiple cycles per rev (often related to the number of
-pole-pairs on the attached motor). LinuxCNC requires an index once per
-revolution for proper threading etc.
+Some resolvers have multiple cycles per rev (often related to the number of pole-pairs on the attached motor).
+LinuxCNC requires an index once per revolution for proper threading etc.
This parameter should be set to the number of cycles per rev of the resolver.
-CAUTION: Which pseudo-index is used will not necessarily be consistent between
-LinuxCNC runs. Do not expect to re-start a thread after restarting LinuxCNC.
+CAUTION: Which pseudo-index is used will not necessarily be consistent between LinuxCNC runs.
+Do not expect to re-start a thread after restarting LinuxCNC.
It is not appropriate to use this parameter for index-homing of axis drives.
.TP
(float, read/write) excitation\-khz
-This pin sets the excitation frequency for
-the resolver. This pin is module-level rather than instance-level as all
-resolvers share the same excitation frequency.
- Valid values are 10 (~10 kHz), 5 (~5 kHz) and 2.5 (~2.5 kHz). The
-actual frequency depends on the FPGA frequency, and they correspond to
-CLOCK_LOW/5000, CLOCK_LOW/10000 and CLOCK_LOW/20000 respectively.
+This pin sets the excitation frequency for the resolver.
+This pin is module-level rather than instance-level as all resolvers share the same excitation frequency.
+Valid values are 10 (~10 kHz), 5 (~5 kHz) and 2.5 (~2.5 kHz).
+The actual frequency depends on the FPGA frequency, and they correspond to CLOCK_LOW/5000, CLOCK_LOW/10000 and CLOCK_LOW/20000 respectively.
The parameter will be set to the closest available of the three frequencies.
- A value of \-1 (the default) indicates that the current setting should be
-retained.
+A value of \-1 (the default) indicates that the current setting should be retained.
.TP
(bit, read/write) use-position-file
In conjunction with \fBjoint-pos-fb\fR (qv) emulate absolute encoders.
-
.SS pwmgen
pwmgens have names like
"hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.pwmgen.\fI<Instance>\fR".
-"Instance" is a two-digit number that corresponds to the HostMot2 pwmgen
-instance number. There are "num_pwmgens" instances, starting with 00.
+"Instance" is a two-digit number that corresponds to the HostMot2 pwmgen instance number.
+There are "num_pwmgens" instances, starting with 00.
-So, for example, the HAL pin that enables output from the fourth pwmgen
-of the first 7I43 board is: hm2_7i43.0.pwmgen.03.enable (this assumes
-that the firmware in that board is configured so that this HAL object
-is available)
+So, for example, the HAL pin that enables output from the fourth pwmgen of the first 7I43 board is:
+hm2_7i43.0.pwmgen.03.enable (this assumes that the firmware in that board is configured so that this HAL object is available).
-In HM2, each pwmgen uses three output IO pins: Not\-Enable, Out0, and
-Out1.
+In HM2, each pwmgen uses three output IO pins: Not\-Enable, Out0, and Out1.
-The function of the Out0 and Out1 IO pins varies with output\-type
-parameter (see below).
+The function of the Out0 and Out1 IO pins varies with output\-type parameter (see below).
The hm2 pwmgen representation is similar to the software pwmgen component.
Each pwmgen instance has the following pins and parameters:
@@ -814,9 +658,8 @@ Pins:
.TP
(bit input) enable
-If True, the pwmgen will set its Not\-Enable pin
-False and output its pulses. If "enable" is False, pwmgen will set its
-Not\-Enable pin True and not output any signals.
+If True, the pwmgen will set its Not\-Enable pin False and output its pulses.
+If "enable" is False, pwmgen will set its Not\-Enable pin True and not output any signals.
.TP
(float input) value
@@ -826,115 +669,90 @@ Parameters:
.TP
(float rw) scale
-Scaling factor to convert "value" from arbitrary units
-to duty cycle: dc = value / scale. Duty cycle has an effective range
-of \-1.0 to +1.0 inclusive, anything outside that range gets clipped.
+Scaling factor to convert "value" from arbitrary units to duty cycle: dc = value / scale.
+Duty cycle has an effective range of \-1.0 to +1.0 inclusive, anything outside that range gets clipped.
The default scale is 1.0.
.TP
(s32 rw) output\-type
-This emulates the output_type load-time argument to
-the software pwmgen component. This parameter may be changed at runtime,
-but most of the time you probably want to set it at startup and then leave
-it alone. Accepted values are 1 (PWM on Out0 and Direction on Out1), 2
-(Up on Out0 and Down on Out1), 3 (PDM mode, PDM on Out0 and Dir on Out1),
-and 4 (Direction on Out0 and PWM on Out1, "for locked antiphase").
+This emulates the output_type load-time argument to the software pwmgen component.
+This parameter may be changed at runtime, but most of the time you probably want to set it at startup and then leave it alone.
+Accepted values are 1 (PWM on Out0 and Direction on Out1), 2 (Up on Out0 and Down on Out1), 3 (PDM mode, PDM on Out0 and Dir on Out1), and 4 (Direction on Out0 and PWM on Out1, "for locked antiphase").
.TP
(bit input) offset\-mode
-When True, offset\-mode modifies the PWM behavior so that a PWM value
-of 0 results in a 50% duty cycle PWM output, a -1 value results in a 0%
-duty cycle and +1 results in a 100% duty cycle (with default scaling)
+When True, offset\-mode modifies the PWM behavior so that a PWM value of 0 results in a 50% duty cycle PWM output,
+a -1 value results in a 0% duty cycle and +1 results in a 100% duty cycle (with default scaling).
This mode is used by some PWM motor drives and PWM to analog converters.
Typically the direction signal is not used in this mode.
-In addition to the per-instance HAL Parameters listed above, there are
-a couple of HAL Parameters that affect all the pwmgen instances:
+In addition to the per-instance HAL Parameters listed above, there are a couple of HAL Parameters that affect all the pwmgen instances:
.TP
(u32 rw) pwm_frequency
-This specifies the PWM frequency, in Hz, of all
-the pwmgen instances running in the PWM modes (modes 1 and 2). This is
-the frequency of the variable-duty-cycle wave. Its effective range is
-from 1 Hz up to 386 kHz. Note that the max frequency is determined by the
-ClockHigh frequency of the Anything IO board; the 5I25 and 7I92 both have
-a 200 MHz clock, resulting in a 386 kHz max PWM frequency. Other boards
-may have different clocks, resulting in different max PWM frequencies.
-If the user attempts to set the frequency too high, it will be clipped
-to the max supported frequency of the board. Frequencies below about
-5 Hz are not terribly accurate, but above 5 Hz they're pretty close.
+This specifies the PWM frequency, in Hz, of all the pwmgen instances running in the PWM modes (modes 1 and 2).
+This is the frequency of the variable-duty-cycle wave. Its effective range is from 1 Hz up to 386 kHz.
+Note that the max frequency is determined by the ClockHigh frequency of the Anything IO board;
+the 5I25 and 7I92 both have a 200 MHz clock, resulting in a 386 kHz max PWM frequency.
+Other boards may have different clocks, resulting in different max PWM frequencies.
+If the user attempts to set the frequency too high, it will be clipped to the max supported frequency of the board.
+Frequencies below about 5 Hz are not terribly accurate, but above 5 Hz they're pretty close.
The default pwm_frequency is 20,000 Hz (20 kHz).
.TP
(u32 rw) pdm_frequency
-This specifies the PDM frequency, in Hz, of
-all the pwmgen instances running in PDM mode (mode 3). This is the
-"pulse slot frequency"; the frequency at which the pdm generator in the
-AnyIO board chooses whether to emit a pulse or a space. Each pulse (and
-space) in the PDM pulse train has a duration of 1/pdm_frequency seconds.
-For example, setting the pdm_frequency to 2e6 (2 MHz) and the duty cycle
-to 50% results in a 1 MHz square wave, identical to a 1 MHz PWM signal
-with 50% duty cycle. The effective range of this parameter is from
-about 1525 Hz up to just under 200 MHz. Note that the max frequency
-is determined by the ClockHigh frequency of the Anything IO board; the
-5I25 and 7I92 both have a 100 MHz clock, resulting in a 100 MHz max
-PDM frequency. Other boards may have different clocks, resulting in
-different max PDM frequencies. If the user attempts to set the frequency
-too high, it will be clipped to the max supported frequency of the board.
+This specifies the PDM frequency, in Hz, of all the pwmgen instances running in PDM mode (mode 3).
+This is the "pulse slot frequency"; the frequency at which the pdm generator in the AnyIO board chooses whether to emit a pulse or a space.
+Each pulse (and space) in the PDM pulse train has a duration of 1/pdm_frequency seconds.
+For example, setting the pdm_frequency to 2e6 (2 MHz) and the duty cycle to 50% results in a 1 MHz square wave, identical to a 1 MHz PWM signal with 50% duty cycle.
+The effective range of this parameter is from about 1525 Hz up to just under 200 MHz.
+Note that the max frequency is determined by the ClockHigh frequency of the Anything IO board;
+the 5I25 and 7I92 both have a 100 MHz clock, resulting in a 100 MHz max PDM frequency.
+Other boards may have different clocks, resulting in different max PDM frequencies.
+If the user attempts to set the frequency too high, it will be clipped to the max supported frequency of the board.
The default pdm_frequency is 20,000 Hz (20 kHz).
.SS 3ppwmgen
-Three-Phase PWM generators (3pwmgens) are intended for controlling the high-side
-and low-side gates in a 3-phase motor driver. The function is included to
-support the Mesa motor controller daughter-cards but can be used to control
-an IGBT or similar driver directly.
-3pwmgens have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.3pwmgen.\fI<Instance>\fR"
-where <Instance> is a 2-digit number. There will be num_3pwmgens instances,
-starting at 00.
+Three-Phase PWM generators (3pwmgens) are intended for controlling the high-side and low-side gates in a 3-phase motor driver.
+The function is included to support the Mesa motor controller daughter-cards but can be used to control an IGBT or similar driver directly.
+3pwmgens have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.3pwmgen.\fI<Instance>\fR" where <Instance> is a 2-digit number.
+There will be num_3pwmgens instances, starting at 00.
Each instance allocates 7 output and one input pins on the Mesa card connectors.
-Outputs are: PWM A, PWM B, PWM C, /PWM A, /PWM B, /PWM C, Enable. The first three
-pins are the high side drivers, the second three are their complementary low-side
-drivers. The enable bit is intended to control the servo amplifier.
-The input bit is a fault bit, typically wired to over-current detection. When set
-the PWM generator is disabled.
-The three phase duty-cycles are individually controllable from \-Scale to +Scale.
+Outputs are: PWM A, PWM B, PWM C, /PWM A, /PWM B, /PWM C, Enable.
+The first three pins are the high side drivers, the second three are their complementary low-side drivers.
+The enable bit is intended to control the servo amplifier.
+The input bit is a fault bit, typically wired to over-current detection.
+When set the PWM generator is disabled. The three phase duty-cycles are individually controllable from \-Scale to +Scale.
Note that 0 corresponds to a 50% duty cycle and this is the inialization value.
Pins:
-(float input) A\-value, B\-value, C\-value: The PWM command value for each phase,
-limited to +/\- "scale". Defaults to zero which is 50% duty cycle on high-side and
-low-sidepins (but see the "deadtime" parameter).
+(float input) A\-value, B\-value, C\-value: The PWM command value for each phase, limited to +/\- "scale".
+Defaults to zero which is 50% duty cycle on high-side and low-sidepins (but see the "deadtime" parameter).
.TP
(bit input) enable
-When high the PWM is enabled as long as the fault bit is not
-set by the external fault input pin. When low the PWM is disabled, with both high-
-side and low-side drivers low. This is not the same as 0 output (50% duty cycle on
-both sets of pins) or negative full scale (where the low side drivers are "on"
-100% of the time).
+When high the PWM is enabled as long as the fault bit is not set by the external fault input pin.
+When low the PWM is disabled, with both high- side and low-side drivers low.
+This is not the same as 0 output (50% duty cycle on both sets of pins) or negative full scale (where the low side drivers are "on" 100% of the time).
.TP
(bit output) fault
-Indicates the status of the fault bit. This output latches high
-once set by the physical fault pin until the "enable" pin is set to high.
+Indicates the status of the fault bit. This output latches high once set by the physical fault pin until the "enable" pin is set to high.
Parameters:
.TP
(u32 rw) deadtime
-Sets the dead-time between the high-side driver turning off and
-the low-side driver turning on and vice-versa. Deadtime is subtracted from on time
-and added to off time symmetrically. For example with 20 kHz PWM (50 uSec period),
-50% duty cycle and zero dead time, the PWM and NPWM outputs would be square
-waves (NPWM being inverted from PWM) with high times of 25 µs. With the same
-settings but 1 µs of deadtime, the PWM and NPWM outputs would both have high
-times of 23 µs (25 \- (2X 1 µs), 1 µs per edge).
-The value is specified in nanoseconds (ns) and defaults to a rather conservative 5000 ns. Setting
-this parameter to too low a value could be both expensive and dangerous as if both
-gates are open at the same time there is effectively a short circuit across the
-supply.
+Sets the dead-time between the high-side driver turning off and the low-side driver turning on and vice-versa.
+Deadtime is subtracted from on time and added to off time symmetrically.
+For example with 20 kHz PWM (50 µs period), 50% duty cycle and zero dead time, the PWM and NPWM outputs would be square waves
+(NPWM being inverted from PWM) with high times of 25 µs.
+With the same settings but 1 µs of deadtime, the PWM and NPWM outputs would both have high times of 23 µs (25 \- (2X 1 µs), 1 µs per edge).
+The value is specified in nanoseconds (ns) and defaults to a rather conservative 5000 ns.
+Setting this parameter to too low a value could be both expensive and dangerous as if both gates are open at the same time
+there is effectively a short circuit across the supply.
.TP
(float rw) scale
@@ -943,34 +761,27 @@ PWM values from \-scale to +scale are valid. Default is +/\- 1.0
.TP
(bit rw) fault\-invert
-Sets the polarity of the fault input pin. A value of 1 means
-that a fault is triggered with the pin high, and 0 means that a fault it triggered
-when the pin is pulled low. Default 0, fault = low so that the PWM works with the
-fault pin unconnected.
+Sets the polarity of the fault input pin.
+A value of 1 means that a fault is triggered with the pin high, and 0 means that a fault it triggered when the pin is pulled low.
+Default 0, fault = low so that the PWM works with the fault pin unconnected.
.TP
(u32 rw) sample\-time
-Sets the time during the cycle when an ADC pulse
-is generated. 0 = start of PWM cycle and 1 = end. Not currently useful
-to LinuxCNC. Default 0.5.
+Sets the time during the cycle when an ADC pulse is generated.
+0 = start of PWM cycle and 1 = end. Not currently useful to LinuxCNC. Default 0.5.
-In addition the per-instance parameters above there is the following parameter
-that affects all instances:
+In addition the per-instance parameters above there is the following parameter that affects all instances:
.TP
(u32 rw) frequency
-Sets the master PWM frequency. Maximum is approx 48 kHz, minimum
-is 1 kHz. Defaults to 20 kHz.
+Sets the master PWM frequency. Maximum is approx 48 kHz, minimum is 1 kHz. Defaults to 20 kHz.
.SS oneshot
-The oneshot is a hardware one-shot device suitable for various timing, delay,
-signal conditioning, PWM generation, and watchdog functions. The oneshot module
-includes 2 timers to allow variable pulse delays for applications like phase control.
-Trigger sources can be software, external inputs, the DPLL timer, a built in
-rate generator or the other timer.
-Oneshots have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.oneshot.\fI<Instance>\fR"
-where <Instance> is a 2-digit number. There will be num_oneshots instances,
-starting at 00. Each instance allocates up to two input and two output pins.
+The oneshot is a hardware one-shot device suitable for various timing, delay, signal conditioning, PWM generation, and watchdog functions.
+The oneshot module includes 2 timers to allow variable pulse delays for applications like phase control.
+Trigger sources can be software, external inputs, the DPLL timer, a built in rate generator or the other timer.
+Oneshots have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.oneshot.\fI<Instance>\fR" where <Instance> is a 2-digit number.
+There will be num_oneshots instances, starting at 00. Each instance allocates up to two input and two output pins.
Pins:
@@ -979,27 +790,25 @@ Pins:
Sets the pulse width of timer1 in ms. Default is 1 ms (1/1000 s).
.TP
-(float rw) width2
+(float rw) width2
Sets the pulse width of timer2 in ms. Default is 1 ms (1/1000 s).
.TP
(float rw) filter1
-Sets digital filter time constant for timer1's external trigger input
-Filter time is in ms. Default filter time constant time is 0.1 ms.
-External trigger response will be delayed by the filter time setting
+Sets digital filter time constant for timer1's external trigger input Filter time is in ms. Default filter time constant time is 0.1 ms.
+External trigger response will be delayed by the filter time setting.
.TP
(float rw) filter2
-Sets digital filter time constant for timer2's external trigger input
-Filter time is in ms. Default filter time constant time is 0.1 ms.
-External trigger response will be delayed by the filter time setting
+Sets digital filter time constant for timer2's external trigger input Filter time is in ms. Default filter time constant time is 0.1 ms.
+External trigger response will be delayed by the filter time setting.
.TP
(float rw) rate
Sets the frequency of the built in rate generator (in Hz)
.TP
-(u32 rw) trigger_select1,trigger_select2
+(u32 rw) trigger_select1,trigger_select2
Sets the trigger source for timer1,timer2 respectively.
Trigger sources are:
.nf
@@ -1017,15 +826,14 @@ When true, triggers timer1, timer2 respectively on the rising edge of the trigge
.TP
(bit rw) trigger_on_fall1,trigger_on_fall2
-When true, triggers timer1,timer2 respectively on the falling edge of the trigger source.
+When true, triggers timer1, timer2 respectively on the falling edge of the trigger source.
.TP
(bit rw) retriggerable1,retriggerable2
When true, the associated timer is retriggerable,
meaning the timer will reset to full time on a trigger event even during the output pulse period.
-When false the timer is not retriggerable,
-meaning it will ignore trigger events during the output pulse period.
-
+When false the timer is not retriggerable, meaning it will ignore trigger events during the output pulse period.
+
.TP
(bit rw) enable1,enable2
trigger enable for timer1 and timer2 respectively True to enable.
@@ -1059,7 +867,7 @@ Pins:
.TP
(float rw) rate
-Sets the master RC PWM frequency. Maximum is 1 kHz, minimum is .01 Hz. Defaults to 50 Hz.
+Sets the master RC PWM frequency. Maximum is 1 kHz, minimum is .01 Hz. Defaults to 50 Hz.
.TP
(float rw) width
@@ -1072,19 +880,18 @@ This would be set to 1.5 ms for 1-2 ms servos for a 0 center position.
.TP
(float rw) scale
-Sets the per channel pulse width scaling, for example, setting the scale to 90
-and the offset to 1.5 ms would result in a position range of +-45 degrees
-scale in degrees for 1-2 ms servos with a full motion range of 90 degrees
+Sets the per channel pulse width scaling.
+For example, setting the scale to 90 and the offset to 1.5 ms would result in a position range of +-45 degrees
+and scale in degrees for 1-2 ms servos with a full motion range of 90 degrees
.SS stepgen
-stepgens have names like
-"hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.stepgen.\fI<Instance>\fR".
+stepgens have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.stepgen.\fI<Instance>\fR".
"Instance" is a two-digit number that corresponds to the HostMot2 stepgen instance number.
There are "num_stepgens" instances, starting with 00.
So, for example, the HAL pin that has the current position feedback from the first stepgen of the second 5I22 board is:
-hm2_5i22.1.stepgen.00.position\-fb (this assumes that the firmware in that board is configured so that this HAL object is available)
+hm2_5i22.1.stepgen.00.position\-fb (this assumes that the firmware in that board is configured so that this HAL object is available).
Each stepgen uses between 2 and 8 IO pins.
The signals on these pins depends on the step_type parameter (described below).
@@ -1121,16 +928,14 @@ This is similar to "counts/position_scale", but has finer than step resolution.
.TP
(float output) velocity\-fb
-Feedback velocity in arbitrary position
-units per second.
+Feedback velocity in arbitrary position units per second.
.TP
(bit input) enable
This pin enables the step generator instance.
When True, the stepgen instance works as expected.
When False, no steps are generated and velocity\-fb goes immediately to 0.
-If the stepgen is moving when enable goes False it stops immediately,
-without obeying the maxaccel limit.
+If the stepgen is moving when enable goes False it stops immediately, without obeying the maxaccel limit.
.TP
(bit input) position\-reset
@@ -1179,7 +984,8 @@ The max velocity will change if the step timings or position\-scale changes. De
(float r/w) maxaccel
Maximum acceleration, in position units per second per second.
Defaults to 1.0.
-If set to 0, the driver will not limit its acceleration at all - this requires that the position\-cmd or velocity\-cmd pin is driven in a way that does not exceed the machine's capabilities.
+If set to 0, the driver will not limit its acceleration at all.
+This requires that the position\-cmd or velocity\-cmd pin is driven in a way that does not exceed the machine's capabilities.
This is probably what you want if you are going to be using the LinuxCNC trajectory planner to jog or run G-code.
.TP
@@ -1200,7 +1006,7 @@ Minimum duration of stable Direction signal after a step ends, in nanoseconds.
.TP
(u32 r/w) step_type
-Output format, like the step_type modparam to the software stepgen(9) component. 0 = Step/Dir, 1 = Up/Down, 2 = Quadrature, 3+ = table-lookup mode.
+Output format, like the step_type modparam to the software stepgen(9) component: 0 = Step/Dir, 1 = Up/Down, 2 = Quadrature, 3+ = table-lookup mode.
In this mode the step_type parameter determines how long the step sequence is.
Additionally the stepgen_width parameter in the loadrt config string must be set to suit the number of pins per stepgen required.
Any stepgen pins above this number will be available for GPIO.
@@ -1221,8 +1027,8 @@ This parameter is only available if the firmware supports this option.
(u32 r/w) table\-data\-N
There are 4 table\-data\-N parameters, table\-data\-0 to table\-data\-3.
These each contain 4 bytes corresponding to 4 stages in the step sequence.
-For example table\-data\-0 = 0x00000001 would set stepgen pin 0 (always called "Step" in the dmesg output) on the first phase of the step sequence, and table\-data\-4 =
-0x20000000 would set stepgen pin 6 ("Table5Pin" in the dmesg output) on the 16th stage of the step sequence.
+For example table\-data\-0 = 0x00000001 would set stepgen pin 0 (always called "Step" in the dmesg output) on the first phase of the step sequence,
+and table\-data\-4 = 0x20000000 would set stepgen pin 6 ("Table5Pin" in the dmesg output) on the 16th stage of the step sequence.
.TP
(s32 r/w) hm2_XXXX.N.stepgen.timer\-number (default: \-1)
@@ -1235,20 +1041,16 @@ Typically, timer\-us should be a negative number with a magnitude larger than th
(e.g., \-100 for a system with mediocre latency, \-50 for a system with good latency).
A negative number specifies latching the specified time before the nominal hostmot2 read time.
-If no DPLL module is present in the FPGA firmware, or if the stepgen module does not support DPLL,
-then this pin is not created.
+If no DPLL module is present in the FPGA firmware, or if the stepgen module does not support DPLL, then this pin is not created.
When available, this feature should typically be enabled.
Doing so generally reduces following errors.
.SS Smart Serial Interface
-The Smart Serial Interface allows up to 32 different devices,
-such as the Mesa 8I20 2.2&#8239;kW 3-phase drive or 7I64 48-way IO cards,
-to be connected to a single FPGA card.
+The Smart Serial Interface allows up to 32 different devices such as the Mesa 8i20 2.2 kW 3-phase drive or 7I64 48-way IO cards to be connected to a single FPGA card.
The driver auto-detects the connected hardware port, channel and device type.
-Devices can be connected in any order to any active channel of an active port
-(see the config modparam definition above).
+Devices can be connected in any order to any active channel of an active port (see the config modparam definition above).
For full details of the smart-serial devices see \fBsserial\fR(9).
@@ -1261,28 +1063,25 @@ pre-processing language: see http://linuxcnc.org/docs/html/hal/comp.html or man
See mesa_7i65(9) and the source of mesa_7i65.comp for details of a typical sub-driver.
See hm2_bspi_setup_chan(3hm2), hm2_bspi_write_chan(3hm2),
hm2_tram_add_bspi_frame(3hm2), hm2_allocate_bspi_tram(3hm2),
-hm2_bspi_set_read_function(3hm2) and hm2_bspi_set_write_function(3hm2)
-for the exported functions.
+hm2_bspi_set_read_function(3hm2) and hm2_bspi_set_write_function(3hm2) for the exported functions.
-The names of the available channels are printed to standard output during the
-driver loading process and take the form
-hm2_<board name>.<board index>.bspi.<index>, e.g., hm2_5i23.0.bspi.0.
+The names of the available channels are printed to standard output during the driver loading process
+and take the form hm2_<board name>.<board index>.bspi.<index>, e.g., hm2_5i23.0.bspi.0.
.SS UART
-The UART driver also does not create any HAL pins, instead it declares two
-simple read/write functions and a setup function to be utilised by user-written code.
-Typically this would be written in the "comp" pre-processing language:
-see http://linuxcnc.org/docs/html/hal/comp.html or man halcompile for further details.
+The UART driver also does not create any HAL pins, instead it declares two simple read/write functions and a setup function to be utilised by user-written code.
+Typically this would be written in the "comp" pre-processing language: see http://linuxcnc.org/docs/html/hal/comp.html or man halcompile for further details.
See mesa_uart(9) and the source of mesa_uart.comp for details of a typical sub-driver.
See hm2_uart_setup_chan(3hm2), hm2_uart_send(3hm2), hm2_uart_read(3hm2) and hm2_uart_setup(3hm2).
-The names of the available uart channels are printed to standard output during the
-driver loading process and take the form hm2_<board name>.<board index>uart.<index>, e.g., hm2_5i23.0.uart.0.
+The names of the available uart channels are printed to standard output during the driver loading process
+and take the form hm2_<board name>.<board index>uart.<index>, e.g., hm2_5i23.0.uart.0.
.SS General Purpose I/O
+
I/O pins on the board which are not used by a module instance are exported to HAL as "full" GPIO pins.
Full GPIO pins can be configured at run-time to be inputs, outputs, or open drains, and have a HAL interface that exposes this flexibility.
-IO pins that are owned by an active module instance are constrained by the requirements of the owning module, and have a restricted HAL interface.
+I/O pins that are owned by an active module instance are constrained by the requirements of the owning module, and have a restricted HAL interface.
GPIOs have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.gpio.\fI<IONum>\fR".
IONum is a three-digit number.
@@ -1290,14 +1089,12 @@ The mapping from IONum to connector and pin-on-that-connector is written to the
and it is documented in Mesa's manual for the Anything I/O boards.
So, for example, the HAL pin that has the current inverted input value read from GPIO 012 of the second 7I43 board is:
-hm2_7i43.1.gpio.012.in\-not
-(this assumes that the firmware in that board is configured so that this HAL object is available).
+hm2_7i43.1.gpio.012.in\-not (this assumes that the firmware in that board is configured so that this HAL object is available)
The HAL parameter that controls whether the last GPIO of the first 5I22 is an input or an output is:
hm2_5i22.0.gpio.095.is_output (this assumes that the firmware in that board is configured so that this HAL object is available).
-The hm2 GPIO representation is modeled after the Digital Inputs and
-Digital Outputs described in the Canonical Device Interface (part of the HAL General Reference document).
+The hm2 GPIO representation is modeled after the Digital Inputs and Digital Outputs described in the Canonical Device Interface (part of the HAL General Reference document).
Each GPIO can have the following HAL Pins:
.TP
@@ -1326,8 +1123,7 @@ Only full GPIO pins have this parameter.
(bit r/w) is_opendrain
This parameter only has an effect if the "is_output" parameter is True.
If this parameter is False, the GPIO behaves as a normal output pin:
-The IO pin on the connector is driven to the value specified by the "out" HAL pin (possibly inverted),
-and the value of the "in" and "in_not" HAL pins is undefined.
+the IO pin on the connector is driven to the value specified by the "out" HAL pin (possibly inverted), and the value of the "in" and "in_not" HAL pins is undefined.
If this parameter is True, the GPIO behaves as an open-drain pin.
Writing 0 to the "out" HAL pin drives the IO pin low, writing 1 to the "out" HAL pin puts the IO pin in a high-impedance state.
In this high-impedance state the IO pin floats (weakly pulled high), and other devices can drive the value;
@@ -1349,8 +1145,7 @@ For instance, if gpio 1 is taken over by pwmgen 0's first output, then aliases l
(referring to
.BR hm2_7i92.0.gpio.001.invert_output )
will be automatically created.
-When more than one GPIO is connected to the same special function,
-an extra .#. is inserted so that the settings for each related GPIO can be set separately.
+When more than one GPIO is connected to the same special function, an extra .#. is inserted so that the settings for each related GPIO can be set separately.
For example, for the firmware SV12IM_2X7I48_72, the alias
.B hm2_5i20.0.pwmgen.00.0.enable.invert_output
(referring to
@@ -1373,9 +1168,7 @@ inmuxes have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.inmux.\fI<Instan
"Instance" is a two-digit number that corresponds to the HostMot2 inm or inmux instance number.
There are "num_inms" or numx_inmuxs" instances, starting with 00.
-Each instance reads between 8 and 32 input pins.
-inm and inmux are identical except for pin names and the physical interface.
-
+Each instance reads between 8 and 32 input pins. inm and inmux are identical except for pin names and the physical interface.
Pins:
@@ -1436,13 +1229,12 @@ Pins:
.TP
(bit in) CR<NN>
-The pins are numbered from CR01 upwards with the name corresponding to the PCB silkscreen.
+The pins are numbered from CR01 upwards with the name corresponding to the PCB silkscreen.
Setting the bit to "True" or 1 lights the LED.
.SS Solid State Relay
-SSRs have names like
-"hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.ssr.\fI<Instance>\fR".
+SSRs have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.ssr.\fI<Instance>\fR".
"Instance" is a two-digit number that corresponds to the HostMot2 SSR instance number.
There are "num_ssrs" instances, starting with 00.
@@ -1498,13 +1290,11 @@ Pins:
.TP
(float in) posx_cmd, posy_cmd
-X and Y position commands.
-Full scale is +-posn_scale default full scale (set by posx_scale and posy_scale) is +- 1
+X and Y position commands. Full scale is +-posn_scale default full scale (set by posx_scale and posy_scale) is +- 1
.TP
(float out) posx_fb, posy_fb
-X and Y position feedback.
-Full scale is +-posN_scale default full scale is +- 1.
+X and Y position feedback. Full scale is +-posN_scale default full scale is +- 1.
This is feedback from the interpolator not the galvanometer.
.TP
@@ -1521,8 +1311,7 @@ X and Y acceleration commands in units of fullscale_position/second^2
.TP
(float in) posx_scale, posy_scale
-This sets the full scale range of the position command and feedback.
-default is +- 1.0.
+This sets the full scale range of the position command and feedback, default is +- 1.0.
.TP
(bit in) enable
@@ -1532,8 +1321,7 @@ Must be True for normal operation.
.TP
(u32 in) controlx, controly
These set the galvanometer control bits.
-There 3 bits per channel in 16 bit mode but just 1 control bit in 18 bit mode,
-so values from 0..7 are valid in 16 bit mode but only 0 and 4 are valid in 18 bit mode.
+There 3 bits per channel in 16 bit mode but just 1 control bit in 18 bit mode, so values from 0..7 are valid in 16 bit mode but only 0 and 4 are valid in 18 bit mode.
.TP
(u32 in) commandx, commandy
@@ -1553,7 +1341,7 @@ When true, these indicate an attempted position move beyond the full scale value
.TP
(bit out) velx-overflow, vely-overflow
-When True, these indicate an attempted velocity update move beyond the full scale value
+When True, these indicate an attempted velocity update move beyond the full scale value.
.TP
(u32 out) status
@@ -1585,9 +1373,9 @@ Pet the watchdog by running the hm2 write() HAL function.
When the watchdog bites,
all the board's I/O pins are disconnected from their Module instances and become high-impedance inputs (pulled high),
and all communication with the board stops.
-The state of the HostMot2 firmware modules is not disturbed (except for the configuration of the IO Pins).
+The state of the HostMot2 firmware modules is not disturbed (except for the configuration of the IO pins).
Encoder instances keep counting quadrature pulses,
-and pwm- and step-generators keep generating signals (which are *not* relayed to the motors, because the IO Pins have become inputs).
+and pwm- and step-generators keep generating signals (which are *not* relayed to the motors, because the IO pins have become inputs).
Resetting the watchdog (by clearing the has_bit pin, see below) resumes communication and
resets the I/O pins to the configuration chosen at load-time.
diff --git a/docs/man/man9/kins.9 b/docs/man/man9/kins.9
index a7c56b8d1e..139d1419d6 100644
--- a/docs/man/man9/kins.9
+++ b/docs/man/man9/kins.9
@@ -40,6 +40,8 @@ For additional information, see the Documents 'Advanced Topics':
.PP
.B loadrt tripodkins
.PP
+.B loadrt xyzab_tdr_kins
+.PP
.B loadrt xyzac\-trt\-kins
.PP
.B loadrt xyzbc\-trt\-kins
@@ -96,9 +98,9 @@ Assigns: x==joint0, y0==joint1, z==joint2, y1==joint3
.PP
-The default kinematics type is \fBKINEMATICS_IDENTITY\fR. Guis may provide
+The default kinematics type is \fBKINEMATICS_IDENTITY\fR. GUIs may provide
special features for configurations using this default kinematics type. For
-instance, the axis gui automatically handles joint and world mode operations so
+instance, the AXIS GUI automatically handles joint and world mode operations so
that the distinctions between joints and axes are not visible to the operator.
This is feasible since there is an exact correspondence between a joint number
and its matching axis letter.
diff --git a/docs/man/man9/lcd.9 b/docs/man/man9/lcd.9
index 70dee46c74..1ffe22c600 100644
--- a/docs/man/man9/lcd.9
+++ b/docs/man/man9/lcd.9
@@ -7,8 +7,8 @@ lcd \- Stream HAL data to an LCD screen
.B loadrt lcd fmt_strings=""Plain Text %4.4f\enAnd So on|Second Page, Next Inst""
.SH FUNCTIONS
.TP
-\fBlcd\fR (requires a floating-point thread). All LCD instances are updated by the
-same function.
+\fBlcd\fR (requires a floating-point thread).
+All LCD instances are updated by the same function.
.SH PINS
.TP
@@ -25,8 +25,8 @@ between them.
.TP
.B lcd.\fINN\fB.contrast\fR (float) in
Attempts to set the contrast of the LCD screen using the byte sequence ESC C and
-then a value from 0x20 to 0xBF (matching the Mesa 7I73). The value should be
-between 0 and 1.
+then a value from 0x20 to 0xBF (matching the Mesa 7I73).
+The value should be between 0 and 1.
.SH PARAMETERS
.TP
@@ -34,13 +34,14 @@ between 0 and 1.
Sets the decimal separator used for floating point numbers. The default value is
46 (0x2E) which corresponds to ".". If a comma is required then set this
parameter to 44 (0x2C).
+
.SH DESCRIPTION
\fBlcd\fR takes format strings much like those used in C and many other languages
in the printf and scanf functions and their variants.
-The component was written specifically to support the Mesa 7I73 pendant
-controller, however it may be of use streaming data to other character devices
+The component was written specifically to support the Mesa 7I73 pendant controller,
+however, it may be of use streaming data to other character devices
and, as the output format mimics the ADM3 terminal format, it could be used
to stream data to a serial device. Perhaps even a genuine ADM3.
The strings contain a mixture of text values (which are displayed directly),
@@ -70,18 +71,17 @@ tab.)
.TP
\fBNumerical formats\fR
-\fBlcd\fR differs slightly from the standard printf conventions. One significant
-difference is that width limits are strictly enforced to prevent the LCD display
+\fBlcd\fR differs slightly from the standard printf conventions.
+One significant difference is that width limits are strictly enforced to prevent the LCD display
wrapping and spoiling the layout. The field width includes the sign character
so that negative numbers will often have a smaller valid range than positive.
-Numbers that do not fit in the specified width are displayed as a line of
-asterisks (\fB********\fR).
+Numbers that do not fit in the specified width are displayed as a line of asterisks (\fB********\fR).
Each format begins with a "%" symbol. (For a literal % use "%%").
Immediately after the % the following modifiers may be used:
-" " (space) Pad the number to the specified width with spaces. This is the
-default and is not strictly necessary.
+" " (space) Pad the number to the specified width with spaces.
+This is the default and is not strictly necessary.
"0" Pad the number to the specified width with the numeral 0.
@@ -89,22 +89,20 @@ default and is not strictly necessary.
will appear immediately to the left of the digits for a space-padded number
and in the extreme left position for a 0-padded number.
-"1234567890" A numerical entry (other than the leading 0 above) defines the
-total number of characters to display including the decimal separator and the
-sign. Whilst this number can be as many digits as required the maximum field
-width is 20 characters. The inherent precision of the "double" data type means
-that more than 14 digits will tend to show errors in the least significant
-digits. The integer data types will never fill more than 10 decimal digits.
+"1234567890" A numerical entry (other than the leading 0 above) defines the
+total number of characters to display including the decimal separator and the sign.
+Whilst this number can be as many digits as required, the maximum field width is 20 characters.
+The inherent precision of the "double" data type means
+that more than 14 digits will tend to show errors in the least significant digits.
+The integer data types will never fill more than 10 decimal digits.
-Following the width specifier should be the decimal specifier. This can only be
-a full-stop character (.) as the comma (,) is used as the instance separator.
-Currently lcd does not access the locale information to determine the correct
-separator but the \fBdecimal\-separator\fR HAL parameter can be used to
-choose any desired separator.
+Following the width specifier should be the decimal specifier.
+This can only be a full-stop character (.) as the comma (,) is used as the instance separator.
+Currently lcd does not access the locale information to determine the correct separator
+but the \fBdecimal\-separator\fR HAL parameter can be used to choose any desired separator.
-Following the decimal separator should be a number that determines how many
-places of decimals to display. This entry is ignored in the case of integer
-formats.
+Following the decimal separator should be a number that determines
+how many places of decimals to display. This entry is ignored in the case of integer formats.
All the above modifiers are optional, but to specify a decimal precision the
decimal point must precede the precision, e.g., as in "%.3f".
@@ -132,33 +130,30 @@ A width may be specified, though the u32 HAL type is only 8 hex digits wide.
\fB%o\fR Creates an unsigned (u32) pin and displays the value in octal representation.
-\fB%c\fR Creates a u32 HAL pin and displays the character corresponding to the value
-of the pin. Values less than 32 (space) are suppressed. A width specifier may
-be used, for example %20c might be used to create a complete line of one
-character.
+\fB%c\fR Creates a u32 HAL pin and displays the character corresponding to the value of the pin.
+Values less than 32 (space) are suppressed. A width specifier may be used,
+for example %20c might be used to create a complete line of one character.
-\fB%b\fR This specifier has no equivalent in printf. It creates a bit (boolean) type
-HAL pin. The b should be followed by two characters and the display will show
-the first of these when the pin is true, and the second when false. Note that
-the characters follow, not precede the "b", unlike the case with other formats.
-The characters may be "escaped" Hex values. For example "%b\eFF " will display a
-solid black block if true, and a space if false and "%b\e7F\e7E" would display
-right-arrow for false and left-arrow for true. An unexpected value of 'E'
-indicates a formatting error.
+\fB%b\fR This specifier has no equivalent in printf.
+It creates a bit (boolean) type HAL pin. The b should be followed by two characters
+and the display will show the first of these when the pin is true, and the second when false.
+Note that the characters follow, not precede the "b", unlike the case with other formats.
+The characters may be "escaped" Hex values.
+For example "%b\eFF " will display a solid black block if true,
+and a space if false and "%b\e7F\e7E" would display right-arrow for false and left-arrow for true.
+An unexpected value of 'E' indicates a formatting error.
\fBPages\fR
The page separator is the "|" (pipe) character (if the actual character is needed then \e7C may be used).
A "Page" in this context refers to a separate format which may be displayed on the same display.
\fBInstances\fR
-The instance separator is the comma. This creates a completely separate lcd
-instance, for example to drive a second lcd display on the second 7I73.
+The instance separator is the comma. This creates a completely separate lcd instance,
+for example to drive a second lcd display on the second 7I73.
The use of comma to separate instances is built in to the modparam reading code
so not even escaped commas "\e," can be used.
A comma may be displayed by using the \e2C sequence.
-
-
.SH AUTHOR
Andy Pugh
.SH LICENSE
diff --git a/docs/man/man9/matrix_kb.9 b/docs/man/man9/matrix_kb.9
index 309904c384..4b75562af6 100644
--- a/docs/man/man9/matrix_kb.9
+++ b/docs/man/man9/matrix_kb.9
@@ -23,38 +23,32 @@ There must be no spaces in the parameter lists.
.SH DESCRIPTION
This component was written to convert matrix keyboard scancodes into HAL pins.
-However, it might also find uses in converting integers from 0 to N into N HAL
-pins.
+However, it might also find uses in converting integers from 0 to N into N HAL pins.
-The component can work in two ways, and the HAL pins created vary according to
-mode.
+The component can work in two ways, and the HAL pins created vary according to mode.
In the default mode the component expects to be given a scan code from a
separate driver but could be any integer from any source. Most typically this
-will be the keypad scancode from a Mesa 7i73. The default codes for keyup and
-keydown are based on the Mesa 7i73 specification with 0x40 indicating a keydown
+will be the keypad scancode from a Mesa 7I73. The default codes for keyup and
+keydown are based on the Mesa 7I73 specification with 0x40 indicating a keydown
and 0x80 a keyup event.
- If using the 7i73 it is important to match the keypad size
-jumpers with the HAL component. Valid configs for the 7i73 are 4x8 and 8x8.
-Note that the component will only work properly with the version 12 (0xC) 7i73
-firmware. The firmware version is visible on the component parameters in HAL.
+If using the 7I73, it is important to match the keypad size jumpers with the HAL component.
+Valid configs for the 7I73 are 4x8 and 8x8.
+Note that the component will only work properly with the version 12 (0xC) 7I73 firmware.
+The firmware version is visible on the component parameters in HAL.
In the optional scan-generation mode the \fBmatrix_kb.\fIN\fB.keycode\fR pin
-changes to an output pin and a set of output row pins and input column pins are
-created.
+changes to an output pin and a set of output row pins and input column pins are created.
These need to be connected to physical inputs and outputs to scan the matrix and
return values to HAL. Note the \fBnegative\-logic\fR parameter described below,
-this will need to be set on the most common forms of inputs which float high
-when unconnected.
+this will need to be set on the most common forms of inputs which float high when unconnected.
-In both modes a set of HAL output pins are created corresponding to each node of
-the matrix.
+In both modes a set of HAL output pins are created corresponding to each node of the matrix.
.SH FUNCTIONS
.TP
.B matrix_kb.\fIN\fR
-Perform all requested functions. Should be run in a slow thread for effective
-debouncing.
+Perform all requested functions. Should be run in a slow thread for effective debouncing.
.SH PINS
.TP
.B matrix_kb.\fIN\fB.col\-\fICC\fB\-in\fR bit in
@@ -64,19 +58,19 @@ The input pin corresponding to column C.
The pin corresponding to the key at row R column C of the matrix.
.TP
.B matrix_kb.\fIN\fB.keycode\fR unsigned in or out depending on mode.
-This pin should be connected to the scancode generator if hardware such as a
-7i73 is being used. In this mode it is an input pin. In the internally-generated
+This pin should be connected to the scancode generator if hardware such as a 7I73 is being used.
+In this mode it is an input pin. In the internally-generated
scanning mode this pin is an output, but will not normally be connected.
.TP
.B matrix_kb.\fIN\fB.row\-\fIRR\fB\-out bit out
-The row scan drive pins.Should be connected to external hardware pins connected
-to the keypad.
+The row scan drive pins.
+Should be connected to external hardware pins connected to the keypad.
.SH PARAMETERS
.TP
.B matrix_kb.\fIN\fB.key_rollover\fR unsigned r/w (default 2)
-With most matrix keyboards the scancodes are only unambiguous with 1 or 2 keys
-pressed. With more keys pressed phantom keystrokes can appear. Some keyboards
+With most matrix keyboards the scancodes are only unambiguous with 1 or 2 keys pressed.
+With more keys pressed phantom keystrokes can appear. Some keyboards
are optimised to reduce this problem, and some have internal diodes so that any
number of keys may be pressed simultaneously. Increase the value of this parameter
if such a keyboard is connected, or if phantom keystrokes are more acceptable
diff --git a/docs/man/man9/motion.9 b/docs/man/man9/motion.9
index 52f20e6327..4bb52acbd6 100644
--- a/docs/man/man9/motion.9
+++ b/docs/man/man9/motion.9
@@ -154,8 +154,7 @@ Note: feed-inhibit applies to G-code commands -- not jogs.
.TP
\fBmotion.feed\-upm\fR OUT FLOAT
-Current feed rate in G-code program units per minute for motion.motion-type
-feed(2) and arc(3).
+Current feed rate in G-code program units per minute for motion.motion-type feed(2) and arc(3).
Value is the G-code program F value multiplied by the current feed override
value and the motion.adaptive-feed setting (if M52 active).
Value is zero if motion.feed-hold or motion.feed-inhibit are asserted.
@@ -167,35 +166,28 @@ be the last units used.
Current feed rate in inches per minute for motion.motion-type
feed(2) and arc(3).
Value is the inch equivalent of the G-code program F value multiplied by the
-current feed override value and the motion.adaptive-feed setting
-(if M52 active).
+current feed override value and the motion.adaptive-feed setting (if M52 active).
Value is zero if motion.feed-hold or motion.feed-inhibit are asserted.
.TP
\fBmotion.feed\-inches-per-second\fR OUT FLOAT
-Current feed rate in inches per second for motion.motion-type
-feed(2) and arc(3).
+Current feed rate in inches per second for motion.motion-type feed(2) and arc(3).
Value is the inch equivalent of the G-code program F value multiplied by the
-current feed override value and the motion.adaptive-feed setting
-(if M52 active).
+current feed override value and the motion.adaptive-feed setting (if M52 active).
Value is zero if motion.feed-hold or motion.feed-inhibit are asserted.
.TP
\fBmotion.feed\-mm-per-minute\fR OUT FLOAT
-Current feed rate in mm per minute for motion.motion-type
-feed(2) and arc(3).
+Current feed rate in mm per minute for motion.motion-type feed(2) and arc(3).
Value is the mm equivalent of the G-code program F value multiplied by the
-current feed override value and the motion.adaptive-feed setting
-(if M52 active).
+current feed override value and the motion.adaptive-feed setting (if M52 active).
Value is zero if motion.feed-hold or motion.feed-inhibit are asserted.
.TP
\fBmotion.feed\-mm-per-second\fR OUT FLOAT
-Current feed rate in mm per second for motion.motion-type
-feed(2) and arc(3).
+Current feed rate in mm per second for motion.motion-type feed(2) and arc(3).
Value is the mm equivalent of the G-code program F value multiplied by the
-current feed override value and the motion.adaptive-feed setting
-(if M52 active).
+current feed override value and the motion.adaptive-feed setting (if M52 active).
Value is zero if motion.feed-hold or motion.feed-inhibit are asserted.
.TP
@@ -210,8 +202,7 @@ TRUE if all active joints is homed.
.TP
\fBmotion.jog\-inhibit\fR IN BIT
-If this bit is TRUE, jogging of any joint or axis is disallowed and an error
-is reported.
+If this bit is TRUE, jogging of any joint or axis is disallowed and an error is reported.
.TP
\fBmotion.jog\-stop\fR IN BIT
@@ -236,14 +227,14 @@ the commanded position).
\fBmotion.misc\-error\-\fINN\fR IN BIT
Extra error inputs for faults such as over-temperature sensors, low coolant
warnings, custom HAL component errors. If driven TRUE this will disable a
-machine. Similar to spindle.amp-fault-in
+machine. Similar to spindle.amp-fault-in.
.TP
\fBmotion.motion\-enabled\fR OUT BIT
.TP
\fBmotion.motion\-type\fR OUT S32
-These values are from src/emc/nml_intf/motion_types.h
+These values are from src/emc/nml_intf/motion_types.h.
.RS
.RS
.TP
@@ -268,12 +259,12 @@ These values are from src/emc/nml_intf/motion_types.h
.TP
\fBmotion.probe\-input\fR IN BIT
-G38.n uses the value on this pin to determine when the probe has made contact. TRUE for probe contact closed (touching), FALSE for probe contact open.
+G38.n uses the value on this pin to determine when the probe has made contact.
+TRUE for probe contact closed (touching), FALSE for probe contact open.
.TP
\fBmotion.program\-line\fR OUT S32
-The current program line while executing. Zero if not running or between
-lines while single stepping.
+The current program line while executing. Zero if not running or between lines while single stepping.
.TP
\fBmotion.requested\-vel\fR OUT FLOAT
@@ -284,15 +275,16 @@ not reflect the feed override or any other adjustments.
.TP
\fBmotion.servo.last\-period\fR OUT U32
-The number of CPU clocks between invocations of the servo thread. Typically, this number divided by the CPU speed gives the time in seconds, and can be used to determine whether the realtime motion controller is meeting its timing constraints
+The number of CPU clocks between invocations of the servo thread.
+Typically, this number divided by the CPU speed gives the time in seconds,
+and can be used to determine whether the realtime motion controller is meeting its timing constraints
.TP
\fBmotion.switchkins-type\fR IN float
Kinematics modules that define the functions kinematicsSwitchable()
and kinematicsSwitch() receive the \fBinteger\fR value of this pin to
-select the machine kinematics functions. Extra G-code commands
-may be required to synchronize task and motion before and after changes
-to the pin value.
+select the machine kinematics functions.
+Extra G-code commands may be required to synchronize task and motion before and after changes to the pin value.
.TP
\fBmotion.teleop\-mode\fR OUT BIT
@@ -323,18 +315,15 @@ Clear external offset request
.TP
\fBaxis.\fIL\fB.eoffset-counts\fR IN S32
Counts input for external offset.
-The eoffset-counts are transferred to an internal
-register. The applied external offset is the
-product of the register counts and the eoffset-scale
-value. The register is \fBreset to zero at each machine
-startup\fR. If the machine is turned off with an external
-offset active, the eoffset-counts pin should be set
-to zero before restarting.
+The eoffset-counts are transferred to an internal register.
+The applied external offset is the product of the register counts and the eoffset-scale value.
+The register is \fBreset to zero at each machine startup\fR.
+If the machine is turned off with an external offset active,
+the eoffset-counts pin should be set to zero before restarting.
.TP
\fBaxis.\fIL\fB.eoffset-enable\fR IN BIT
-Enable for external offset (also requires INI file
-setting for [AXIS_L]OFFSET_AV_RATIO)
+Enable for external offset (also requires INI file setting for [AXIS_L]OFFSET_AV_RATIO)
.TP
\fBaxis.\fIL\fB.eoffset-request\fR OUT FLOAT
@@ -346,8 +335,8 @@ Scale for external offset.
.TP
\fBaxis.\fIL\fB.jog\-accel\-fraction\fR IN FLOAT
-Sets acceleration for wheel jogging to a fraction of the INI max_acceleration for
-the axis. Values greater than 1 or less than zero are ignored.
+Sets acceleration for wheel jogging to a fraction of the INI max_acceleration for the axis.
+Values greater than 1 or less than zero are ignored.
.TP
\fBaxis.\fIL\fB.jog\-counts\fR IN S32
@@ -363,7 +352,9 @@ Sets the distance moved for each count on "jog\-counts", in machine units.
.TP
\fBaxis.\fIL\fB.jog\-vel\-mode\fR IN BIT
-When FALSE (the default), the jogwheel operates in position mode. The axis will move exactly jog\-scale units for each count, regardless of how long that might take. When TRUE, the wheel operates in velocity mode - motion stops when the wheel stops, even if that means the commanded motion is not completed.
+When FALSE (the default), the jogwheel operates in position mode.
+The axis will move exactly jog\-scale units for each count, regardless of how long that might take.
+When TRUE, the wheel operates in velocity mode - motion stops when the wheel stops, even if that means the commanded motion is not completed.
.TP
\fBaxis.\fIL\fB.kb\-jog\-active\fR OUT BIT
@@ -371,22 +362,24 @@ When FALSE (the default), the jogwheel operates in position mode. The axis will
.TP
\fBaxis.\fIL\fB.pos\-cmd\fR OUT FLOAT
-The axis commanded position. There may be several offsets between the axis and motor coordinates: backlash compensation, screw error compensation, and home offsets. External offsets are reported separately (axis.\fBL\fR.eoffset).
+The axis commanded position.
+There may be several offsets between the axis and motor coordinates: backlash compensation, screw error compensation, and home offsets.
+External offsets are reported separately (axis.\fBL\fR.eoffset).
.TP
\fBaxis.\fIL\fB.teleop\-pos\-cmd\fR OUT FLOAT
.TP
\fBaxis.\fIL\fB.teleop\-tp\-enable\fR OUT BIT
-TRUE when the "teleop planner" is enabled for this axis
+TRUE when the "teleop planner" is enabled for this axis.
.TP
\fBaxis.\fIL\fB.teleop\-vel\-cmd\fR OUT FLOAT
-The axis's commanded velocity
+The axis's commanded velocity.
.TP
\fBaxis.\fIL\fB.teleop\-vel\-lim\fR OUT FLOAT
-The velocity limit for the teleop planner
+The velocity limit for the teleop planner.
.TP
\fBaxis.\fIL\fB.wheel\-jog\-active\fR OUT BIT
@@ -394,55 +387,54 @@ The velocity limit for the teleop planner
.SH JOINT PINS
\fBN\fR is the joint number (\fB0\fR ... \fBnum_joints\-1\fR))
.TP
-(\fBNote:\fR pins marked \fB(DEBUG)\fR serve as debugging aids
-and are subject to change or removal at any time.)
+(\fBNote:\fR pins marked \fB(DEBUG)\fR serve as debugging aids and are subject to change or removal at any time.)
.TP
\fBjoint.\fIN\fB.joint\-acc\-cmd\fR OUT FLOAT \fB(DEBUG)\fR
-The joint's commanded acceleration
+The joint's commanded acceleration.
.TP
\fBjoint.\fIN\fB.active\fR OUT BIT \fB(DEBUG)\fR
-TRUE when this joint is active
+TRUE when this joint is active.
.TP
\fBjoint.\fIN\fB.amp\-enable\-out\fR OUT BIT
-TRUE if the amplifier for this joint should be enabled
+TRUE if the amplifier for this joint should be enabled.
.TP
\fBjoint.\fIN\fB.amp\-fault\-in\fR IN BIT
-Should be driven TRUE if an external fault is detected with the amplifier for this joint
+Should be driven TRUE if an external fault is detected with the amplifier for this joint.
.TP
\fBjoint.\fIN\fB.backlash\-corr\fR OUT FLOAT \fB(DEBUG)\fR
-Backlash or screw compensation raw value
+Backlash or screw compensation raw value.
.TP
\fBjoint.\fIN\fB.backlash\-filt\fR OUT FLOAT \fB(DEBUG)\fR
-Backlash or screw compensation filtered value (respecting motion limits)
+Backlash or screw compensation filtered value (respecting motion limits).
.TP
\fBjoint.\fIN\fB.backlash\-vel\fR OUT FLOAT \fB(DEBUG)\fR
-Backlash or screw compensation velocity
+Backlash or screw compensation velocity.
.TP
\fBjoint.\fIN\fB.coarse\-pos\-cmd\fR OUT FLOAT \fB(DEBUG)\fR
.TP
\fBjoint.\fIN\fB.error\fR OUT BIT \fB(DEBUG)\fR
-TRUE when this joint has encountered an error, such as a limit switch closing
+TRUE when this joint has encountered an error, such as a limit switch closing.
.TP
\fBjoint.\fIN\fB.f\-error\fR OUT FLOAT \fB(DEBUG)\fR
-The actual following error
+The actual following error.
.TP
\fBjoint.\fIN\fB.f\-error\-lim\fR OUT FLOAT \fB(DEBUG)\fR
-The following error limit
+The following error limit.
.TP
\fBjoint.\fIN\fB.f\-errored\fR OUT BIT \fB(DEBUG)\fR
-TRUE when this joint has exceeded the following error limit
+TRUE when this joint has exceeded the following error limit.
.TP
\fBjoint.\fIN\fB.faulted\fR OUT BIT \fB(DEBUG)\fR
@@ -453,11 +445,11 @@ The "free planner" commanded position for this joint.
.TP
\fBjoint.\fIN\fB.free\-tp\-enable\fR OUT BIT \fB(DEBUG)\fR
-TRUE when the "free planner" is enabled for this joint
+TRUE when the "free planner" is enabled for this joint.
.TP
\fBjoint.\fIN\fB.free\-vel\-lim\fR OUT FLOAT \fB(DEBUG)\fR
-The velocity limit for the free planner
+The velocity limit for the free planner.
.TP
\fBjoint.\fIN\fB.home\-state\fR OUT S32 \fB(DEBUG)\fR
@@ -465,23 +457,23 @@ homing state machine state
.TP
\fBjoint.\fIN\fB.home\-sw\-in\fR IN BIT
-Should be driven TRUE if the home switch for this joint is closed
+Should be driven TRUE if the home switch for this joint is closed.
.TP
\fBjoint.\fIN\fB.homed\fR OUT BIT \fB(DEBUG)\fR
-TRUE if the joint has been homed
+TRUE if the joint has been homed.
.TP
\fBjoint.\fIN\fB.homing\fR OUT BIT
-TRUE if the joint is currently homing
+TRUE if the joint is currently homing.
.TP
\fBjoint.\fIN\fB.in\-position\fR OUT BIT \fB(DEBUG)\fR
-TRUE if the joint is using the "free planner" and has come to a stop
+TRUE if the joint is using the "free planner" and has come to a stop.
.TP
\fBjoint.\fIN\fB.index\-enable\fR IO BIT
-Should be attached to the index\-enable pin of the joint's encoder to enable homing to index pulse
+Should be attached to the index\-enable pin of the joint's encoder to enable homing to index pulse.
.br
.ns
@@ -491,8 +483,8 @@ Indicates joint is unlocked (see JOINT UNLOCK PINS).
.TP
\fBjoint.\fIN\fB.jog\-accel\-fraction\fR IN FLOAT
-Sets acceleration for wheel jogging to a fraction of the INI max_acceleration for
-the joint. Values greater than 1 or less than zero are ignored.
+Sets acceleration for wheel jogging to a fraction of the INI max_acceleration for the joint.
+Values greater than 1 or less than zero are ignored.
.TP
\fBjoint.\fIN\fB.jog\-counts\fR IN S32
@@ -508,7 +500,9 @@ Sets the distance moved for each count on "jog\-counts", in machine units.
.TP
\fBjoint.\fIN\fB.jog\-vel\-mode\fR IN BIT
-When FALSE (the default), the jogwheel operates in position mode. The joint will move exactly jog\-scale units for each count, regardless of how long that might take. When TRUE, the wheel operates in velocity mode - motion stops when the wheel stops, even if that means the commanded motion is not completed.
+When FALSE (the default), the jogwheel operates in position mode.
+The joint will move exactly jog\-scale units for each count, regardless of how long that might take.
+When TRUE, the wheel operates in velocity mode - motion stops when the wheel stops, even if that means the commanded motion is not completed.
.TP
\fBjoint.\fIN\fB.kb\-jog\-active\fR OUT BIT \fB(DEBUG)\fR
@@ -536,15 +530,18 @@ Should be driven TRUE if the negative limit switch for this joint is tripped.
.TP
\fBjoint.\fIN\fB.pos\-cmd\fR OUT FLOAT
-The joint (as opposed to motor) commanded position. There may be several offsets between the joint and motor coordinates: backlash compensation, screw error compensation, and home offsets.
+The joint (as opposed to motor) commanded position.
+There may be several offsets between the joint and motor coordinates: backlash compensation, screw error compensation, and home offsets.
.TP
\fBjoint.\fIN\fB.pos\-fb\fR OUT FLOAT
-The joint feedback position. This value is computed from the actual motor position minus joint offsets. Useful for machine visualization.
+The joint feedback position.
+This value is computed from the actual motor position minus joint offsets.
+Useful for machine visualization.
.TP
\fBjoint.\fIN\fB.pos\-hard\-limit\fR OUT BIT \fB(DEBUG)\fR
-The positive hard limit for the joint
+The positive hard limit for the joint.
.TP
\fBjoint.\fIN\fB.pos\-lim\-sw\-in\fR IN BIT
@@ -552,8 +549,7 @@ Should be driven TRUE if the positive limit switch for this joint is tripped.
.TP
\fBjoint.\fIN\fB.unlock\fR OUT BIT
-TRUE if the axis is a locked joint (typically a rotary) and a move
-is commanded (see JOINT UNLOCK PINS).
+TRUE if the axis is a locked joint (typically a rotary) and a move is commanded (see JOINT UNLOCK PINS).
.TP
\fBjoint.\fIN\fB.joint\-vel\-cmd\fR OUT FLOAT \fB(DEBUG)\fR
@@ -563,15 +559,14 @@ The joint's commanded velocity
\fBjoint.\fIN\fB.wheel\-jog\-active\fR OUT BIT \fB(DEBUG)\fR
.SH JOINT posthome pins
-Each joint designated as an 'extra' joint is provided with a HAL pin
-\fBjoint.N.posthome-cmd\fR. The pin value is ignored prior to homing.
-After homing, the pin value is augmented by the motor offset value
-and routed to the \fBjoint.N.motor-pos-cmd\fR.
+Each joint designated as an 'extra' joint is provided with a HAL pin \fBjoint.N.posthome-cmd\fR.
+The pin value is ignored prior to homing.
+After homing, the pin value is augmented by the motor offset value and routed to the \fBjoint.N.motor-pos-cmd\fR.
.SH JOINT unlock pins
-The joint pins used for unlocking a joint
-(\fBjoint.N.unlock\fR, \fBjoint.N.is-unlocked\fR),
-are created according to the \fBunlock_joints_mask=\fRjointmask parameter for motmod. These pins may be required for locking indexers (typically a rotary joint)
+The joint pins used for unlocking a joint (\fBjoint.N.unlock\fR, \fBjoint.N.is-unlocked\fR),
+are created according to the \fBunlock_joints_mask=\fRjointmask parameter for motmod.
+These pins may be required for locking indexers (typically a rotary joint)
The jointmask bits are: (lsb)0:joint0, 1:joint1, 2:joint2, ...
@@ -585,21 +580,22 @@ Example: loadrt motmod ... \fBunlock_joints_mask=\fR0x38 creates unlock pins for
.TP
\fBspindle.M\fB.amp\-fault\-in\fR IN BIT
-Should be driven TRUE if an external fault is detected with the amplifier for this spindle
+Should be driven TRUE if an external fault is detected with the amplifier for this spindle.
.TP
\fBspindle.M.at\-speed\fR IN BIT
-Motion will pause until this pin is TRUE, under the following conditions: before the
-first feed move after each spindle start or speed change; before the start of every
-chain of spindle\-synchronized moves; and if in CSS mode, at every rapid\->feed transition.
+Motion will pause until this pin is TRUE, under the following conditions:
+before the first feed move after each spindle start or speed change;
+before the start of every chain of spindle\-synchronized moves;
+and if in CSS mode, at every rapid\->feed transition.
.TP
\fBspindle.M.brake\fR OUT BIT
-TRUE when the spindle brake should be applied
+TRUE when the spindle brake should be applied.
.TP
\fBspindle.M.forward\fR OUT BIT
-TRUE when the spindle should rotate forward
+TRUE when the spindle should rotate forward.
.TP
\fBspindle.M.index\-enable\fR I/O BIT
@@ -611,8 +607,10 @@ When TRUE, the spindle speed is set and held to 0.
.TP
\fBspindle.M.is\-oriented\fR IN BIT
-Acknowledge pin for spindle\-orient. Completes orient cycle. If spindle\-orient was true when spindle\-is\-oriented
-was asserted, the spindle\-orient pin is cleared and the spindle\-locked pin is asserted. Also, the spindle\-brake pin is asserted.
+Acknowledge pin for spindle\-orient. Completes orient cycle.
+If spindle\-orient was true when spindle\-is\-oriented was asserted,
+the spindle\-orient pin is cleared and the spindle\-locked pin is asserted.
+Also, the spindle\-brake pin is asserted.
.TP
\fBspindle.M.locked\fR OUT BIT
@@ -620,7 +618,7 @@ Spindle orient complete pin. Cleared by any of M3,M4,M5.
.TP
\fBspindle.M.on\fR OUT BIT
-TRUE when spindle should rotate
+TRUE when spindle should rotate.
.TP
\fBspindle.M.orient\fR OUT BIT
@@ -642,7 +640,7 @@ Desired spindle rotation mode. Reflects M19 P parameter word.
.TP
\fBspindle.M.reverse\fR OUT BIT
-TRUE when the spindle should rotate backward
+TRUE when the spindle should rotate backward.
.TP
\fBspindle.M.revs\fR IN FLOAT
@@ -650,7 +648,7 @@ For correct operation of spindle synchronized moves, this signal must be hooked
.TP
\fBspindle.M.speed\-cmd\-rps\fR FLOAT OUT
-Commanded spindle speed in units of revolutions per second
+Commanded spindle speed in units of revolutions per second.
.TP
\fBspindle.M.speed\-in\fR IN FLOAT
@@ -658,7 +656,7 @@ Actual spindle speed feedback in revolutions per second; used for G96 (constant
.TP
\fBspindle.M.speed\-out\fR OUT FLOAT
-Desired spindle speed in rotations per minute
+Desired spindle speed in rotations per minute.
.TP
\fBspindle.M.speed\-out\-abs\fR OUT FLOAT
@@ -666,7 +664,7 @@ Desired spindle speed in rotations per minute, always positive regardless of spi
.TP
\fBspindle.M.speed\-out\-rps\fR OUT FLOAT
-Desired spindle speed in rotations per second
+Desired spindle speed in rotations per second.
.TP
\fBspindle.M.speed\-out\-rps\-abs\fR OUT FLOAT
@@ -680,7 +678,7 @@ Many of the parameters serve as debugging aids, and are subject to change or rem
.ns
.TP
\fBmotion\-command\-handler.tmax\fR RW S32
-Show information about the execution time of these HAL functions in CPU clocks
+Show information about the execution time of these HAL functions in CPU clocks.
.br
.ns
@@ -691,7 +689,7 @@ Show information about the execution time of these HAL functions in CPU clocks
.ns
.TP
\fBmotion\-controller.tmax\fR RW S32
-Show information about the execution time of these HAL functions in CPU clocks
+Show information about the execution time of these HAL functions in CPU clocks.
.br
.ns
@@ -710,15 +708,13 @@ Generally, these functions are both added to the servo-thread in the order shown
\fBmotion\-command\-handler\fR
Processes motion commands coming from user space.
The pin named \fBmotion-command-handler.time\fR and parameters
-\fBmotion-command-handler.tmax,tmax-increased\fRare created for
-this function.
+\fBmotion-command-handler.tmax,tmax-increased\fRare created for this function.
.TP
\fBmotion\-controller\fR
-Runs the LinuxCNC motion controller
+Runs the LinuxCNC motion controller.
The pin named \fBmotion-controller.time\fR and parameters
-\fBmotion-controller.tmax,tmax-increased\fR are created for
-this function.
+\fBmotion-controller.tmax,tmax-increased\fR are created for this function.
.SH BUGS
This manual page is incomplete.
diff --git a/docs/man/man9/mux_generic.9 b/docs/man/man9/mux_generic.9
index 98e646298f..6e3c1dccb0 100644
--- a/docs/man/man9/mux_generic.9
+++ b/docs/man/man9/mux_generic.9
@@ -49,8 +49,7 @@ The possible output values that are selected by the selection pins.
.SH PARAMETERS
.TP
.B mux\-gen.\fIN\fB.elapsed\fR float r \fR
-Current value of the internal debounce timer
-for debugging.
+Current value of the internal debounce timer for debugging.
.TP
.B mux\-gen.\fIN\fB.selected\fR s32 r \fR
Current value of the internal selection variable after conversion for debugging.
@@ -60,24 +59,22 @@ Possibly useful for setting up gray-code switches.
This component is a more general version of the other multiplexing components.
It allows the creation of arbitrary-size multiplexers (up to 1024 entries) and
also supports differing data types on the input and output pins.
-The configuration string is a comma-separated list of code-letters and numbers,
-such as "bb4,fu12" This would create a 4-element bit-to-bit mux and a
-12-element float-to-unsigned mux. The code letters are b = bit, f = float, s =
-signed integer, u = unsigned integer. The first letter code is the input type,
-the second is the output type. The codes are not case-sensitive. The order of
-the letters is significant but the position in the string is not. Do not
-insert any spaces in the config string.
-Any non-zero float value will be converted to a "true" output in bit form. Be
-wary that float datatypes can be very, very, close to zero and not actually be
-equal to zero.
+The configuration string is a comma-separated list of code-letters and numbers, such as "bb4,fu12".
+ This would create a 4-element bit-to-bit mux and a 12-element float-to-unsigned mux.
+The code letters are b = bit, f = float, s = signed integer, u = unsigned integer.
+The first letter code is the input type, the second is the output type.
+The codes are not case-sensitive. The order of the letters is significant but the position in the string is not.
+Do not insert any spaces in the config string.
+Any non-zero float value will be converted to a "true" output in bit form.
+Be wary that float datatypes can be very, very, close to zero and not actually be equal to zero.
Each mux has its own HAL function and must be added to a thread separately.
-If neither input nor output is of type float then the function is base-thread
-(non floating-point) safe. Any mux_generic with a floating point input or
-output can only be added to a floating-point thread.
+If neither input nor output is of type float then the function is base-thread (non floating-point) safe.
+Any mux_generic with a floating point input or output can only be added to a floating-point thread.
+
+.SH AUTHOR
+Andy Pugh
.SH LICENSE
GPL
-.SH AUTHOR
-Andy Pugh
diff --git a/docs/man/man9/opto_ac5.9 b/docs/man/man9/opto_ac5.9
index cfda5f047b..dae78fec20 100644
--- a/docs/man/man9/opto_ac5.9
+++ b/docs/man/man9/opto_ac5.9
@@ -49,8 +49,7 @@ Turns one of the on board LEDS on/off. LEDS are numbered 0 to 3.
.SH PARAMETERS
.TP
\fBopto_ac5.[\fIBOARDNUMBER\fB\fR].\fBport[\fIPORTNUMBER\fB\fR].\fBout\-[\fIPINNUMBER\fB\fR]\-invert W bit
-When TRUE, invert the meaning of the corresponding \fB\-out\fR pin so that TRUE
-gives LOW and FALSE gives HIGH.
+When TRUE, invert the meaning of the corresponding \fB\-out\fR pin so that TRUE gives LOW and FALSE gives HIGH.
.SH FUNCTIONS
diff --git a/docs/man/man9/pid.9 b/docs/man/man9/pid.9
index 46a3a0a928..792673647b 100644
--- a/docs/man/man9/pid.9
+++ b/docs/man/man9/pid.9
@@ -7,45 +7,38 @@ pid \- proportional/integral/derivative controller with automatic tuning support
.SH DESCRIPTION
\fBpid\fR is a classic Proportional/Integral/Derivative controller,
-used to control position or speed feedback loops for servo motors and
-other closed-loop applications.
+used to control position or speed feedback loops for servo motors and other closed-loop applications.
.P
-\fBpid\fR supports a maximum of sixteen controllers. The number that
-are actually loaded is set by the \fBnum_chan\fR argument when
-the module is loaded. Alternatively, specify names= and unique names
-separated by commas.
+\fBpid\fR supports a maximum of sixteen controllers.
+The number that are actually loaded is set by the \fBnum_chan\fR argument when the module is loaded.
+Alternatively, specify names= and unique names separated by commas.
.P
The \fBnum_chan=\fR and \fBnames=\fR specifiers are mutually exclusive.
-If neither \fBnum_chan=\fR nor \fBnames=\fR are specified, the default
-value is three. If \fBdebug\fR is set to 1 (the default is 0), some
-additional HAL parameters will be exported, which might be useful
-for tuning, but are otherwise unnecessary.
+If neither \fBnum_chan=\fR nor \fBnames=\fR are specified, the default value is three.
+If \fBdebug\fR is set to 1 (the default is 0), some additional HAL parameters will be exported,
+which might be useful for tuning, but are otherwise unnecessary.
.P
-In the following description, it is assumed that we are discussing
-position loops. However this component can be used to implement other
-loops such as speed loops, torch height control, and others.
+In the following description, it is assumed that we are discussing position loops.
+However this component can be used to implement other loops such as speed loops, torch height control, and others.
.P
-Each loop has a number of pins and parameters, whose names begin
-with 'pid.N.', where 'N' is the channel number. Channel numbers start
-at zero.
+Each loop has a number of pins and parameters, whose names begin with 'pid.N.', where 'N' is the channel number.
+Channel numbers start at zero.
.P
The three most important pins are 'command', 'feedback', and 'output'.
For a position loop, 'command' and 'feedback' are in position units.
-For a linear axis, this could be inches, mm, metres, or whatever is
-relevant. Likewise, for a angular axis, it could be degrees, radians,
-etc. The units of the 'output' pin represent the change needed to
-make the feedback match the command. As such, for a position
-loop 'Output' is a velocity, in inches/sec, mm/sec, degrees/sec, etc.
-.P
-Each loop has several other pins as well. 'error' is equal
-to 'command' minus 'feedback'. 'enable' is a bit that enables the
-loop. If 'enable' is false, all integrators are reset, and the output
-is forced to zero. If 'enable' is true, the loop operates normally.
-.P
-The PID gains, limits, and other 'tunable' features of the loop are
-implemented as parameters. These are as follows:
+For a linear axis, this could be inches, mm, metres, or whatever is relevant.
+Likewise, for a angular axis, it could be degrees, radians, etc.
+The units of the 'output' pin represent the change needed to make the feedback match the command.
+As such, for a position loop 'output' is a velocity, in inches/sec, mm/sec, degrees/sec, etc.
+.P
+Each loop has several other pins as well. 'error' is equal to 'command' minus 'feedback'. 'enable' is a bit that enables the loop.
+If 'enable' is false, all integrators are reset, and the output is forced to zero.
+If 'enable' is true, the loop operates normally.
+.P
+The PID gains, limits, and other 'tunable' features of the loop are implemented as parameters.
+These are as follows:
.PP
\fBPgain\fR Proportional gain
@@ -110,13 +103,10 @@ implemented as parameters. These are as follows:
.PD
\fBmaxoutput\fR Limit on output value
.P
-All of the limits (max____) are implemented such that if the parameter
-value is zero, there is no limit.
+All of the limits (max____) are implemented such that if the parameter value is zero, there is no limit.
.P
-A number of internal values which may be useful for testing and tuning
-are also available as parameters. To avoid cluttering the parameter
-list, these are only exported if "debug=1" is specified on the insmod
-command line.
+A number of internal values which may be useful for testing and tuning are also available as parameters.
+To avoid cluttering the parameter list, these are only exported if "debug=1" is specified on the insmod command line.
.PP
\fBerrorI\fR Integral of error
@@ -138,8 +128,7 @@ command line.
\fBcommandDDD\fR 3rd derivative of the command
.P
-The PID loop calculations are as follows (see the code in pid.c for
-all the nitty gritty details):
+The PID loop calculations are as follows (see the code in pid.c for all the nitty gritty details):
.IP
.nf
error = command - feedback
@@ -162,39 +151,30 @@ limit output to +/- maxoutput
.fi
.P
-This component has a built in auto tune mode. It works by setting up a
-limit cycle to characterize the process. This is called the Relay
-method and described in the 1984 Automation paper \fBAutomatic Tuning
-of Simple Regulators with Specifications on Phase and Amplitude
-Margins\fR by Karl Johan Åström and Tore Hägglund
-(doi:10.1016/0005-1098(84)90014-1),
-https://lup.lub.lu.se/search/ws/files/6340936/8509157.pdf. Using this
-method, \fBPgain/Igain/Dgain\fR or \fBPgain/Igain/FF1\fR can be
-determined using the Ziegler-Nichols algorithm. When using \fBFF1\fR
-tuning, scaling must be set so that \fBoutput\fR is in user units per
-second.
+This component has a built in auto tune mode. It works by setting up a limit cycle to characterize the process.
+This is called the Relay method and described in the 1984 Automation paper
+\fBAutomatic Tuning of Simple Regulators with Specifications on Phase and Amplitude Margins\fR by Karl Johan Åström and Tore Hägglund (doi:10.1016/0005-1098(84)90014-1),
+https://lup.lub.lu.se/search/ws/files/6340936/8509157.pdf.
+Using this method, \fBPgain/Igain/Dgain\fR or \fBPgain/Igain/FF1\fR can be determined using the Ziegler-Nichols algorithm.
+When using \fBFF1\fR tuning, scaling must be set so that \fBoutput\fR is in user units per second.
.P
-During auto tuning, the \fBcommand\fR input should not change. The
-limit cycle is setup around the commanded position. No initial tuning
-values are required to start auto tuning. Only \fBtune\-cycles\fR,
-\fBtune\-effort\fR and \fBtune\-mode\fR need be set before starting
-auto tuning. Note that setting \fBtune\-mode\fR to true disable the
-control loop. When auto tuning completes, the tuning parameters will
-be set, the output set to bias and the controller still be
-disabled. If running from LinuxCNC, the FERROR setting for the axis
-being tuned may need to be loosened up as it must be larger than the
-limit cycle amplitude in order to avoid a following error.
-.P
-To perform auto tuning, take the following steps. Move the axis to be
-tuned somewhere near the center of it's travel. Set
-\fBtune\-cycles\fR (the default value should be fine in most cases)
-and \fBtune\-mode\fR. Set \fBtune\-effort\fR to a small value. Set
-\fBenable\fR to true. Set \fBtune\-mode\fR to true. Set
-\fBtune\-start\fR to true. If no oscillation occurs, or the
-oscillation is too small, slowly increase \fBtune\-effort\fR. Auto
-tuning can be aborted at any time by setting \fBenable\fR or
-\fBtune\-mode\fR to false.
+During auto tuning, the \fBcommand\fR input should not change.
+The limit cycle is setup around the commanded position.
+No initial tuning values are required to start auto tuning.
+Only \fBtune\-cycles\fR, \fBtune\-effort\fR and \fBtune\-mode\fR need be set before starting auto tuning.
+Note that setting \fBtune\-mode\fR to true disable the control loop.
+When auto tuning completes, the tuning parameters will be set, the output set to bias and the controller still be disabled.
+If running from LinuxCNC, the FERROR setting for the axis being tuned may need to be loosened up, as it must be larger than the limit cycle amplitude in order to avoid a following error.
+.P
+To perform auto tuning, take the following steps.
+Move the axis to be tuned somewhere near the center of it's travel.
+Set \fBtune\-cycles\fR (the default value should be fine in most cases) and \fBtune\-mode\fR.
+Set \fBtune\-effort\fR to a small value. Set \fBenable\fR to true. Set \fBtune\-mode\fR to true.
+Set \fBtune\-start\fR to true. If no oscillation occurs, or the oscillation is too small, slowly increase \fBtune\-effort\fR.
+Set \fBtune\-start\fR to true.
+If no oscillation occurs, or the oscillation is too small, slowly increase \fBtune\-effort\fR
+Auto tuning can be aborted at any time by setting \fBenable\fR or \fBtune\-mode\fR to false.
.SH NAMING
The names for pins, parameters, and functions are prefixed as:
@@ -215,21 +195,16 @@ Does the PID calculations for control loop \fIN\fR.
The desired (commanded) value for the control loop.
.TP
\fBpid.\fIN\fB.Pgain\fR float in
-Proportional gain. Results in a contribution to the output that is the error
-multiplied by \fBPgain\fR.
+Proportional gain. Results in a contribution to the output that is the error multiplied by \fBPgain\fR.
.TP
\fBpid.\fIN\fB.Igain\fR float in
-Integral gain. Results in a contribution to the output that is the integral
-of the error multiplied by \fBIgain\fR. For example an error of 0.02 that
-lasted 10 seconds would result in an integrated error (\fBerrorI\fR) of 0.2,
-and if \fBIgain\fR is 20, the integral term would add 4.0 to the output.
+Integral gain. Results in a contribution to the output that is the integral of the error multiplied by \fBIgain\fR.
+For example an error of 0.02 that lasted 10 seconds would result in an integrated error (\fBerrorI\fR) of 0.2, and if \fBIgain\fR is 20, the integral term would add 4.0 to the output.
.TP
\fBpid.\fIN\fB.Dgain\fR float in
-Derivative gain. Results in a contribution to the output that is the rate of
-change (derivative) of the error multiplied by \fBDgain\fR. For example an
-error that changed from 0.02 to 0.03 over 0.2 seconds would result in an error
-derivative (\fBerrorD\fR) of of 0.05, and if \fBDgain\fR is 5, the derivative
-term would add 0.25 to the output.
+Derivative gain. Results in a contribution to the output that is the rate of change (derivative) of the error multiplied by \fBDgain\fR.
+For example an error that changed from 0.02 to 0.03 over 0.2 seconds would result in an error derivative (\fBerrorD\fR) of of 0.05, and if \fBDgain\fR is 5,
+the derivative term would add 0.25 to the output.
.TP
\fBpid.\fIN\fB.feedback\fR float in
The actual (feedback) value, from some sensor such as an encoder.
@@ -238,128 +213,102 @@ The actual (feedback) value, from some sensor such as an encoder.
The output of the PID loop, which goes to some actuator such as a motor.
.TP
\fBpid.\fIN\fB.command\-deriv\fR float in
-The derivative of the desired (commanded) value for the control loop. If no
-signal is connected then the derivative will be estimated numerically.
+The derivative of the desired (commanded) value for the control loop. If no signal is connected then the derivative will be estimated numerically.
.TP
\fBpid.\fIN\fB.feedback\-deriv\fR float in
-The derivative of the actual (feedback) value for the control loop. If no
-signal is connected then the derivative will be estimated numerically. When
-the feedback is from a quantized position source (e.g., encoder feedback
-position), behavior of the D term can be improved by using a better velocity
-estimate here, such as the velocity output of encoder(9) or hostmot2(9).
+The derivative of the actual (feedback) value for the control loop.
+If no signal is connected then the derivative will be estimated numerically.
+When the feedback is from a quantized position source (e.g., encoder feedback position),
+behavior of the D term can be improved by using a better velocity estimate here, such as the velocity output of encoder(9) or hostmot2(9).
.TP
\fBpid.\fIN\fB.error\-previous\-target\fR bit in
-Use previous invocation's target vs. current position for error calculation,
-like the motion controller expects. This may make torque-mode position loops
-and loops requiring a large I gain easier to tune, by eliminating
-velocity\-dependent following error.
+Use previous invocation's target vs. current position for error calculation, like the motion controller expects.
+This may make torque-mode position loops and loops requiring a large I gain easier to tune, by eliminating velocity\-dependent following error.
.TP
\fBpid.\fIN\fB.error\fR float out
The difference between command and feedback.
.TP
\fBpid.\fIN\fB.enable\fR bit in
-When true, enables the PID calculations. When false, \fBoutput\fR is zero,
-and all internal integrators, etc, are reset.
+When true, enables the PID calculations. When false, \fBoutput\fR is zero, and all internal integrators, etc, are reset.
.TP
\fBpid.\fIN\fB.index\-enable\fR bit in
-On the falling edge of \fBindex\-enable\fR, pid does not update the
-internal command derivative estimate. On systems which use the encoder
-index pulse, this pin should be connected to the index\-enable signal.
-When this is not done, and FF1 is nonzero, a step change in the input
-command causes a single-cycle spike in the PID output. On systems which use
-exactly one of the \fB\-deriv\fR inputs, this affects the D term as well.
+On the falling edge of \fBindex\-enable\fR, pid does not update the internal command derivative estimate.
+On systems which use the encoder index pulse, this pin should be connected to the index\-enable signal.
+When this is not done, and FF1 is nonzero, a step change in the input command causes a single-cycle spike in the PID output.
+On systems which use exactly one of the \fB\-deriv\fR inputs, this affects the D term as well.
.TP
\fBpid.\fIN\fB.bias\fR float in
-\fBbias\fR is a constant amount that is added to the output. In most cases
-it should be left at zero. However, it can sometimes be useful to compensate
-for offsets in servo amplifiers, or to balance the weight of an object that
-moves vertically. \fBbias\fR is turned off when the PID loop is disabled,
-just like all other components of the output. If a non-zero output is needed
-even when the PID loop is disabled, it should be added with an external HAL
-sum2 block.
+\fBbias\fR is a constant amount that is added to the output. In most cases it should be left at zero.
+However, it can sometimes be useful to compensate for offsets in servo amplifiers, or to balance the weight of an object that moves vertically.
+\fBbias\fR is turned off when the PID loop is disabled, just like all other components of the output.
+If a non-zero output is needed even when the PID loop is disabled, it should be added with an external HAL sum2 block.
.TP
\fBpid.\fIN\fB.FF0\fR float in
-Zero order feed-forward term. Produces a contribution to the output that is
-\fBFF0\fR multiplied by the commanded value. For position loops, it should
-usually be left at zero. For velocity loops, \fBFF0\fR can compensate for
-friction or motor counter-EMF and may permit better tuning if used properly.
+Zero order feed-forward term.
+Produces a contribution to the output that is \fBFF0\fR multiplied by the commanded value.
+For position loops, it should usually be left at zero.
+For velocity loops, \fBFF0\fR can compensate for friction or motor counter-EMF and may permit better tuning if used properly.
.TP
\fBpid.\fIN\fB.FF1\fR float in
-First order feed-forward term. Produces a contribution to the output that
-is \fBFF1\fR multiplied by the derivative of the commanded value. For
-position loops, the contribution is proportional to speed, and can be used
-to compensate for friction or motor CEMF. For velocity loops, it is
-proportional to acceleration and can compensate for inertia. In both
-cases, it can result in better tuning if used properly.
+First order feed-forward term.
+Produces a contribution to the output that is \fBFF1\fR multiplied by the derivative of the commanded value.
+For position loops, the contribution is proportional to speed, and can be used to compensate for friction or motor CEMF.
+For velocity loops, it is proportional to acceleration and can compensate for inertia.
+In both cases, it can result in better tuning if used properly.
.TP
\fBpid.\fIN\fB.FF2\fR float in
-Second order feed-forward term. Produces a contribution to the output that is
-\fBFF2\fR multiplied by the second derivative of the commanded value. For
-position loops, the contribution is proportional to acceleration, and can be
-used to compensate for inertia. For velocity loops, the contribution is
-proportional to jerk, and should usually be left at zero.
+Second order feed-forward term.
+Produces a contribution to the output that is \fBFF2\fR multiplied by the second derivative of the commanded value.
+For position loops, the contribution is proportional to acceleration, and can be used to compensate for inertia.
+For velocity loops, the contribution is proportional to jerk, and should usually be left at zero.
.TP
\fBpid.\fIN\fB.FF3\fR float in
-Third order feed-forward term. Produces a contribution to the output that is
-\fBFF3\fR multiplied by the third derivative of the commanded value. For
-position loops, the contribution is proportional to jerk, and can be
-used to compensate for residual errors during acceleration. For velocity
-loops, the contribution is proportional to snap(jounce), and should usually
-be left at zero.
+Third order feed-forward term.
+Produces a contribution to the output that is \fBFF3\fR multiplied by the third derivative of the commanded value.
+For position loops, the contribution is proportional to jerk, and can be used to compensate for residual errors during acceleration.
+For velocity loops, the contribution is proportional to snap(jounce), and should usually be left at zero.
.TP
\fBpid.\fIN\fB.deadband\fR float in
-Defines a range of "acceptable" error. If the absolute value of \fBerror\fR
-is less than \fBdeadband\fR, it will be treated as if the error is zero.
+Defines a range of "acceptable" error.
+If the absolute value of \fBerror\fR is less than \fBdeadband\fR, it will be treated as if the error is zero.
When using feedback devices such as encoders that are inherently quantized,
-the deadband should be set slightly more than one-half count, to prevent
-the control loop from hunting back and forth if the command is between two
-adjacent encoder values. When the absolute value of the error is greater
-than the deadband, the deadband value is subtracted from the error before
-performing the loop calculations, to prevent a step in the transfer function
-at the edge of the deadband. (See \fBBUGS\fR.)
+the deadband should be set slightly more than one-half count,
+to prevent the control loop from hunting back and forth if the command is between two adjacent encoder values.
+When the absolute value of the error is greater than the deadband,
+the deadband value is subtracted from the error before performing the loop calculations,
+to prevent a step in the transfer function at the edge of the deadband (see \fBBUGS\fR).
.TP
\fBpid.\fIN\fB.maxoutput\fR float in
-Output limit. The absolute value of the output will not be permitted
-to exceed \fBmaxoutput\fR, unless \fBmaxoutput\fR is zero. When the output
-is limited, the error integrator will hold instead of integrating, to prevent
-windup and overshoot.
+Output limit. The absolute value of the output will not be permitted to exceed \fBmaxoutput\fR, unless \fBmaxoutput\fR is zero.
+When the output is limited, the error integrator will hold instead of integrating, to prevent windup and overshoot.
.TP
\fBpid.\fIN\fB.maxerror\fR float in
-Limit on the internal error variable used for P, I, and D. Can be used to
-prevent high \fBPgain\fR values from generating large outputs under conditions
-when the error is large (for example, when the command makes a step change).
+Limit on the internal error variable used for P, I, and D.
+Can be used to prevent high \fBPgain\fR values from generating large outputs under conditions when the error is large (for example, when the command makes a step change).
Not normally needed, but can be useful when tuning non-linear systems.
.TP
\fBpid.\fIN\fB.maxerrorD\fR float in
Limit on the error derivative. The rate of change of error used by the
-\fBDgain\fR term will be limited to this value, unless the value is
-zero. Can be used to limit the effect of \fBDgain\fR and prevent large
-output spikes due to steps on the command and/or feedback. Not normally
-needed.
+\fBDgain\fR term will be limited to this value, unless the value is zero.
+Can be used to limit the effect of \fBDgain\fR and prevent large output spikes due to steps on the command and/or feedback.
+Not normally needed.
.TP
\fBpid.\fIN\fB.maxerrorI\fR float in
-Limit on error integrator. The error integrator used by the \fBIgain\fR
-term will be limited to this value, unless it is zero. Can be used to prevent
-integrator windup and the resulting overshoot during/after sustained errors.
+Limit on error integrator. The error integrator used by the \fBIgain\fR term will be limited to this value, unless it is zero.
+Can be used to prevent integrator windup and the resulting overshoot during/after sustained errors.
Not normally needed.
.TP
\fBpid.\fIN\fB.maxcmdD\fR float in
-Limit on command derivative. The command derivative used by \fBFF1\fR will
-be limited to this value, unless the value is zero. Can be used to prevent
-\fBFF1\fR from producing large output spikes if there is a step change on the
-command. Not normally needed.
+Limit on command derivative. The command derivative used by \fBFF1\fR will be limited to this value, unless the value is zero.
+Can be used to prevent \fBFF1\fR from producing large output spikes if there is a step change on the command. Not normally needed.
.TP
\fBpid.\fIN\fB.maxcmdDD\fR float in
-Limit on command second derivative. The command second derivative used by
-\fBFF2\fR will be limited to this value, unless the value is zero. Can be
-used to prevent \fBFF2\fR from producing large output spikes if there is a
-step change on the command. Not normally needed.
+Limit on command second derivative. The command second derivative used by \fBFF2\fR will be limited to this value, unless the value is zero.
+Can be used to prevent \fBFF2\fR from producing large output spikes if there is a step change on the command. Not normally needed.
.TP
\fBpid.\fIN\fB.maxcmdDDD\fR float in
-Limit on command third derivative. The command third derivative used by
-\fBFF3\fR will be limited to this value, unless the value is zero. Can be
-used to prevent \fBFF3\fR from producing large output spikes if there is a
-step change on the command. Not normally needed.
+Limit on command third derivative. The command third derivative used by \fBFF3\fR will be limited to this value, unless the value is zero.
+Can be used to prevent \fBFF3\fR from producing large output spikes if there is a step change on the command. Not normally needed.
.TP
\fBpid.\fIN\fB.saturated\fR bit out
When true, the current PID output is saturated. That is,
@@ -378,36 +327,31 @@ When true, the output of PID was continually saturated for this many seconds
.SS Additional auto tuning pins
.TP
\fBpid.\fIN\fB.tune\-mode\fR bit in
-When true, enables auto tune mode. When false, normal PID calculations are
-performed.
+When true, enables auto tune mode. When false, normal PID calculations are performed.
.TP
\fBpid.\fIN\fB.tune\-start\fR bit io
When set to true, starts auto tuning. Cleared when the auto tuning completes.
.TP
\fBpid.\fIN\fB.tune\-type\fR u32 rw
-When set to 0, \fBPgain/Igain/Dgain\fR are calculated. When set to 1,
-\fBPgain/Igain/FF1\fR are calculated.
+When set to 0, \fBPgain/Igain/Dgain\fR are calculated. When set to 1, \fBPgain/Igain/FF1\fR are calculated.
.TP
\fBpid.\fIN\fB.tune\-cycles\fR u32 rw
Determines the number of cycles to run to characterize the process.
-\fBtune\-cycles\fR actually sets the number of half cycles. More cycles results
-in a more accurate characterization as the average of all cycles is used.
+\fBtune\-cycles\fR actually sets the number of half cycles.
+More cycles results in a more accurate characterization as the average of all cycles is used.
.TP
\fBpid.\fIN\fB.tune\-effort\fR float rw
The maximum output value used during automatic tuning.
Determines the effort used in setting up the limit cycle in the process.
\fBtune\-effort\fR should be set to a positive value less than \fBmaxoutput\fR.
-Start with something small and work up to a value that results in a good
-portion of the maximum motor current being used. The smaller the value, the
-smaller the amplitude of the limit cycle.
+Start with something small and work up to a value that results in a good portion of the maximum motor current being used.
+The smaller the value, the smaller the amplitude of the limit cycle.
.TP
\fBpid.\fIN\fB.ultimate\-gain\fR float ro (only if debug=1)
-Determined from process characterization. \fBultimate\-gain\fR is the ratio of
-\fBtune\-effort\fR to the limit cycle amplitude multiplied by 4.0 divided by Pi.
+Determined from process characterization. \fBultimate\-gain\fR is the ratio of \fBtune\-effort\fR to the limit cycle amplitude multiplied by 4.0 divided by Pi.
.TP
\fBpid.\fIN\fB.ultimate\-period\fR float ro (only if debug=1)
-Determined from process characterization. \fBultimate\-period\fR is the period
-of the limit cycle.
+Determined from process characterization. \fBultimate\-period\fR is the period of the limit cycle.
.SH PARAMETERS
.TP
@@ -421,23 +365,16 @@ Derivative of error. This is the value that is multiplied by \fBDgain\fR to pro
Derivative of command. This is the value that is multiplied by \fBFF1\fR to produce the first order feed-forward term of the output.
.TP
\fBpid.\fIN\fB.commandDD\fR float ro (only if debug=1)
-Second derivative of command. This is the value that is multiplied by
-\fBFF2\fR to produce the second order feed-forward term of the output.
+Second derivative of command. This is the value that is multiplied by \fBFF2\fR to produce the second order feed-forward term of the output.
.TP
\fBpid.\fIN\fB.commandDDD\fR float ro (only if debug=1)
-Third derivative of command. This is the value that is multiplied by
-\fBFF3\fR to produce the third order feed-forward term of the output.
+Third derivative of command. This is the value that is multiplied by \fBFF3\fR to produce the third order feed-forward term of the output.
.SH BUGS
-Some people would argue that deadband should be implemented such that error is
-treated as zero if it is within the deadband, and be unmodified if it is outside
-the deadband. This was not done because it would cause a step in the transfer
-function equal to the size of the deadband. People who prefer that behavior are
-welcome to add a parameter that will change the behavior, or to write their own
-version of \fBpid\fR. However, the default behavior should not be changed.
+Some people would argue that deadband should be implemented such that error is treated as zero if it is within the deadband, and be unmodified if it is outside the deadband.
+This was not done because it would cause a step in the transfer function equal to the size of the deadband.
+People who prefer that behavior are welcome to add a parameter that will change the behavior, or to write their own version of \fBpid\fR.
+However, the default behavior should not be changed.
-Negative gains may lead to unwanted behavior. It is possible in some
-situations that negative FF gains make sense, but in general all gains
-should be positive. If some output is in the wrong direction, negating
-gains to fix it is a mistake; set the scaling correctly elsewhere
-instead.
+Negative gains may lead to unwanted behavior. It is possible in some situations that negative FF gains make sense, but in general all gains should be positive.
+If some output is in the wrong direction, negating gains to fix it is a mistake; set the scaling correctly elsewhere instead.
diff --git a/docs/man/man9/pwmgen.9 b/docs/man/man9/pwmgen.9
index 99276be38e..29d4ec8edb 100644
--- a/docs/man/man9/pwmgen.9
+++ b/docs/man/man9/pwmgen.9
@@ -38,13 +38,13 @@ a bipolar output.
.SH FUNCTIONS
.TP
-\fBpwmgen.make\-pulses \fR(no floating-point)
+\fBpwmgen.make\-pulses\fR (no floating-point)
Generates the actual PWM waveforms, using information computed by
\fBupdate\fR. Must be called as frequently as possible, to maximize
the attainable PWM frequency and resolution, and minimize jitter.
Operates on all channels at once.
.TP
-\fBpwmgen.update \fR(uses floating point)
+\fBpwmgen.update\fR (uses floating point)
Accepts an input value, performs scaling and limit checks, and converts
it into a form usable by \fBmake\-pulses\fR for PWM/PDM generation. Can
(and should) be called less frequently than \fBmake\-pulses\fR. Operates
@@ -53,13 +53,12 @@ on all channels at once.
.SH PINS
.TP
\fBpwmgen.\fIN\fB.enable\fR bit in
-Enables PWM generator \fIN\fR - when false, all \fBpwmgen.\fIN\fR output
-pins are low.
+Enables PWM generator \fIN\fR - when false, all \fBpwmgen.\fIN\fR output pins are low.
.TP
\fBpwmgen.\fIN\fB.value\fR float in
-Commanded value. When \fBvalue\fR = 0.0, duty cycle is 0%, and when
-\fBvalue\fR = \(+-\fBscale\fR, duty cycle is \(+- 100%. (Subject to
-\fBmin\-dc\fR and \fBmax\-dc\fR limitations.)
+Commanded value. When \fBvalue\fR = 0.0, duty cycle is 0%,
+and when \fBvalue\fR = \(+-\fBscale\fR, duty cycle is \(+- 100%
+(subject to \fBmin\-dc\fR and \fBmax\-dc\fR limitations).
.TP
\fBpwmgen.\fIN\fB.pwm\fR bit out (output types 0 and 1 only)
PWM/PDM waveform.
@@ -78,13 +77,13 @@ The current duty cycle, after all scaling and limits have been applied.
Range is from \-1.0 to +1.0.
.TP
\fBpwmgen.\fIN\fB.max\-dc\fR float in/out
-The maximum duty cycle. A value of 1.0 corresponds to 100%. This can
-be useful when using transistor drivers with bootstrapped power supplies,
+The maximum duty cycle. A value of 1.0 corresponds to 100%.
+This can be useful when using transistor drivers with bootstrapped power supplies,
since the supply requires some low time to recharge.
.TP
\fBpwmgen.\fIN\fB.min\-dc\fR float in/out
-The minimum duty cycle. A value of 1.0 corresponds to 100%. Note that
-when the pwm generator is disabled, the outputs are constantly low,
+The minimum duty cycle. A value of 1.0 corresponds to 100%.
+Note that when the pwm generator is disabled, the outputs are constantly low,
regardless of the setting of \fBmin\-dc\fR.
.TP
\fBpwmgen.\fIN\fB.scale\fR float in/out
@@ -92,26 +91,20 @@ regardless of the setting of \fBmin\-dc\fR.
.ns
.TP
\fBpwmgen.\fIN\fB.offset\fR float in/out
-These parameters provide a scale and offset from the \fBvalue\fR pin to the
-actual duty cycle. The duty cycle is calculated according to \fIdc =
-(value/scale) + offset\fR, with 1.0 meaning 100%.
+These parameters provide a scale and offset from the \fBvalue\fR pin to thewactual duty cycle.
+The duty cycle is calculated according to \fIdc = (value/scale) + offset\fR, with 1.0 meaning 100%.
.TP
\fBpwmgen.\fIN\fB.pwm\-freq\fR float in/out
-PWM frequency in Hz. The upper limit is half of the frequency at which
-\fBmake\-pulses\fR is invoked, and values above that limit will be changed
-to the limit. If \fBdither\-pwm\fR is false, the value will be changed to
-the nearest integer submultiple of the \fBmake\-pulses\fR frequency. A
-value of zero produces Pulse Density Modulation instead of Pulse Width
-Modulation.
+PWM frequency in Hz. The upper limit is half of the frequency at which \fBmake\-pulses\fR is invoked,
+and values above that limit will be changed to the limit.
+If \fBdither\-pwm\fR is false, the value will be changed to the nearest integer submultiple of the \fBmake\-pulses\fR frequency.
+A value of zero produces Pulse Density Modulation instead of Pulse Width Modulation.
.TP
\fBpwmgen.\fIN\fB.dither\-pwm\fR bit in/out
-Because software-generated PWM uses a fairly slow timebase (several to many
-microseconds), it has limited resolution. For example, if \fBmake\-pulses\fR
-is called at a 20 kHz rate, and \fBpwm\-freq\fR is 2 kHz, there are only 10
-possible duty cycles. If \fBdither\-pwm\fR is false, the commanded duty cycle
-will be rounded to the nearest of those values. Assuming \fBvalue\fR remains
-constant, the same output will repeat every PWM cycle. If \fBdither\-pwm\fR is
-true, the output duty cycle will be dithered between the two closest values,
-so that the long-term average is closer to the desired level. \fBdither\-pwm\fR
-has no effect if \fBpwm\-freq\fR is zero (PDM mode), since PDM is an inherently
-dithered process.
+Because software-generated PWM uses a fairly slow timebase (several to many microseconds), it has limited resolution.
+For example, if \fBmake\-pulses\fR is called at a 20 kHz rate, and \fBpwm\-freq\fR is 2 kHz, there are only 10 possible duty cycles.
+If \fBdither\-pwm\fR is false, the commanded duty cycle will be rounded to the nearest of those values.
+Assuming \fBvalue\fR remains constant, the same output will repeat every PWM cycle.
+If \fBdither\-pwm\fR is true, the output duty cycle will be dithered between the two closest values,
+so that the long-term average is closer to the desired level.
+\fBdither\-pwm\fR has no effect if \fBpwm\-freq\fR is zero (PDM mode), since PDM is an inherently dithered process.
diff --git a/docs/man/man9/rosekins.9 b/docs/man/man9/rosekins.9
index 58e9f15de6..8d886462eb 100644
--- a/docs/man/man9/rosekins.9
+++ b/docs/man/man9/rosekins.9
@@ -10,14 +10,13 @@ rosekins \- Kinematics for a rose engine
.SH KINEMATICS
joint_0 linear, transverse (perpendicular to spindle)
joint_1 linear, longitudinal (parallel to spindle identity to z)
- joint_2 rotary, spindle (workholding, not tool holding, e.g.
- not a highspeed spindle)
+ joint_2 rotary, spindle (workholding, not tool holding, e.g. not a highspeed spindle)
.SH PINS
.TP
.B rosekins.revolutions\fR float out
-Count of crossings of the negative X axis. Clockwise crossings
-increment revolutions by 1, Counterclockwise crossings decrement by 1
+Count of crossings of the negative X axis.
+Clockwise crossings increment revolutions by 1, Counterclockwise crossings decrement by 1.
.TP
.B rosekins.theta_degrees\fR float out
@@ -29,13 +28,12 @@ Accumulated angle (theta + revolutions * 360)
.SH NOTES
-Theta is the principal value of arctan(Y/X). Joint_2 angle values are
-not limited to principal values of arctan(Y/X) but accumulate
-continuously as the spindle is rotated. Hal pins are provided for
-the principal value and a count of the number of revolutions.
+Theta is the principal value of arctan(Y/X).
+Joint_2 angle values are not limited to principal values of arctan(Y/X)
+but accumulate continuously as the spindle is rotated.
+HAL pins are provided for the principal value and a count of the number of revolutions.
-The transverse motion is exactly perpendicular to the spindle. In a
-traditional rose engine, the transverse motion is created by 'rocking'
-the headstock about a pivot. A typical pivot length combined with the
-limited amount of X travel in a real machine make the perpendicular
-approximation a reasonable model.
+The transverse motion is exactly perpendicular to the spindle.
+In a traditional rose engine, the transverse motion is created by 'rocking' the headstock about a pivot.
+A typical pivot length combined with the limited amount of X travel in a real machine
+make the perpendicular approximation a reasonable model.
diff --git a/docs/man/man9/sampler.9 b/docs/man/man9/sampler.9
index 02a204af63..2b8436c6de 100644
--- a/docs/man/man9/sampler.9
+++ b/docs/man/man9/sampler.9
@@ -127,12 +127,13 @@ command. The sample number can optionally be printed in the first column of the
.BR halsampler ,
using the
.I \-t
-option. (see
-.BR "man 1 halsampler" )
+option (see
+.BR "man 1 halsampler"
+).
.SH "SEE ALSO"
-.BR halsampler (1)
-.BR streamer (9)
+.BR halsampler (1),
+.BR streamer (9),
.BR halstreamer (1)
.SH AUTHOR
diff --git a/docs/man/man9/sserial.9 b/docs/man/man9/sserial.9
index 8960642606..7e271933e5 100644
--- a/docs/man/man9/sserial.9
+++ b/docs/man/man9/sserial.9
@@ -3,123 +3,94 @@
.TH SSERIAL "9" "2008-05-13" "LinuxCNC Documentation" "HAL Component"
.SH NAME
-hostmot2 - Smart Serial LinuxCNC HAL driver for the Mesa Electronics HostMot2
-Smart-Serial remote cards
+hostmot2 - Smart Serial LinuxCNC HAL driver for the Mesa Electronics HostMot2 Smart-Serial remote cards
.SH SYNOPSIS
-The Mesa Smart-Serial interface is a 2.5Mbs proprietary interface between the
-Mesa Anything-IO cards and a range of subsidiary devices termed "smart-serial remotes".
-The remote cards perform a variety of functions, but typically they combine
-various classes of IO.
-The remote cards are self-configuring, in that they tell the main LinuxCNC
-Hostmot2 driver what their pin functions are and what they should be named.
+The Mesa Smart-Serial interface is a 2.5Mbs proprietary interface between the Mesa Anything-IO cards and a range of subsidiary devices termed "smart-serial remotes".
+The remote cards perform a variety of functions, but typically they combine various classes of IO.
+The remote cards are self-configuring, in that they tell the main LinuxCNC Hostmot2 driver what their pin functions are and what they should be named.
Many sserial remotes offer different pinouts depending on the mode they are started up in.
-This is set using the sserial_port_N= option in the hm2_pci modparam.
-See the hostmot2 manpage for further details.
+This is set using the sserial_port_N= option in the hm2_pci modparam. See the hostmot2 manpage for further details.
-It is likely that this documentation will be permanently out of date.
+It is likely that this documentation will be permanently out of date.
-Each Anything-IO board can attach up to 8 sserial remotes to each header
-(either the 5-pin headers on the 5I20/5I22/5I23/7I43 or the 25-pin connectors on
-the 5I25, 6I25 and 7I80). The remotes are grouped into "ports" of up to 8
-"channels". Typically each header will be a single 8 channel port, but this is
-not necessarily always the case.
+Each Anything-IO board can attach up to 8 sserial remotes to each header
+(either the 5-pin headers on the 5I20/5I22/5I23/7I43 or the 25-pin connectors on the 5I25, 6I25 and 7I80).
+The remotes are grouped into "ports" of up to 8 "channels".
+Typically each header will be a single 8 channel port, but this is not necessarily always the case.
.SH PORTS
-In addition to the per-channel/device pins detailed below there are three
-per-port pins and three parameters.
+In addition to the per-channel/device pins detailed below there are three per-port pins and three parameters.
\fBPins:\fR
(bit, in) .sserial.port\-N.run: Enables the specific Smart Serial module.
-Setting this pin low will disable all boards on the port and puts the port in a
-pass-through mode where device parameter setting is possible. It is necessary
-to toggle the state of this pin if there is a requirement to alter a
-remote parameter on a live system.
-This pin defaults to TRUE and can be left unconnected. However, toggling the pin
-low-to-high will re-enable a faulted drive so the pin could usefully be
-connected to the iocontrol.0.user\-enable\-out pin.
+Setting this pin low will disable all boards on the port and puts the port in a pass-through mode where device parameter setting is possible.
+It is necessary to toggle the state of this pin if there is a requirement to alter a remote parameter on a live system.
+This pin defaults to TRUE and can be left unconnected.
+However, toggling the pin low-to-high will re-enable a faulted drive so the pin could usefully be connected to the iocontrol.0.user\-enable\-out pin.
(u32, ro) .run_state: Shows the state of the sserial communications state-machine.
-This pin will generally show a value of 0x03 in normal operation, 0x07 in
-setup mode and 0x00 when the "run" pin is false.
+This pin will generally show a value of 0x03 in normal operation, 0x07 in setup mode and 0x00 when the "run" pin is false.
-(u32, ro) .error\-count: Indicates the state of the Smart Serial error handler,
-see the parameters sections for more details.
+(u32, ro) .error\-count: Indicates the state of the Smart Serial error handler, see the parameters section for more details.
\fBParameters:\fR
-(u32 r/w) .fault\-inc: Any over-run or handshaking error in the SmartSerial
-communications will increment the .fault\-count pin by the amount specified by
-this parameter. Default = 10.
+(u32 r/w) .fault\-inc: Any over-run or handshaking error in the SmartSerial communications will increment the .fault\-count pin by the amount specified by this parameter.
+Default = 10.
-(u32 r/w) .fault\-dec: Every successful read/write cycle decrements the fault
-counter by this amount. Default = 1.
+(u32 r/w) .fault\-dec: Every successful read/write cycle decrements the fault counter by this amount. Default = 1.
-(u32 r/w) .fault\-lim: When the fault counter reaches this threshold the Smart
-Serial interface on the corresponding port will be stopped and an error printed
-in dmesg. Together these three pins allow for control over the degree of fault-
-tolerance allowed in the interface. The default values mean that if more than
-one transaction in ten fails, more than 20 times, then a hard error will be
-raised. If the increment were to be set to zero then no error would ever be
-raised, and the system would carry on regardless. Conversely setting decrement to
-zero, threshold to 1 and limit to 1 means that absolutely no errors will be
-tolerated. (This structure is copied directly from vehicle ECU practice)
+(u32 r/w) .fault\-lim: When the fault counter reaches this threshold the Smart Serial interface on the corresponding port will be stopped and an error printed in dmesg.
+Together these three pins allow for control over the degree of fault- tolerance allowed in the interface.
+The default values mean that if more than one transaction in ten fails, more than 20 times, then a hard error will be raised.
+If the increment were to be set to zero then no error would ever be raised, and the system would carry on regardless.
+Conversely setting decrement to zero, threshold to 1 and limit to 1 means that absolutely no errors will be tolerated.
+(This structure is copied directly from vehicle ECU practice.)
-Any other parameters than the ones above are created by the card istelf from
-data in the remote firmware. They may be set in the HAL file using "setp" in
-the usual way.
+Any other parameters than the ones above are created by the card istelf from data in the remote firmware.
+They may be set in the HAL file using "setp" in the usual way.
-NOTE: Because a Smart-Serial remote can only communicate non-process data
-to the host card in setup mode it is necessary to stop and re-start the
-smart-serial port associated with the card to alter the value of a parameter.
+NOTE: Because a Smart-Serial remote can only communicate non-process data to the host card in setup mode,
+it is necessary to stop and re-start the smart-serial port associated with the card to alter the value of a parameter.
-HALSO NOTE: in the case of parameters beginning with "nv" (which are stored
-in non-volatile memory) the effect will not be seen until after the next
-power cycle of the drive.
+ALSO NOTE: in the case of parameters beginning with "nv" (which are stored in non-volatile memory) the effect will not be seen until after the next power cycle of the drive.
-Unchanged values will not be re-written so it is safe to leave the
-"setp" commands in the HAL file or delete them as you see fit.
+Unchanged values will not be re-written so it is safe to leave the "setp" commands in the HAL file or delete them as you see fit.
.SH DEVICES
The other pins and parameters created in HAL depend on the devices detected.
-The following list of Smart Serial devices is by no means exhaustive.
+The following list of Smart Serial devices is by no means exhaustive.
-.SS 8i20
-The 8i20 is a 2.2 kW three-phase drive for brushless DC motors and AC servo
-motors.
-8i20 pins and parameters have names like
-"hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.8i20.\fI<PortNum>\fR.\fI<ChanNum>\fR.\fI<Pin>\fR", for example
-"hm2_5i23.0.8i20.1.3.current" would set the phase current for the drive
-connected to the fourth channel of the second sserial port of the first 5I23
-board. Note that the sserial ports do not necessarily correlate in layout or
-number to the physical ports on the card.
+.SS 8I20
+The 8I20 is a 2.2 kW three-phase drive for brushless DC motors and AC servo motors.
+8I20 pins and parameters have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.8i20.\fI<PortNum>\fR.\fI<ChanNum>\fR.\fI<Pin>\fR",
+for example "hm2_5i23.0.8i20.1.3.current" would set the phase current for the drive connected to the fourth channel of the second sserial port of the first 5I23 board.
+Note that the sserial ports do not necessarily correlate in layout or number to the physical ports on the card.
\fBPins:\fR
.TP
(float in) angle
-The rotor angle of the motor in fractions of a full
-\fBphase\fR revolution. An angle of 0.5 indicates that the motor is half a turn
-/ 180 degrees / \[*p] radians from the zero position. The zero position is taken to
-be the position that the motor adopts under no load with a poitive voltage
-applied to the A (or U) phase and both B and C (or V and W) connected to \-V or
-0V. A 6 pole motor will have 3 zero positions per physical rotation. Note that
-the 8i20 drive automatically adds the phase lead/lag angle, and that this pin
-should see the raw rotor angle. There is a HAL module (bldc) which handles the
-complexity of differing motor and drive types.
+The rotor angle of the motor in fractions of a full \fBphase\fR revolution.
+An angle of 0.5 indicates that the motor is half a turn / 180 degrees / \[*p] radians from the zero position.
+The zero position is taken to be the position that the motor adopts under no load with a poitive voltage applied to the A (or U) phase
+and both B and C (or V and W) connected to \-V or 0 V.
+A 6 pole motor will have 3 zero positions per physical rotation.
+Note that the 8I20 drive automatically adds the phase lead/lag angle, and that this pin should see the raw rotor angle.
+There is a HAL module (bldc) which handles the complexity of differing motor and drive types.
.TP
(float, in) current
-The phase current command to the drive. This is scaled
-from \-1 to +1 for forwards and reverse maximum currents. The absolute value of
-the current is set by the max_current parameter.
+The phase current command to the drive.
+This is scaled from \-1 to +1 for forwards and reverse maximum currents.
+The absolute value of the current is set by the max_current parameter.
.TP
(float, ro) bus-voltage
-The drive bus voltage in V. This will tend to show 25.6 V
-when the drive is unpowered and the drive will not operate below about 50 V.
+The drive bus voltage in V. This will tend to show 25.6 V when the drive is unpowered and the drive will not operate below about 50 V.
.TP
(float, ro) temp
@@ -127,13 +98,11 @@ The temperature of the driver in degrees C.
.TP
(u32, ro) comms
-The communication status of the drive. See the manual for
-more details.
+The communication status of the drive. See the manual for more details.
.TP
(bit, ro) status and fault.
-The following fault/status bits are exported. For further details see the
-8i20 manual.
+The following fault/status bits are exported. For further details see the 8I20 manual.
fault.U\-current / fault.U\-current\-not
fault.V\-current / fault.V\-current\-not
fault.W\-current / fault.W\-current\-not
@@ -160,8 +129,8 @@ status.wd\-reset / status.wd\-reset\-not
.TP
\fBParameters:\fR
-The following parameters are exported. See the PDF documentation downloadable
-from Mesa for further details
+The following parameters are exported.
+See the PDF documentation downloadable from Mesa for further details.
hm2_5i25.0.8i20.0.1.angle\-maxlim
hm2_5i25.0.8i20.0.1.angle\-minlim
@@ -189,85 +158,76 @@ from Mesa for further details
.TP
(float, rw) max_current
-Sets the maximum drive current in Amps. The default
-value is the maximum current programmed into the drive EEPROM. The value must be
-positive, and an error will be raised if a current in excess of the drive
-maximum is requested.
+Sets the maximum drive current in Amps.
+The default value is the maximum current programmed into the drive EEPROM.
+The value must be positive, and an error will be raised if a current in excess of the drive maximum is requested.
.TP
(u32, ro) serial_number
-The serial number of the connected drive. This is
-also shown on the label on the drive.
+The serial number of the connected drive. This is also shown on the label on the drive.
.SS 7I64
The 7I64 is a 24-input 24-output IO card.
-7I64 pins and parameters have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.7i64.
-<PortNum>.<ChanNum>.<Pin>", for example hm2_5i23.0.7i64.1.3.output\-01
+7I64 pins and parameters have names like "hm2_\fI<BoardType>\fR.\fI<BoardNum>\fR.7i64.<PortNum>.<ChanNum>.<Pin>",
+for example hm2_5i23.0.7i64.1.3.output\-01 .
\fBPins:\fR
-(bit, in) 7i64.0.0.output\-NN: Writing a 1 or TRUE to this pin will enable output
-driver NN. Note that the outputs are drivers (switches) rather than voltage
-outputs. The LED adjacent to the connector on the board shows the status.
+(bit, in) 7i64.0.0.output\-NN: Writing a 1 or TRUE to this pin will enable output driver NN.
+Note that the outputs are drivers (switches) rather than voltage outputs.
+The LED adjacent to the connector on the board shows the status.
The output can be inverted by setting a parameter.
-(bit, out) 7i64.0.0.input\-NN: The value of input NN. Note that the inputs are
-isolated and both pins of each input must be connected. (Typically to signal and
-the ground of the signal. This need not be the ground of the board.)
+(bit, out) 7i64.0.0.input\-NN: The value of input NN.
+Note that the inputs are isolated and both pins of each input must be connected, typically to signal and the ground of the signal.
+(This need not be the ground of the board.)
(bit, out) 7i64.0.0.input\-NN\-not: An inverted copy of the corresponding input.
-(float, out) 7i64.0.0.analog0 & 7i64.0.0.analog1: The two analogue inputs
-(0 to 3.3V) on the board.
+(float, out) 7i64.0.0.analog0 & 7i64.0.0.analog1: The two analogue inputs (0 to 3.3 V) on the board.
\fBParameters:\fR
-(bit, rw) 7i64.0.0.output\-NN\-invert: Setting this parameter to 1 / TRUE will invert
-the output value, such that writing 0 to .gpio.NN.out will enable the output
-and vice-versa.
+(bit, rw) 7i64.0.0.output\-NN\-invert: Setting this parameter to 1 / TRUE will invert the output value,
+such that writing 0 to .gpio.NN.out will enable the output and vice-versa.
.SS 7I76
-The 7I76 is not really a smart-serial device.
-It serves as a breakout for a number of other Hostmot2 functions.
+The 7I76 is not really a smart-serial device. It serves as a breakout for a number of other Hostmot2 functions.
There are connections for 5 step generators (for which see the main hostmot2 manpage).
The stepgen pins are associated with the 5I25 (hm2_5i25.0.stepgen.00....)
whereas the smart-serial pins are associated with the 7I76 (hm2_5i25.0.7i76.0.0.output\-00).
\fBPins:\fR
-(float out) .7i76.0.0.analogN (modes 1 and 2 only) Analogue input values.
+(float out) .7i76.0.0.analogN (modes 1 and 2 only) Analogue input values.
-(float out) .7i76.0.0.fieldvoltage (mode 2 only) Field voltage monitoring pin.
+(float out) .7i76.0.0.fieldvoltage (mode 2 only) Field voltage monitoring pin.
-(bit in) .7i76.0.0.spindir:
-This pin provides a means to drive the spindle VFD direction terminals on the 7I76 board.
+(bit in) .7i76.0.0.spindir: This pin provides a means to drive the spindle VFD direction terminals on the 7I76 board.
(bit in) .7i76.0.0.spinena: This pin drives the spindle-enable terminals on the 7I76 board.
-(float in) .7i76.0.0.spinout: This controls the analogue output of the 7I76.
-This is intended as a speed control signal for a VFD.
+(float in) .7i76.0.0.spinout: This controls the analogue output of the 7I76.
+This is intended as a speed control signal for a VFD.
-(bit out) .7i76.0.0.output\-NN: (NN = 0 to 15). 16 digital outputs.
-The sense of the signal can be set via a parameter
+(bit out) .7i76.0.0.output\-NN: (NN = 0 to 15). 16 digital outputs. The sense of the signal can be set via a parameter.
(bit out) .7i76.0.0.input\-NN: (NN = 0 to 31) 32 digital inputs.
(bit in) .7i76.0.0.input\-NN\-not: (NN = 0 to 31) An inverted copy of the inputs provided for convenience.
-The two complementary pins may be connected to different signal nets.
+The two complementary pins may be connected to different signal nets.
\fBParameters:\fR
-(u32 ro) .7i76.0.0.nvbaudrate: Indicates the vbaud rate. This probably should
-not be altered.
+(u32 ro) .7i76.0.0.nvbaudrate: Indicates the vbaud rate. This probably should not be altered.
-(u32 ro) .7i76.0.0.nvunitnumber: Indicates the serial number of the device and
-should match a sticker on the card. This can be useful for working out which
-card is which.
+(u32 ro) .7i76.0.0.nvunitnumber: Indicates the serial number of the device and should match a sticker on the card.
+This can be useful for working out which card is which.
(u32 ro) .7i76.0.0.nvwatchdogtimeout: The sserial remote watchdog timeout.
-This is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
+This is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
-(bit rw) .7i76.0.0.output\-NN\-invert: Invert the sense of the corresponding output pin.
+(bit rw) .7i76.0.0.output\-NN\-invert: Invert the sense of the corresponding output pin.
(bit rw) .7i76.0.0.spindir\-invert: Invert the senseof the spindle direction pin.
@@ -279,17 +239,16 @@ This is separate from the Anything-IO card timeout. This is unlikely to need to
(float rw) .7i76.0.0.spinout\-scalemax: The spindle speed scaling.
This is the speed request which would correspond to full-scale output from the spindle control pin.
-For example with a 10V drive voltage and a 10,000 rpm scalemax a value of 10,000 rpm on the spinout pin would produce 10V output.
-However, if spinout\-maxlim were set to 5,000 rpm then no voltage above 5V would be output.
+For example with a 10 V drive voltage and a 10000 RPM scalemax a value of 10,000 RPM on the spinout pin would produce 10 V output.
+However, if spinout\-maxlim were set to 5,000 RPM then no voltage above 5 V would be output.
-(u32 ro) .7i76.0.0.swrevision: The onboard firmware revision number.
+(u32 ro) .7i76.0.0.swrevision: The onboard firmware revision number.
Utilities (man setsserial for details) exist to update and change this firmware.
.SS 7I77
-The 7I77 is an 6-axis servo control card. The analogue outputs are smart-serial
-devices but the encoders are conventional hostmot2 encoders and further details
-of them may be found in the hostmot2 manpage.
+The 7I77 is an 6-axis servo control card. The analogue outputs are smart-serial devices,
+but the encoders are conventional hostmot2 encoders and further details of them may be found in the hostmot2 manpage.
\fBPins:\fR
@@ -298,21 +257,18 @@ of them may be found in the hostmot2 manpage.
(bit in) .7i77.0.0.input\-NN\-not: (NN = 0 to 31) An inverted copy of the inputs provided for convenience.
The two complementary pins may be connected to different signal nets.
-(bit out) .7i77.0.0.output\-NN: (NN = 0 to 15). 16 digital outputs.
-The sense of the signal can be set via a parameter.
+(bit out) .7i77.0.0.output\-NN: (NN = 0 to 15). 16 digital outputs. The sense of the signal can be set via a parameter
-(bit in) .7i77.0.0.spindir:
-This pin provides a means to drive the spindle VFD direction terminals on the 7I76 board.
+(bit in) .7i77.0.0.spindir: This pin provides a means to drive the spindle VFD direction terminals on the 7I76 board.
(bit in) .7i77.0.0.spinena: This pin drives the spindle-enable terminals on the 7I76 board.
(float in) .7i77.0.0.spinout: This controls the analog output of the 7I77.
-This is intended as a speed control signal for a VFD.
+This is intended as a speed control signal for a VFD.
(bit in) .7i77.0.1.analogena: This pin drives the analog enable terminals on the 7I77 board.
-(float in) .7i77.0.1.analogoutN: (N = 0 to 5) This controls the analog output
-of the 7I77.
+(float in) .7i77.0.1.analogoutN: (N = 0 to 5) This controls the analog output of the 7I77.
\fBParameters:\fR
@@ -328,8 +284,8 @@ of the 7I77.
(float rw) .7i77.0.0.spinout\-scalemax: The spindle speed scaling.
This is the speed request which would correspond to full-scale output from the spindle control pin.
-For example with a 10V drive voltage and a 10,000 rpm scalemax a value of 10,000 rpm on the spinout pin would produce 10V output.
-However, if spinout\-maxlim were set to 5,000 rpm then no voltage above 5V would be output.
+For example with a 10 V drive voltage and a 10000 RPM scalemax a value of 10,000 RPM on the spinout pin would produce 10 V output.
+However, if spinout\-maxlim were set to 5,000 RPM then no voltage above 5 V would be output.
(float rw) .7i77.0.0.analogoutN\-maxlim: (N = 0 to 5) The maximum speed request allowable
@@ -352,7 +308,7 @@ The 7I69 is a 48 channel digital IO card. It can be configured in four different
\fBPins:\fR
-(bit in) .7i69.0.0.output\-NN: Digital output. Sense can be inverted with the corresponding Parameter
+(bit in) .7i69.0.0.output\-NN: Digital output. Sense can be inverted with the corresponding Parameter.
(bit out) .7i69.0.0.input\-NN: Digital input
@@ -362,17 +318,15 @@ The 7I69 is a 48 channel digital IO card. It can be configured in four different
(u32 ro) .7i69.0.0.nvbaudrate: Indicates the vbaud rate. This probably should not be altered.
-(u32 ro) .7i69.0.0.nvunitnumber:
-Indicates the serial number of the device and should match a sticker on the card.
+(u32 ro) .7i69.0.0.nvunitnumber: Indicates the serial number of the device and should match a sticker on the card.
This can be useful for working out which card is which.
(u32 ro) .7i69.0.0.nvwatchdogtimeout: The sserial remote watchdog timeout.
-This is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
+This is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
-(bit rw) .7i69.0.0.output\-NN\-invert: Invert the sense of the corresponding
-output pin.
+(bit rw) .7i69.0.0.output\-NN\-invert: Invert the sense of the corresponding output pin.
-(u32 ro) .7i69.0.0.swrevision: The onboard firmware revision number.
+(u32 ro) .7i69.0.0.swrevision: The onboard firmware revision number.
Utilities exist to update and change this firmware.
.SS 7I70
@@ -388,12 +342,12 @@ For high speed applications, choosing the correct mode can reduced the data tran
MODE 0: Input mode (48 bits input data only
MODE 1: Input plus analog mode (48 bits input data plus 6 channels of analog data)
MODE 2: Input plus field voltage
-
-\fBPins:\fR
-(float out) .7i70.0.0.analogN (modes 1 and 2 only) Analogue input values.
+\fBPins:\fR
+
+(float out) .7i70.0.0.analogN (modes 1 and 2 only) Analogue input values.
-(float out) .7i70.0.0.fieldvoltage (mode 2 only) Field voltage monitoring pin.
+(float out) .7i70.0.0.fieldvoltage (mode 2 only) Field voltage monitoring pin.
(bit out) .7i70.0.0.input\-NN: (NN = 0 to 47) 48 digital inputs.
@@ -407,10 +361,11 @@ The two complementary pins may be connected to different signal nets.
(u32 ro) .7i70.0.0.nvunitnumber: Indicates the serial number of the device and should match a sticker on the card.
This can be useful for working out which card is which.
-(u32 ro) .7i70.0.0.nvwatchdogtimeout: The sserial remote watchdog timeout. This
-is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
+(u32 ro) .7i70.0.0.nvwatchdogtimeout: The sserial remote watchdog timeout.
+This is separate from the Anything-IO card timeout.
+This is unlikely to need to be changed.
-(u32 ro) .7i69.0.0.swrevision: The onboard firmware revision number.
+(u32 ro) .7i69.0.0.swrevision: The onboard firmware revision number.
Utilities exist to update and change this firmware.
.SS 7I71
@@ -422,13 +377,15 @@ All outputs have LED status indicators.
The 7I71 has two software selectable modes. For high speed applications,
choosing the correct mode can reduced the data transfer sizes, resulting in higher maximum update rates:
- MODE 0: Output only mode (48 bits output data only)
+ MODE 0: Output only mode (48 bits output data only)
MODE 1: Outputs plus read back field voltage
-\fBPins:\fR
+\fBPins:\fR
+
+(float out) .7i71.0.0.fieldvoltage (mode 2 only) Field voltage monitoring pin.
-(float out) .7i71.0.0.fieldvoltage (mode 2 only) Field voltage monitoring pin.
+(bit out) .7i71.0.0.output\-NN: (NN = 0 to 47) 48 digital outputs. The sense may be inverted by the invert parameter.
(bit out) .7i71.0.0.output\-NN: (NN = 0 to 47) 48 digital outputs.
The sense may be inverted by the invert parameter.
@@ -444,25 +401,21 @@ Indicates the serial number of the device and should match a sticker on the card
This can be useful for determining which card is which.
(u32 ro) .7i71.0.0.nvwatchdogtimeout: The sserial remote watchdog timeout.
-This is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
+This is separate from the Anything-IO card timeout. This is unlikely to need to be changed.
-(u32 ro) .7i69.0.0.swrevision: The onboard firmware revision number.
-Utilities exist to update and change this firmware.
+(u32 ro) .7i69.0.0.swrevision: The onboard firmware revision number. Utilities exist to update and change this firmware.
.SS 7I73
-The 7I73 is a remote real time pendant or control panel interface.
+The 7I73 is a remote real time pendant or control panel interface.
-The 7I73 supports up to four 50 kHz encoder inputs for MPGs, 8 digital inputs
-and 6 digital outputs and up to a 64 Key keypad. If a smaller keypad is used,
-more digital inputs and outputs become available. Up to eight 0.0V to 3.3V
-analog inputs are also provided.
+The 7I73 supports up to four 50 kHz encoder inputs for MPGs, 8 digital inputs and 6 digital outputs and up to a 64 Key keypad.
+If a smaller keypad is used, more digital inputs and outputs become available.
+Up to eight 0.0 V to 3.3 V analog inputs are also provided.
The 7I73 can drive a 4 line 20 character LCD for local DRO applications.
-The 7I73 has 3 software selectable process data modes. These different modes
-select different sets of 7I73 data to be transferred between the host and the 7
-I73 during real time process data exchanges. For high speed applications,
-choosing the correct mode can reduced the data transfer sizes, resulting in
-higher maximum update rates
+The 7I73 has 3 software selectable process data modes.
+These different modes select different sets of 7I73 data to be transferred between the host and the 7I73 during real time process data exchanges.
+For high speed applications, choosing the correct mode can reduced the data transfer sizes, resulting in higher maximum update rates
MODE 0: I/O + ENCODER
MODE 1: I/O + ENCODER + ANALOG IN
@@ -475,11 +428,9 @@ Up to 8 channels may be available dependent on software and hardware configurati
(see the PDF manual downloadable from www.mesanet.com).
(u32 in) .7i73.0.1.display (modes 1 and 2). Data for LCD display.
-This pin may be conveniently driven by the HAL "lcd" component
-which allows the formatted display of the values any number of HAL pins and textual content.
+This pin may be conveniently driven by the HAL "lcd" component which allows the formatted display of the values any number of HAL pins and textual content.
-
-(u32 in) .7i73.0.1.display32 (mode 2 only). 4 bytes of data for LCD display.
+(u32 in) .7i73.0.1.display32 (mode 2 only). 4 bytes of data for LCD display.
This mode is not supported by the HAL "lcd" component.
(s32 out) .7i73.0.1.encN: The position of the MPG encoder counters.
@@ -490,7 +441,7 @@ This mode is not supported by the HAL "lcd" component.
(bit in) .7i73.0.1.output\-NN: Up to 22 digital outputs (dependent on config)
-\fBParameters:\fR
+\fBParameters:\fR
(u32 ro) .7i73.0.1.nvanalogfilter
(u32 ro) .7i73.0.1.nvbaudrate
@@ -504,14 +455,11 @@ This mode is not supported by the HAL "lcd" component.
(u32 ro) .7i73.0.1.nvunitnumber
(u32 ro) .7i73.0.1.nvwatchdogtimeout
(u32 ro) .7i73.0.1.output\-00\-invert
-
- For further details of the use of the above see the Mesa manual.
+
+For further details of the use of the above see the Mesa manual.
(bit rw) .7i73.0.1.output\-01\-invert: Invert the corresponding output bit.
(s32 ro) .7i73.0.1.swrevision: The version of firmware installed.
-
-\# TODO: Add 7I66, 7I72, 7I83, 7I84, 7I87.
-
-
+\# TODO: Add 7I66, 7I72, 7I83, 7I84, 7I87.
diff --git a/docs/src/code/building-linuxcnc.adoc b/docs/src/code/building-linuxcnc.adoc
index 92d0f59919..58fe25424c 100644
--- a/docs/src/code/building-linuxcnc.adoc
+++ b/docs/src/code/building-linuxcnc.adoc
@@ -94,21 +94,18 @@ $ sudo make setuid
LinuxCNC can also be built and run on non-realtime platforms, such as
a regular install of Debian or Ubuntu without any special realtime kernel.
-In this mode LinuxCNC is not useful for controlling machine tools, but
-it is useful for simulating the execution of G-code and for testing the
-non-realtime parts of the system (such as the user interfaces, and some
-kinds of components and device drivers).
+In this mode LinuxCNC is not useful for controlling machine tools,
+but it is useful for simulating the execution of G-code and for testing the non-realtime parts of the system
+(such as the user interfaces, and some kinds of components and device drivers).
== Build modes
-There are two ways to build LinuxCNC: the developer-friendly "run in
-place" mode and the user-friendly Debian packaging mode.
+There are two ways to build LinuxCNC: the developer-friendly "run in place" mode and the user-friendly Debian packaging mode.
=== Building for Run In Place
-In a Run-In-Place build, the LinuxCNC programs are compiled from source
-and then run directly from within the build directory. Nothing is
-installed outside the build directory.
+In a Run-In-Place build, the LinuxCNC programs are compiled from source and then run directly from within the build directory.
+Nothing is installed outside the build directory.
This is quick and easy, and suitable for rapid iteration of changes.
@@ -116,15 +113,14 @@ The LinuxCNC test suite runs only in a Run-In-Place build.
Most LinuxCNC developers primarily build using this mode.
-Building for Run-In-Place follows the steps in the <<Quick-Start,Quick Start>>
-section at the top of this document, possibly with different arguments
-to `src/configure` and `make`.
+Building for Run-In-Place follows the steps in the <<Quick-Start,Quick Start>> section at the top of this document,
+possibly with different arguments to `src/configure` and `make`.
[[src-configure-arguments]]
==== `src/configure` arguments
-The `src/configure` script configures how the source code will be
-compiled. It takes many optional arguments.
+The `src/configure` script configures how the source code will be compiled.
+It takes many optional arguments.
List all arguments to `src/configure` by running this:
@@ -198,9 +194,9 @@ internet access.
Building Debian packages requires the `dpkg-buildpackage` tool, from the
`dpkg-dev` package:
------
+----
$ sudo apt-get install dpkg-dev
------
+----
Building Debian packages also requires that all build dependencies are
installed, as described in the section <<Satisfying-Build-Dependencies,
@@ -212,38 +208,35 @@ of two steps.
The first step is generating the Debian package scripts and meta-data
from the git repo by running this:
------
+----
$ cd linuxcnc-dev/debian
$ ./configure uspace
$ cd ..
------
+----
[NOTE]
-=====
-The `debian/configure` script is different from the `src/configure`
-script!
+====
+The `debian/configure` script is different from the `src/configure` script!
-The `debian/configure` script needs different arguments depending on the
-platform you're building on/for, see the <<debian-configure-arguments,
-`debian/configure` arguments>> section.
-=====
+The `debian/configure` script needs different arguments depending on the platform you're building on/for,
+see the <<debian-configure-arguments, `debian/configure` arguments>> section.
+====
-Once the Debian package scripts and meta-data are configured, build the
-package by running `dpkg-buildpackage` (note that it needs to run from
-the `linuxcnc-dev` directory, *not* from `linuxcnc-dev/debian`):
+Once the Debian package scripts and meta-data are configured, build the package by running `dpkg-buildpackage`
+(note that it needs to run from the `linuxcnc-dev` directory, *not* from `linuxcnc-dev/debian`):
------
+----
$ dpkg-buildpackage -b -uc
------
+----
[[debian-configure-arguments]]
==== `debian/configure` arguments
-The `debian/configure` script configures the Debian packaging. It must
-be run before `dpkg-checkbuilddeps` and `dpkg-buildpackage` can be run.
+The `debian/configure` script configures the Debian packaging.
+It must be run before `dpkg-checkbuilddeps` and `dpkg-buildpackage` can be run.
-It takes a single argument which specifies the realtime or non-realtime
-platform to build for. The normal values for this argument are:
+It takes a single argument which specifies the realtime or non-realtime platform to build for.
+The normal values for this argument are:
`uspace`::
Configure the Debian package for Preempt-RT realtime or for
diff --git a/docs/src/drivers/hostmot2.adoc b/docs/src/drivers/hostmot2.adoc
index faecc570da..a46f5c74c7 100644
--- a/docs/src/drivers/hostmot2.adoc
+++ b/docs/src/drivers/hostmot2.adoc
@@ -136,7 +136,7 @@ exported:
(This function is not available on the 7i43 due to limitations of the EPP bus.)
[NOTE]
-=====================================================================
+====
The above 'read_gpio' and 'write_gpio' functions should not
normally be needed, since the GPIO bits are read and written along
with everything else in the standard 'read' and 'write'
@@ -147,7 +147,7 @@ case some very fast (frequently updated) I/O is needed. These
functions should be run in the base thread. If you have need for
this, please send an email and tell us about it, and what your
application is.
-=====================================================================
+====
== Pinouts
diff --git a/docs/src/drivers/mb2hal.adoc b/docs/src/drivers/mb2hal.adoc
index 6021084999..058a3030d2 100644
--- a/docs/src/drivers/mb2hal.adoc
+++ b/docs/src/drivers/mb2hal.adoc
@@ -12,31 +12,23 @@
== Introduction
-MB2HAL is a generic userspace HAL component to communicate with one or more
-Modbus devices. So far, there are two options to communicate with a Modbus
-device:
+MB2HAL is a generic userspace HAL component to communicate with one or more Modbus devices.
+So far, there are two options to communicate with a Modbus device:
-. One option is to create a HAL component as a driver see
- https://wiki.linuxcnc.org/cgi-bin/wiki.pl?VFD_Modbus[VFD Modbus].
-. Another option is to use Classic Ladder which has Modbus built in
- see <<cha:classicladder,ClassicLadder>>.
-. Now there is a third option that consists of a "generic" driver
- configured by text file, this is called MB2HAL.
+. One option is to create a HAL component as a driver see https://wiki.linuxcnc.org/cgi-bin/wiki.pl?VFD_Modbus[VFD Modbus].
+. Another option is to use Classic Ladder which has Modbus built in, see <<cha:classicladder,ClassicLadder>>.
+. Now there is a third option that consists of a "generic" driver configured by text file, this is called MB2HAL.
Why MB2HAL?
Consider using MB2HAL if:
-* You have to write a new driver and you don't know anything about
- programming.
+* You have to write a new driver and you don't know anything about programming.
* You need to use Classic Ladder "only" to manage the Modbus connections.
* You have to discover and configure first time the Modbus transactions.
MB2HAL have debug levels to facilitate the low level protocol debug.
-* You have more than one device to connect. MB2HAL is very efficient
- managing multiple devices, transactions and links.
- Currently I am monitoring two axis drivers using a Rs232 port, a VFD
- driver using another Rs232 port, and a remote I/O using TCP/IP.
-* You want a protocol to connect your Arduino to HAL. Look the included
- sample configuration file, sketch and library for Arduino Modbus.
+* You have more than one device to connect. MB2HAL is very efficiently managing multiple devices, transactions and links.
+ Currently I am monitoring two axis drivers using a Rs232 port, a VFD driver using another Rs232 port, and a remote I/O using TCP/IP.
+* You want a protocol to connect your Arduino to HAL. Look the included sample configuration file, sketch and library for Arduino Modbus.
== Usage
@@ -77,52 +69,30 @@ m|TOTAL_TRANSACTIONS | Integer | Yes | The number of total Modbus transactions.
=== Transaction Sections
-One transaction section is required per transaction, starting at
-`[TRANSACTION_00]` and counting up sequentially.
-If there is a new link (not transaction), you must provide the REQUIRED
-parameters 1st time.
-Warning: Any OPTIONAL parameter not specified are copied from the
-previous transaction.
+One transaction section is required per transaction, starting at `[TRANSACTION_00]` and counting up sequentially.
+If there is a new link (not transaction), you must provide the REQUIRED parameters 1st time.
+Warning: Any OPTIONAL parameter not specified are copied from the previous transaction.
[options="header",cols="14,8,13,67"]
|===
-|Value | Type | Required | Description
-m|LINK_TYPE | String | Yes | You must specify either a "serial" or
-"tcp" link for the first transaction.
-Later transactions will use the previous transaction link if not
-specified.
-m|TCP_IP | IP address | If `LINK_TYPE=tcp` | The Modbus slave
-device IP address. Ignored if `LINK_TYPE=serial`.
-m|TCP_PORT | Integer | No | The Modbus slave device TCP port.
-Defaults to 502. Ignored if `LINK_TYPE=serial`.
-m|SERIAL_PORT | String | If `LINK_TYPE=serial` | The serial port.
-For example "/dev/ttyS0". Ignored if `LINK_TYPE=tcp`.
-m|SERIAL_BAUD | Integer | If `LINK_TYPE=serial` | The baud rate.
-Ignored if `LINK_TYPE=tcp`.
-m|SERIAL_BITS | Integer | If `LINK_TYPE=serial` | Data bits.
-One of 5, 6, 7, 8. Ignored if `LINK_TYPE=tcp`.
-m|SERIAL_PARITY | String | If `LINK_TYPE=serial` | Data parity.
-One of: even, odd, none. Ignored if `LINK_TYPE=tcp`.
-m|SERIAL_STOP | Integer | If `LINK_TYPE=serial` | Stop bits.
-One of 1, 2. Ignored if `LINK_TYPE=tcp`.
-m|SERIAL_DELAY_MS | Integer | If `LINK_TYPE=serial` | Serial port delay
-between transactions of this section only.
-In ms. Defaults to 0. Ignored if `LINK_TYPE=tcp`.
-m|MB_SLAVE_ID | Integer | Yes | Modbus slave number.
-m|FIRST_ELEMENT | Integer | Yes | The first element address.
-m|NELEMENTS | Integer | Unless `PIN_NAMES` is specified | The
-number of elements. It is an error to specify both `NELEMENTS` and
-`PIN_NAMES`. The pin names will be sequential numbers
-e.g. `mb2hal.plcin.01`
-m|PIN_NAMES | List | Unless `NELEMENTS` is specified | A list of
-element names.
-These names will be used for the pin names, e.g.
-mb2hal.plcin.cycle_start. +
-*NOTE:* There must be no white space characters in the list. Example:
-`PIN_NAMES=cycle_start,stop,feed_hold`
-m|MB_TX_CODE | String | Yes |
-
-Modbus transaction function code (see link:https://modbus.org/specs.php[specifications]):
+|Value | Type | Required | Description
+m|LINK_TYPE | String | Yes | You must specify either a "serial" or "tcp" link for the first transaction.
+Later transactions will use the previous transaction link if not specified.
+m|TCP_IP | IP address | If `LINK_TYPE=tcp` | The Modbus slave device IP address. Ignored if `LINK_TYPE=serial`.
+m|TCP_PORT | Integer | No | The Modbus slave device TCP port. Defaults to 502. Ignored if `LINK_TYPE=serial`.
+m|SERIAL_PORT | String | If `LINK_TYPE=serial` | The serial port. For example "/dev/ttyS0". Ignored if `LINK_TYPE=tcp`.
+m|SERIAL_BAUD | Integer | If `LINK_TYPE=serial` | The baud rate. Ignored if `LINK_TYPE=tcp`.
+m|SERIAL_BITS | Integer | If `LINK_TYPE=serial` | Data bits. One of 5, 6, 7, 8. Ignored if `LINK_TYPE=tcp`.
+m|SERIAL_PARITY | String | If `LINK_TYPE=serial` | Data parity. One of: even, odd, none. Ignored if `LINK_TYPE=tcp`.
+m|SERIAL_STOP | Integer | If `LINK_TYPE=serial` | Stop bits. One of 1, 2. Ignored if `LINK_TYPE=tcp`.
+m|SERIAL_DELAY_MS | Integer | If `LINK_TYPE=serial` | Serial port delay between transactions of this section only. In ms. Defaults to 0. Ignored if `LINK_TYPE=tcp`.
+m|MB_SLAVE_ID | Integer | Yes | Modbus slave number.
+m|FIRST_ELEMENT | Integer | Yes | The first element address.
+m|NELEMENTS | Integer | Unless `PIN_NAMES` is specified | The number of elements.
+It is an error to specify both `NELEMENTS` and `PIN_NAMES`. The pin names will be sequential numbers, e.g. `mb2hal.plcin.01`.
+m|PIN_NAMES | List | Unless `NELEMENTS` is specified | A list of element names. These names will be used for the pin names, e.g. mb2hal.plcin.cycle_start. +
+*NOTE:* There must be no white space characters in the list. Example: `PIN_NAMES=cycle_start,stop,feed_hold`
+m|MB_TX_CODE | String | Yes | Modbus transaction function code (see link:https://modbus.org/specs.php[specifications]):
• fnct_01_read_coils +
• fnct_02_read_discrete_inputs +
@@ -134,30 +104,22 @@ Modbus transaction function code (see link:https://modbus.org/specs.php[specific
• fnct_16_write_multiple_registers +
m|MB_RESPONSE_TIMEOUT_MS | Integer | No |
-Response timeout for this transaction. In ms. Defaults to 500 ms. This
-is how much to wait for 1st byte before raise an error.
-m|MB_BYTE_TIMEOUT_MS | Integer | No | Byte timeout for this
-transaction. In ms. Defaults to 500 ms. This is how much to wait from
-byte to byte before raise an error.
-m|HAL_TX_NAME | String | No | Instead of giving the transaction
-number, use a name. Example: `mb2hal.00.01`
+Response timeout for this transaction. In ms. Defaults to 500 ms.
+This is how much to wait for 1st byte before raise an error.
+m|MB_BYTE_TIMEOUT_MS | Integer | No | Byte timeout for this transaction.
+In ms. Defaults to 500 ms. This is how much to wait from byte to byte before raise an error.
+m|HAL_TX_NAME | String | No | Instead of giving the transaction number, use a name. Example: `mb2hal.00.01`
could become `mb2hal.plcin.01`. The name must not exceed 28 characters.
-*NOTE:* when using names be careful that
-you don't end up with two transactions using the same name.
-m|MAX_UPDATE_RATE | Float | No | Maximum update rate in Hz. Defaults to
-0.0 (0.0 = as soon as available = infinite).
-*NOTE:* This is a maximum rate and the actual rate may be lower. If you
-want to calculate it in ms use (1000 / required_ms).
-Example: 100 ms = `MAX_UPDATE_RATE=10.0`,
-because 1000.0 ms / 100.0 ms = 10.0 Hz.
-m|DEBUG | String | No | Debug level for this transaction only.
-See `INIT_DEBUG` parameter above.
+*NOTE:* when using names be careful that you don't end up with two transactions using the same name.
+m|MAX_UPDATE_RATE | Float | No | Maximum update rate in Hz. Defaults to 0.0 (0.0 = as soon as available = infinite).
+*NOTE:* This is a maximum rate and the actual rate may be lower. If you want to calculate it in ms use (1000 / required_ms).
+Example: 100 ms = `MAX_UPDATE_RATE=10.0`, because 1000.0 ms / 100.0 ms = 10.0 Hz.
+m|DEBUG | String | No | Debug level for this transaction only. See `INIT_DEBUG` parameter above.
|===
=== Error codes
-While debugging transactions, note the returned "`ret[]`" value
-correspond to:
+While debugging transactions, note the returned "`ret[]`" value correspond to:
Modbus protocol exceptions:
@@ -197,10 +159,10 @@ include::mb2hal_HOWTO.ini[]
[NOTE]
====
[yellow yellow-background]#Yellow# = New in MB2HAL 1.1 (LinuxCNC 2.9)
-To use these new features you have to set `VERSION = 1.1`
+To use these new features you have to set `VERSION = 1.1`.
-m = Value of `HAL_TX_NAME` if set or transaction number +
-n = element number (`NELEMENTS`) or name from `PIN_NAMES`
+_m_ = Value of `HAL_TX_NAME` if set or transaction number +
+_n_ = element number (`NELEMENTS`) or name from `PIN_NAMES`
Example:
@@ -210,49 +172,49 @@ Example:
=== [yellow-background]#fnct_01_read_coils#
-* [yellow-background]#mb2hal.m.n.bit# _bit out_
-* [yellow-background]#mb2hal.m.n.bit-inv# _bit out_
+* [yellow-background]#mb2hal.__m__.__n__.bit# _bit out_
+* [yellow-background]#mb2hal.__m__.__n__.bit-inv# _bit out_
=== fnct_02_read_discrete_inputs
-* mb2hal.m.n.[yellow-background]#bit# _bit out_
-* [yellow-background]#mb2hal.m.n.bit-inv# _bit out_
+* mb2hal.__m__.__n__.[yellow-background]#bit# _bit out_
+* [yellow-background]#mb2hal.__m__.__n__.bit-inv# _bit out_
=== fnct_03_read_holding_registers
-* mb2hal.m.n.float _float out_
-* mb2hal.m.n.int _s32 out_
+* mb2hal.__m__.__n__.float _float out_
+* mb2hal.__m__.__n__.int _s32 out_
=== fnct_04_read_input_registers
-* mb2hal.m.n.float _float out_
-* mb2hal.m.n.int _s32 out_
+* mb2hal.__m__.__n__.float _float out_
+* mb2hal.__m__.__n__.int _s32 out_
=== [yellow-background]#fnct_05_write_single_coil#
-* [yellow-background]#mb2hal.m.n.bit# _bit in_
+* [yellow-background]#mb2hal.__m__.__n__.bit# _bit in_
`NELEMENTS` needs to be 1 or `PIN_NAMES` must contain just one name.
=== fnct_06_write_single_register
-* mb2hal.m.n.[yellow-background]#float# _float in_
-* [yellow-background]#mb2hal.m.n.int# _s32 in_
+* mb2hal.__m__.__n__.[yellow-background]#float# _float in_
+* [yellow-background]#mb2hal.__m__.__n__.int# _s32 in_
`NELEMENTS` needs to be 1 or `PIN_NAMES` must contain just one name.
-Both pin values are added and limited to 65535 (UINT16_MAX). Use one and
-let the other open (read as 0).
+Both pin values are added and limited to 65535 (UINT16_MAX).
+Use one and let the other open (read as 0).
=== fnct_15_write_multiple_coils
-* mb2hal.m.n.[yellow-background]#bit# _bit in_
+* mb2hal.__m__.__n__.[yellow-background]#bit# _bit in_
=== fnct_16_write_multiple_registers
-* mb2hal.m.n.[yellow-background]#float# _float in_
-* [yellow-background]#mb2hal.m.n.int# _s32 in_
+* mb2hal.__m__.__n__.[yellow-background]#float# _float in_
+* [yellow-background]#mb2hal.__m__.__n__.int# _s32 in_
-Both pin values are added and limited to 65535 (UINT16_MAX). Use one and
-let the other open (read as 0).
+Both pin values are added and limited to 65535 (UINT16_MAX).
+Use one and let the other open (read as 0).
// vim: set syntax=asciidoc:
diff --git a/docs/src/drivers/shuttle.adoc b/docs/src/drivers/shuttle.adoc
index 81951dfedb..138cae8f52 100644
--- a/docs/src/drivers/shuttle.adoc
+++ b/docs/src/drivers/shuttle.adoc
@@ -6,42 +6,32 @@
== Description
-Shuttle is a non-realtime HAL component that interfaces Contour Design's
-ShuttleXpress, ShuttlePRO, and ShuttlePRO2 devices with LinuxCNC's HAL.
+Shuttle is a non-realtime HAL component that interfaces Contour Design's ShuttleXpress, ShuttlePRO, and ShuttlePRO2 devices with LinuxCNC's HAL.
-If the driver is started without command-line arguments, it will probe
-all /dev/hidraw* device files for Shuttle devices, and use all devices
-found. If it is started with command-line arguments, it will only
-probe the devices specified.
+If the driver is started without command-line arguments,
+it will probe all /dev/hidraw* device files for Shuttle devices, and use all devices found.
+If it is started with command-line arguments, it will only probe the devices specified.
-The ShuttleXpress has five momentary buttons, a 10 counts/revolution
-jog wheel with detents, and a 15-position spring-loaded outer wheel that
-returns to center when released.
+The ShuttleXpress has five momentary buttons, a 10 counts/revolution jog wheel with detents,
+and a 15-position spring-loaded outer wheel that returns to center when released.
-The ShuttlePRO has 13 momentary buttons, a 10 counts/revolution jog
-wheel with detents, and a 15-position spring-loaded outer wheel that
-returns to center when released.
+The ShuttlePRO has 13 momentary buttons, a 10 counts/revolution jog wheel with detents,
+and a 15-position spring-loaded outer wheel that returns to center when released.
-The ShuttlePRO2 has 15 momentary buttons, a 10 counts/revolution jog
-wheel with detents, and a 15-position spring-loaded outer wheel that
-returns to center when released.
+The ShuttlePRO2 has 15 momentary buttons, a 10 counts/revolution jog wheel with detents,
+and a 15-position spring-loaded outer wheel that returns to center when released.
[WARNING]
-=====
-The Shuttle devices have an internal 8-bit counter for the current
-jog-wheel position. The shuttle driver can not know this value until the
-Shuttles device sends its first event. When the first event comes into
-the driver, the driver uses the device's reported jog-wheel position
-to initialize counts to 0.
+====
+The Shuttle devices have an internal 8-bit counter for the current jog-wheel position.
+The shuttle driver can not know this value until the Shuttles device sends its first event.
+When the first event comes into the driver, the driver uses the device's reported jog-wheel position to initialize counts to 0.
-This means that if the first event is generated by a jog-wheel move,
-that first move will be lost.
+This means that if the first event is generated by a jog-wheel move, that first move will be lost.
-Any user interaction with the Shuttle device will generate an event,
-informing the driver of the jog-wheel position. So if you (for example)
-push one of the buttons at startup, the jog-wheel will work fine and
-notice the first click.
-=====
+Any user interaction with the Shuttle device will generate an event, informing the driver of the jog-wheel position.
+So if you (for example) push one of the buttons at startup, the jog-wheel will work fine and notice the first click.
+====
== Setup
@@ -56,33 +46,27 @@ SUBSYSTEM=="hidraw", ATTRS{idVendor}=="05f3", ATTRS{idProduct}=="0240", MODE="04
SUBSYSTEM=="hidraw", ATTRS{idVendor}=="0b33", ATTRS{idProduct}=="0030", MODE="0444"
----
-The LinuxCNC Debian package installs an appropriate udev file
-automatically, but if you are building LinuxCNC from source and are not
-using the Debian packaging you'll need to install this file by hand.
-If you install the file by hand you'll need to tell udev to reload its
-rules files by running `udevadm control --reload-rules`.
+The LinuxCNC Debian package installs an appropriate udev file automatically,
+but if you are building LinuxCNC from source and are not using the Debian packaging you'll need to install this file by hand.
+If you install the file by hand you'll need to tell udev to reload its rules files by running `udevadm control --reload-rules`.
== Pins
-All HAL pin names are prefixed with `shuttle` followed by the index
-of the device (the order in which the driver found them), for example
-"shuttle.0" or "shuttle.2".
+All HAL pin names are prefixed with `shuttle` followed by the index of the device (the order in which the driver found them),
+for example `shuttle.0` or `shuttle.2`.
-'<Prefix>.button-<ButtonNumber>' (bit out)::
+_<Prefix>_`.button-<ButtonNumber>` (bit out)::
These pins are True (1) when the button is pressed.
-'<Prefix>.button-<ButtonNumber>-not' (bit out)::
+_<Prefix>_`.button-<ButtonNumber>-not` (bit out)::
These pins have the inverse of the button state, so they're True (1) when the button is not pressed.
-'<Prefix>.counts' (s32 out)::
+_<Prefix>_`.counts` (s32 out)::
Accumulated counts from the jog wheel (the inner wheel).
-'<Prefix>.spring-wheel-s32' (s32 out)::
+_<Prefix>_`.spring-wheel-s32` (s32 out)::
The current deflection of the spring-wheel (the outer wheel).
- It's 0 at rest, and ranges from -7 at the counter-clockwise extreme
- to +7 at the clockwise extreme.
-'<Prefix>.spring-wheel-f' (float out)::
+ It's 0 at rest, and ranges from -7 at the counter-clockwise extreme to +7 at the clockwise extreme.
+_<Prefix>_`.spring-wheel-f` (float out)::
The current deflection of the spring-wheel (the outer wheel).
- It's 0.0 at rest, -1.0 at the counter-clockwise extreme, and +1.0 at
- the clockwise extreme. (The Shuttle devices report the spring-wheel
- position as an integer from -7 to +7, so this pin reports only 15
- discrete values in it's range.)
+ It's 0.0 at rest, -1.0 at the counter-clockwise extreme, and +1.0 at the clockwise extreme.
+ The Shuttle devices report the spring-wheel position as an integer from -7 to +7, so this pin reports only 15 discrete values in it's range.
// vim: set syntax=asciidoc:
diff --git a/docs/src/getting-started/updating-linuxcnc.adoc b/docs/src/getting-started/updating-linuxcnc.adoc
index b70309726f..d06ef80064 100644
--- a/docs/src/getting-started/updating-linuxcnc.adoc
+++ b/docs/src/getting-started/updating-linuxcnc.adoc
@@ -19,12 +19,12 @@ updates. If you don't have an internet connection to your PC see
== Upgrade to the new version
-This section describes how to upgrade LinuxCNC from version 2.7 to the
-new 2.8.0 version. It assumes that you have an existing 2.7 install that you
+This section describes how to upgrade LinuxCNC from version 2.8 to the
+new 2.9.0 version. It assumes that you have an existing 2.8 install that you
want to update.
-To upgrade LinuxCNC from a version older than 2.7, you have to first
-https://linuxcnc.org/docs/2.7/html/getting-started/updating-linuxcnc.html[upgrade your old install to 2.7],
+To upgrade LinuxCNC from a version older than 2.8, you have to first
+https://linuxcnc.org/docs/2.8/html/getting-started/updating-linuxcnc.html[upgrade your old install to 2.8],
then follow these instructions to upgrade to the new version.
If you do not have an old version of LinuxCNC to upgrade, then you're
@@ -39,9 +39,9 @@ as these releases were EOL in 2017 and 2018 respectively.
If you are running on Ubuntu Lucid then you will have to do this, as
Lucid is no longer supported by LinuxCNC (it was EOL in 2013).
-To upgrade major versions like 2.7 to 2.8 when you have a network connection at
-the machine you need to disable the old linuxcnc.org apt sources in the file /etc/apt/sources.list and add a new
-linuxcnc.org apt source for 2.7, then upgrade LinuxCNC.
+To upgrade major versions like 2.8 to 2.9 when you have a network connection at
+the machine you need to disable the old linuxcnc.org apt sources in the file /etc/apt/sources.list and add a new
+linuxcnc.org apt source for 2.9, then upgrade LinuxCNC.
The details will depend on which platform you're running on. Open a
<<faq:terminal,terminal>> then type `lsb_release -ic` to find this information
@@ -183,6 +183,39 @@ package manager with this command:
sudo dpkg -i linuxcnc_2.8.0.deb
----
+
+== Updating Configuration Files for 2.9
+
+=== Stricter handling of pluggable interpreters
+
+If you just run regular G-code and you don't know what a pluggable
+interpreter is, then this section does not affect you.
+
+A seldom-used feature of LinuxCNC is support for pluggable interpreters,
+controlled by the undocumented `[TASK]INTERPRETER` INI setting.
+
+Versions of LinuxCNC before 2.9.0 used to handle an incorrect
+`[TASK]INTERPRETER` setting by automatically falling back to using the
+default G-code interpreter.
+
+As of 2.9.0, an incorrect `[TASK]INTERPRETER` value will cause
+LinuxCNC to refuse to start up. Fix this condition by deleting the
+`[TASK]INTERPRETER` setting from your INI file, so that LinuxCNC will
+use the default G-code interpreter.
+
+
+=== Canterp
+
+If you just run regular G-code and you don't use the `canterp` pluggable
+interpreter, then this section does not affect you.
+
+In the extremely unlikely event that you are using `canterp`,
+know that the module has moved from `/usr/lib/libcanterp.so` to
+`/usr/lib/linuxcnc/canterp.so`, and the `[TASK]INTERPRETER` setting
+correspondingly needs to change from `libcanterp.so` to `canterp.so`.
+
+
+
== Updating Configuration Files (for 2.8.x)
The new version of LinuxCNC differs from version 2.7 in some ways that
diff --git a/docs/src/gui/gmoccapy.adoc b/docs/src/gui/gmoccapy.adoc
index d13793e86d..011cefc88b 100644
--- a/docs/src/gui/gmoccapy.adoc
+++ b/docs/src/gui/gmoccapy.adoc
@@ -10,63 +10,57 @@
:ini: {basebackend@docbook:'':ini}
:hal: {basebackend@docbook:'':hal}
:ngc: {basebackend@docbook:'':ngc}
+:css: {basebackend@docbook:'':css}
== Introduction
GMOCCAPY is a GUI for LinuxCNC, designed to be used with a touch screen,
-but can also be used on normal screens with a mouse or hardware buttons and MPG
-wheels, as it presents HAL Pins for the most common needs. Please find more
-information in the following.
+but can also be used on normal screens with a mouse or hardware buttons and MPG wheels,
+as it presents HAL Pins for the most common needs.
+Please find more information in the following.
-It offers the possibility to display up to 9 axes, support a lathe mode for
-normal and back tool lathe and can be adapted to nearly every need, because
-GMOCCAPY supports embedded tabs and side panels.
-As a good example for that see
-https://wiki.linuxcnc.org/cgi-bin/wiki.pl?Gmoccapy_plasma[gmoccapy_plasma].
+It offers the possibility to display up to 9 axes,
+support a lathe mode for normal and back tool lathe and can be adapted to nearly every need,
+because GMOCCAPY supports embedded tabs and side panels.
+As a good example for that see https://wiki.linuxcnc.org/cgi-bin/wiki.pl?Gmoccapy_plasma[gmoccapy_plasma].
-GMOCCAPY 3 does support up to 9 axes and 9 joints. As GMOCCAPY 3 has been
-changed in code to support the joint / axis changes in LinuxCNC it does not
-work on 2.7 or 2.6 branch!
+GMOCCAPY 3 does support up to 9 axes and 9 joints.
+As GMOCCAPY 3 has been changed in code to support the joint / axis changes in LinuxCNC it does not work on 2.7 or 2.6 branch!
It has support for integrated virtual keyboard (onboard or matchbox-keyboard),
-so there is no need for a hardware keyboard or mouse, but it can also be used
-with that hardware. GMOCCAPY offers a separate settings page to configure most
-settings of the GUI without editing files.
-
-GMOCCAPY can be localized very easy, because the corresponding files are
-separated from the linuxcnc.po files, so there is no need to translate unneeded
-stuff. The files are placed in */src/po/gmoccapy*. You could just copy the gmoccapy.pot
-file to something like it.po and translate that file with gtranslator or poedit.
-After rebuilding, you'd get the GUI in your preference language. To facilitate the
-sharing of the translation, GMOCCAPY is available on the
-https://hosted.weblate.org/projects/linuxcnc/gmocappy/[Weblate web interface].
-GMOCCAPY is currently available in English, German,
-Spanish, Polish, Serbian and Hungarian. Feel free to help me to introduce more
-languages, be it locally or via the web.
+so there is no need for a hardware keyboard or mouse, but it can also be used with that hardware.
+GMOCCAPY offers a separate settings page to configure most settings of the GUI without editing files.
+
+GMOCCAPY can be localized very easy, because the corresponding files are separated from the linuxcnc.po files,
+so there is no need to translate unneeded stuff.
+The files are placed in */src/po/gmoccapy*.
+You could just copy the gmoccapy.pot file to something like it.po and translate that file with gtranslator or poedit.
+After rebuilding, you'd get the GUI in your preference language.
+To facilitate the sharing of the translation,
+GMOCCAPY is available on the https://hosted.weblate.org/projects/linuxcnc/gmocappy/[Weblate web interface].
+GMOCCAPY is currently available in English, German, Spanish, Polish, Serbian and Hungarian.
+Feel free to help me to introduce more languages, be it locally or via the web.
If you need help, don't hesitate to contact me on *nieson@web.de*.
image:images/gmoccapy_5_axis_mid.png[align="left",link="images/gmoccapy_5_axis.png"]
== Requirements
-GMOCCAPY 3 has been tested on Debian Jessie, Debian Stretch and MINT 18
-with LinuxCNC master and 2.8 release. It fully support joint / axis changes of LinuxCNC, making
-it suitable as GUI for Scara, Robots or any other config with more joints than
-axes. So it supports also gantry configs. If you use other versions, please
-inform about problems and / or solutions on the
+GMOCCAPY 3 has been tested on Debian Jessie, Debian Stretch and MINT 18 with LinuxCNC master and 2.8 release.
+It fully support joint / axis changes of LinuxCNC, making it suitable as GUI for Scara, Robots or any other config with more joints than axes.
+So it supports also gantry configs.
+If you use other versions, please inform about problems and / or solutions on the
https://linuxcnc.org/index.php/english/forum/41-guis/26314-gmoccapy-a-new-screen-for-linuxcnc[LinuxCNC forum] or the
http://www.cncecke.de/forum/showthread.php?t=78549[German CNC Ecke Forum] or
https://lists.sourceforge.net/lists/listinfo/emc-users[LinuxCNC users mailing list].
-The minimum screen resolution for GMOCCAPY, using it without side panels is
-*979 x 750 Pixel*, so it should fit to every standard screen. It is recommended to use
-screens with minimum resolution of 1024x748.
+The minimum screen resolution for GMOCCAPY, using it without side panels is *979 x 750 Pixel*, so it should fit to every standard screen.
+It is recommended to use screens with minimum resolution of 1024x748.
== How to Get GMOCCAPY
GMOCCAPY 3 is included in the standard distribution of LinuxCNC since release 2.7.
-So the easiest way to get GMOCCAPY on your controlling PC, is just to download the
-https://linuxcnc.org/downloads/[ISO] and install it from the CD/DVD/USB-stick.
+So the easiest way to get GMOCCAPY on your controlling PC is just to download the https://linuxcnc.org/downloads/[ISO] and install it from the CD/DVD/USB-stick.
This allows you to receive updates with the regular Debian packages.
In the link:gmoccapy_release_notes.txt[*release notes*] aka changelist you can track the latest bugfixes and features.
@@ -82,8 +76,8 @@ GMOCCAPY 3 supports the following command line options:
* '-user_mode': If set, the setup button will be disabled, so normal machine operators are not able to edit the settings of the machine.
* '-logo <path to logo file>': If given, the logo will hide the jog button tab in manual mode, this is only useful for machines with hardware buttons for jogging and increment selection.
-There is really not to much to configure just to run GMOCCAPY, but there are some points
-you should take care off if you want to use all the features of the GUI.
+There is really not to much to configure just to run GMOCCAPY,
+but there are some points you should take care off if you want to use all the features of the GUI.
You will find a lot of simulation configurations (INI files) included, just to show the basics:
@@ -110,8 +104,7 @@ The names should explain the main intention of the different INI files.
If you use an existing configuration of your machine, just edit your INI according to this document.
-So let us take a closer look at the INI file and what you need to include
-to use GMOCCAPY on your machine:
+So let us take a closer look at the INI file and what you need to include to use GMOCCAPY on your machine:
[[gmoccapy:display-section]]
=== The DISPLAY Section
@@ -144,23 +137,20 @@ settings will not be mixed if you use several configs. If you only want to use
one file for several machines, you need to include `PREFERENCE_FILE_PATH` in your
INI.
-- _MAX_FEED_OVERRIDE = 1.5_ - Sets the maximum feed override, in the example given,
-you will be allowed to override the feed by 150%.
+- _MAX_FEED_OVERRIDE = 1.5_ - Sets the maximum feed override, in the example given, you will be allowed to override the feed by 150%.
+
[NOTE]
If no value is given, it will be set to 1.0.
-- _MIN_SPINDLE_OVERRIDE = 0.5_ and _MAX_SPINDLE_OVERRIDE = 1.2_ -
-Will allow you to change the spindle override within a limit from 50% to 120%.
+- _MIN_SPINDLE_OVERRIDE = 0.5_ and _MAX_SPINDLE_OVERRIDE = 1.2_ - Will allow you to change the spindle override within a limit from 50% to 120%.
+
[NOTE]
If no values are given, MIN will be set to 0.1 and MAX to 1.0.
- _LATHE = 1_ - Set the screen layout to control a lathe.
-- _BACK_TOOL_LATHE = 1_ - Is optional and will switch the X axis in a way you need for a
-back tool lathe. Also the keyboard shortcuts will react in a different way.
-It is allowed with GMOCCAPY to configure a lathe also with additional axes,
-so you may use also a XZCW config for a lathe.
+- _BACK_TOOL_LATHE = 1_ - Is optional and will switch the X axis in a way you need for a back tool lathe.
+Also the keyboard shortcuts will react in a different way.
+It is allowed with GMOCCAPY to configure a lathe also with additional axes, so you may use also a XZCW config for a lathe.
+
[TIP]
See also the <<gmoccapy:lathe-section,Lathe Specific Section>>.
@@ -191,10 +181,10 @@ Defaults to 600 if not set.
[[gmoccapy:macros]]
=== Macro Buttons
-You can add macros to GMOCCAPY, similar to Touchy's way. A macro is nothing
-else than a NGC file. You are able to execute complete CNC programs in MDI
-mode by just pushing one button. To do so, you first have to specify the search
-path for macros:
+You can add macros to GMOCCAPY, similar to Touchy's way.
+A macro is nothing else than a NGC file.
+You are able to execute complete CNC programs in MDI mode by just pushing one button.
+To do so, you first have to specify the search path for macros:
[[gmocappy:rs274ngc]]
[source,{ini}]
@@ -202,8 +192,8 @@ path for macros:
[RS274NGC]
SUBROUTINE_PATH = macros
----
-This sets the path to search for macros and other subroutines. Several subroutine
-paths can be separated ":".
+This sets the path to search for macros and other subroutines.
+Several subroutine paths can be separated ":".
Then you just have to add a section like this:
@@ -220,20 +210,16 @@ MACRO = go_to_position X-pos Y-pos Z-pos
Then you have to provide the corresponding NGC files which have to follow these rules:
-* The name of the file need to be exactly the same as the name mentioned in the macro
- line, just with the ".ngc" extension (case sensitive).
-* The file must contain a subroutine like '*O<i_am_lost> sub*', the name
- of the sub must match exactly (case sensitive) the name of the macro.
+* The name of the file need to be exactly the same as the name mentioned in the macro line, just with the ".ngc" extension (case sensitive).
+* The file must contain a subroutine like '*O<i_am_lost> sub*', the name of the sub must match exactly (case sensitive) the name of the macro.
* The file must end with an endsub '*O<i_am_lost> endsub*' followed by an '*M2*' command.
-* The files need to be placed in a folder specified in your INI file by 'SUBROUTINE_PATH' in the
- RS274NGC section
+* The files need to be placed in a folder specified in your INI file by 'SUBROUTINE_PATH' in the RS274NGC section
-The code between sub and endsub will be executed by pushing the
-corresponding macro button.
+The code between sub and endsub will be executed by pushing the corresponding macro button.
[NOTE]
-A maximum of 16 macros will be shown in the GUI. Due to space reasons you may need to
-click on an arrow to switch the page and display hidden macro buttons.
+A maximum of 16 macros will be shown in the GUI.
+Due to space reasons you may need to click on an arrow to switch the page and display hidden macro buttons.
The macro buttons will be displayed in the order of the INI entries.
It is no error placing more than 16 macros in your INI file, they will just not be shown.
@@ -241,9 +227,9 @@ It is no error placing more than 16 macros in your INI file, they will just not
//image::images/gmoccapy_mdi_hidden_keyboard.png[align="left"]
[NOTE]
-You will find the sample macros in a folder named 'macros' placed in the GMOCCAPY
-sim folder. If you have given several subroutine paths, they will be searched
-in the order of the given paths. The first file found will be used.
+You will find the sample macros in a folder named 'macros' placed in the GMOCCAPY sim folder.
+If you have given several subroutine paths, they will be searched in the order of the given paths.
+The first file found will be used.
GMOCCAPY will also accept macros asking for parameters like:
[source,{ini}]
@@ -281,13 +267,11 @@ O<go_to_position> endsub
M2
----
-After pushing the '*execute macro button*', you will be asked to enter the
-values for '*X-pos Y-pos Z-pos*' and the macro will only run if all values
-have been given.
+After pushing the '*execute macro button*',
+you will be asked to enter the values for '*X-pos Y-pos Z-pos*' and the macro will only run if all values have been given.
[NOTE]
-If you would like to use a macro without any movement,
-see also the notes in <<sub:NOT_ENDING_MACROS,known problems>>.
+If you would like to use a macro without any movement, see also the notes in <<sub:NOT_ENDING_MACROS,known problems>>.
.Macro example using the "go to position"-macro
image:images/gmoccapy_getting_macro_info_mid.png[align="left",link="images/gmoccapy_getting_macro_info.png"]
@@ -295,9 +279,8 @@ image:images/gmoccapy_getting_macro_info_mid.png[align="left",link="images/gmocc
[[gmoccapy:configuration-of-tabs-and-side-panels]]
=== Embedded Tabs and Panels
-You can add embedded programs to GMOCCAPY like you can do in AXIS, Touchy and
-Gscreen. All is done by GMOCCAPY automatically if you include a few lines in
-your INI file in the DISPLAY section.
+You can add embedded programs to GMOCCAPY like you can do in AXIS, Touchy and Gscreen.
+All is done by GMOCCAPY automatically if you include a few lines in your INI file in the DISPLAY section.
If you have never used a Glade panel, I recommend to read the excellent documentation
on https://linuxcnc.org/docs/2.9/html/gui/gladevcp.html[Glade VCP].
@@ -317,8 +300,7 @@ EMBED_TAB_COMMAND = gladevcp -x {XID} vcp_box.glade
All you have to take care of, is that you include for every tab or side panel the mentioned three lines:
-* EMBED_TAB_NAME = Represents the name of the tab or side panel, it is up to you
- what name you use, but it must be present!
+* EMBED_TAB_NAME = Represents the name of the tab or side panel, it is up to you what name you use, but it must be present!
* EMBED_TAB_LOCATION = The place where your program will be placed in the GUI, see figure <<fig:gmoccapy_emb_tab_locations,Embedded tab locations>>. Valid values are:
** *ntb_user_tabs* (as main tab, covering the complete screen)
** *ntb_preview* (as tab on the preview side *(1)*)
@@ -346,24 +328,22 @@ See also the included sample INI files to see the differences.
gladevcp -x {XID} dro.glade
----
+
-includes a custom glade file called dro.glade in the mentioned location
+includes a custom glade file called dro.glade in the mentioned location.
The file must be placed in the config folder of your machine.
+
----
gladevcp h_buttonlist.glade
----
+
-will just open a new user window called h_buttonlist.glade note the difference,
-this one is stand alone, and can be moved around independent from GMOCCAPY
-window.
+will just open a new user window called h_buttonlist.glade note the difference.
+This one is stand alone, and can be moved around independent from GMOCCAPY window.
+
----
gladevcp -c gladevcp -u hitcounter.py -H manual-example.hal manual-example.ui
----
+
will add a the panel manual-example.ui, include a custom Python handler,
-hitcounter.py and make all connections after realizing the panel according to
-manual-example.hal.
+hitcounter.py and make all connections after realizing the panel according to manual-example.hal.
+
----
hide
@@ -376,15 +356,13 @@ will hide the chosen box.
image::images/gmoccapy_embedded_tabs.png[align="left"]
[NOTE]
-If you make any HAL connections to your custom glade panel, you need to do that in the HAL file
-specified in the EMBED_TAB_COMMAND line, otherwise you may get an error that the HAL pin does not exist --
-this is because of race conditions loading the HAL files. Connections to GMOCCAPY HAL pins need to be made in the
-postgui HAL file specified in your INI file, because these pins do not exist prior of realizing the GUI.
+If you make any HAL connections to your custom glade panel, you need to do that in the HAL file specified in the EMBED_TAB_COMMAND line,
+otherwise you may get an error that the HAL pin does not exist -- this is because of race conditions loading the HAL files.
+Connections to GMOCCAPY HAL pins need to be made in the postgui HAL file specified in your INI file,
+because these pins do not exist prior of realizing the GUI.
Here are some examples:
-
-
[cols="10a,13a", grid="none", frame="none"]
|===
|.ntb_preview
@@ -395,8 +373,8 @@ image:images/gmoccapy_with_right_panel_in_MDI_mode_small.png[align="left",link="
[[sub:gmocccapy-configuration-user-messages]]
=== User Created Messages
-GMOCCAPY has the ability to create HAL driven user messages. To use them you
-need to introduce some lines in the [DISPLAY] section of the INI file.
+GMOCCAPY has the ability to create HAL driven user messages.
+To use them you need to introduce some lines in the [DISPLAY] section of the INI file.
These three lines are needed to define a user pop up message dialog:
[source,{ini}]
@@ -412,12 +390,9 @@ https://developer.gnome.org/pango/stable/PangoMarkupFormat.html[Pango Markup].
The following three dialog types are available:
-* *status* - Will just display a message as pop up window, using the messaging
- system of GMOCCAPY.
-* *okdialog* - Will hold focus on the message dialog and will activate a
- `-waiting` HAL pin.
-* *yesnodialog* - Will hold focus on the message dialog and will activate
- a `-waiting` HAL pin and provide a `-response` HAL pin.
+* *status* - Will just display a message as pop up window, using the messaging system of GMOCCAPY.
+* *okdialog* - Will hold focus on the message dialog and will activate a `-waiting` HAL pin.
+* *yesnodialog* - Will hold focus on the message dialog and will activate a `-waiting` HAL pin and provide a `-response` HAL pin.
For more detailed information of the pins see <<gmoccapy:user-created-message,User Created Message HAL Pins>>.
@@ -440,12 +415,11 @@ MESSAGE_PINNAME = okdialog
[NOTE]
Currently the formatting doesn't work.
-
-
=== Preview Control
Magic comments can be used to control the G-code preview.
-On very large programs the preview can take a long time to load. You can control what is shown and what is hidden on the graphics screen by adding the appropriate comments from this list into your G-code:
+On very large programs the preview can take a long time to load.
+You can control what is shown and what is hidden on the graphics screen by adding the appropriate comments from this list into your G-code:
----
(PREVIEW,hide)
@@ -453,36 +427,94 @@ On very large programs the preview can take a long time to load. You can control
(PREVIEW,show)
----
+=== User Command File
+
+If a file ~/.gmoccapyrc exists, its contents are executed as Python source code just after
+the GUI is displayed. The details of what may be written in the ~/.gmoccapyrc are subject
+to change during the development cycle.
+
+A configuration-specific Python file may be specified with an INI file setting
+[source,{ini}]
+----
+[DISPLAY]
+USER_COMMAND_FILE=filename.py
+----
+If this file is specified, this file is sourced just after the AXIS GUI is displayed
+*instead* of ~/.gmoccapyrc.
+
+
+The following example changes the size of the vertical buttons and changes the order of buttons:
+.Example of .axisrc file
+-----
+self.widgets.vbtb_main.set_size_request(85,-1)
+BB_SIZE = (70, 70) # default = (90, 56)
+self.widgets.tbtn_estop.set_size_request(*BB_SIZE)
+self.widgets.tbtn_on.set_size_request(*BB_SIZE)
+self.widgets.rbt_manual.set_size_request(*BB_SIZE)
+self.widgets.rbt_mdi.set_size_request(*BB_SIZE)
+self.widgets.rbt_auto.set_size_request(*BB_SIZE)
+self.widgets.tbtn_setup.set_size_request(*BB_SIZE)
+self.widgets.tbtn_user_tabs.set_size_request(*BB_SIZE)
+self.widgets.btn_exit.set_size_request(*BB_SIZE)
+
+self.widgets.vbtb_main.remove(self.widgets.tbtn_setup)
+self.widgets.vbtb_main.remove(self.widgets.lbl_time)
+self.widgets.vbtb_main.add(self.widgets.tbtn_setup)
+self.widgets.vbtb_main.add(self.widgets.lbl_time)
+-----
+
+The widget names can the looked up in the /usr/share/gmoccapy.glade file
+
+=== User CSS File
+
+Similar to the User command file it's possible to influence the appearance by cascading style sheets (CSS).
+If a file ~/.gmoccapy_css exists, its contents are loaded into the stylesheet provider and are so beeing applied to the GUI.
+
+A configuration-specific CSS file may be specified with an INI file setting
+[source,{ini}]
+----
+[DISPLAY]
+USER_CSS_FILE=filename.css
+----
+If this file is specified, this file is used *instead* of ~/.gmoccapy_css.
+
+Information what can be controlled by CSS can be found here: link:https://docs.gtk.org/gtk3/css-overview.html[Overview of CSS in GTK]
+
+Here an example how the color of checked buttons can be set to yellow:
+.Example Yellow color for checked buttons
+[source,{css}]
+----
+button:checked {
+ background: rgba(250,230,0,0.8);
+}
+----
+
+
== HAL Pins
GMOCCAPY exports several HAL pins to be able to react to hardware devices.
-The goal is to get a GUI that may be operated in a tool shop, completely/mostly
-without mouse or keyboard.
+The goal is to get a GUI that may be operated in a tool shop, completely/mostly without mouse or keyboard.
[NOTE]
====
You will have to do all connections to GMOCCAPY pins in your postgui.hal file.
-When GMOCCAPY is started, it creates the HAL pins for the GUI then it executes
-the post-GUI HAL file named in the INI file:
+When GMOCCAPY is started, it creates the HAL pins for the GUI then it executes the post-GUI HAL file named in the INI file:
[source,{ini}]
----
[HAL]
POSTGUI_HALFILE=<filename>
----
-Typically `<filename>` would be the configs base name + `_postgui.hal`,
-e.g. `lathe_postgui.hal`, but can be any legal filename. +
-These commands are executed after the screen is built, guaranteeing the widget's HAL
-pins are available. +
+Typically `<filename>` would be the configs base name + `_postgui.hal`, e.g. `lathe_postgui.hal`, but can be any legal filename. +
+These commands are executed after the screen is built, guaranteeing the widget's HAL pins are available. +
You can have multiple line of `POSTGUI_HALFILE=<filename>` in the INI file.
Each will be run one after the other in the order they appear.
====
=== Right and Bottom Button Lists
-The screen has two main button lists, one on the right side an one on the
-bottom. The right handed buttons will not change during operation, but the
-bottom button list will change very often. The buttons are count from up to
-down and from left to right beginning with 0.
+The screen has two main button lists, one on the right side an one on the bottom.
+The right handed buttons will not change during operation, but the bottom button list will change very often.
+The buttons are count from up to down and from left to right beginning with 0.
[NOTE]
The pin names have changed in GMOCCAPY 2 to order them in a better way.
@@ -510,10 +542,9 @@ For the bottom (horizontal) buttons they are:
* *gmoccapy.h-button.button-8* _(bit IN)_
* *gmoccapy.h-button.button-9* _(bit IN)_
-As the buttons in the bottom list will change according to the mode and other
-influences, the hardware buttons will activate the displayed functions. So you
-don't have to take care about switching functions around in HAL, because that
-is done completely by GMOCCAPY!
+As the buttons in the bottom list will change according to the mode and other influences,
+the hardware buttons will activate the displayed functions.
+So you don't have to take care about switching functions around in HAL, because that is done completely by GMOCCAPY!
For a three axes XYZ machine the HAL pins will react as shown in the following three tables:
@@ -521,17 +552,17 @@ For a three axes XYZ machine the HAL pins will react as shown in the following t
.Functional assignment of horizontal buttons (1)
[cols="10,10,10,10", options="header"]
|====
-| Pin | Manual Mode | MDI Mode | Auto Mode
-| gmoccapy.h-button.button-0 | open homing button | macro_0 or nothing | open file
-| gmoccapy.h-button.button-1 | open touch off stuff | macro_1 or nothing | reload program
-| gmoccapy.h-button.button-2 | | macro_2 or nothing | run
-| gmoccapy.h-button.button-3 | open tool dialogs | macro_3 or nothing | stop
-| gmoccapy.h-button.button-4 | | macro_4 or nothing | pause
-| gmoccapy.h-button.button-5 | | macro_5 or nothing | step by step
-| gmoccapy.h-button.button-6 | | macro_6 or nothing | run from line if enabled in settings, otherwise Nothing
-| gmoccapy.h-button.button-7 | | macro_7 or nothing | optional blocks
-| gmoccapy.h-button.button-8 | full-size preview | macro_8 or switch page to additional macros | full-size preview
-| gmoccapy.h-button.button-9 | exit if machine is off, otherwise no reaction | open keyboard or abort if macro is running | edit code
+| Pin | Manual Mode | MDI Mode | Auto Mode
+m| gmoccapy.h-button.button-0 | open homing button | macro_0 or nothing | open file
+m| gmoccapy.h-button.button-1 | open touch off stuff | macro_1 or nothing | reload program
+m| gmoccapy.h-button.button-2 | | macro_2 or nothing | run
+m| gmoccapy.h-button.button-3 | open tool dialogs | macro_3 or nothing | stop
+m| gmoccapy.h-button.button-4 | | macro_4 or nothing | pause
+m| gmoccapy.h-button.button-5 | | macro_5 or nothing | step by step
+m| gmoccapy.h-button.button-6 | | macro_6 or nothing | run from line if enabled in settings, otherwise Nothing
+m| gmoccapy.h-button.button-7 | | macro_7 or nothing | optional blocks
+m| gmoccapy.h-button.button-8 | full-size preview | macro_8 or switch page to additional macros | full-size preview
+m| gmoccapy.h-button.button-9 | exit if machine is off, otherwise no reaction | open keyboard or abort if macro is running | edit code
|====
[[table:b]]
@@ -539,16 +570,16 @@ For a three axes XYZ machine the HAL pins will react as shown in the following t
[cols="10,10,10,10", options="header"]
|====
| Pin | Settings Mode | Homing Mode | Touch off Mode
-| gmoccapy.h-button.button-0 | delete MDI history | | edit offsets
-| gmoccapy.h-button.button-1 | | home all | touch X
-| gmoccapy.h-button.button-2 | | | touch Y
-| gmoccapy.h-button.button-3 | | home x | touch Z
-| gmoccapy.h-button.button-4 | open classic ladder | home y |
-| gmoccapy.h-button.button-5 | open HAL scope | home z |
-| gmoccapy.h-button.button-6 | open HAL status | | zero G92
-| gmoccapy.h-button.button-7 | open HAL meter | |
-| gmoccapy.h-button.button-8 | open HAL calibration | unhome all | set selected
-| gmoccapy.h-button.button-9 | open HAL show | back | back
+m|gmoccapy.h-button.button-0 | delete MDI history | | edit offsets
+m|gmoccapy.h-button.button-1 | | home all | touch X
+m|gmoccapy.h-button.button-2 | | | touch Y
+m|gmoccapy.h-button.button-3 | | home x | touch Z
+m|gmoccapy.h-button.button-4 | open classic ladder | home y |
+m|gmoccapy.h-button.button-5 | open HAL scope | home z |
+m|gmoccapy.h-button.button-6 | open HAL status | | zero G92
+m|gmoccapy.h-button.button-7 | open HAL meter | |
+m|gmoccapy.h-button.button-8 | open HAL calibration | unhome all | set selected
+m|gmoccapy.h-button.button-9 | open HAL show | back | back
|====
[[table:c]]
@@ -556,23 +587,23 @@ For a three axes XYZ machine the HAL pins will react as shown in the following t
[cols="10,10,10,10", options="header"]
|====
| Pin | Tool Mode | Edit Mode | Select File
-| gmoccapy.h-button.button-0 | delete tool(s) | | go to home directory
-| gmoccapy.h-button.button-1 | new tool | reload file | one directory level up
-| gmoccapy.h-button.button-2 | reload tool table | save |
-| gmoccapy.h-button.button-3 | apply changes | save as | move selection left
-| gmoccapy.h-button.button-4 | change tool by number T? M6 | | move selection right
-| gmoccapy.h-button.button-5 | set tool by number without change M61 Q? | | jump to directory as set in settings
-| gmoccapy.h-button.button-6 | change tool to the selected one | new file |
-| gmoccapy.h-button.button-7 | | | select / ENTER
-| gmoccapy.h-button.button-8 | touch of tool in Z | show keyboard |
-| gmoccapy.h-button.button-9 | back | back | back
+m|gmoccapy.h-button.button-0 | delete tool(s) | | go to home directory
+m|gmoccapy.h-button.button-1 | new tool | reload file | one directory level up
+m|gmoccapy.h-button.button-2 | reload tool table | save |
+m|gmoccapy.h-button.button-3 | apply changes | save as | move selection left
+m|gmoccapy.h-button.button-4 | change tool by number T? M6 | | move selection right
+m|gmoccapy.h-button.button-5 | set tool by number without change M61 Q? | | jump to directory as set in settings
+m|gmoccapy.h-button.button-6 | change tool to the selected one | new file |
+m|gmoccapy.h-button.button-7 | | | select / ENTER
+m|gmoccapy.h-button.button-8 | touch of tool in Z | show keyboard |
+m|gmoccapy.h-button.button-9 | back | back | back
|====
So we have 67 reactions with only 10 HAL pins!
-These pins are made available to be able to use the screen without an touch
-panel, or protect it from excessive use by placing hardware buttons around
-the panel. They are available in a sample configuration like shown in the <<gmoccapy-sim-hardware-button,image below>>.
+These pins are made available to be able to use the screen without an touch panel,
+or protect it from excessive use by placing hardware buttons around the panel.
+They are available in a sample configuration like shown in the <<gmoccapy-sim-hardware-button,image below>>.
[[gmoccapy-sim-hardware-button]]
.Sample configuration "gmoccapy_sim_hardware_button" showing the side buttons
@@ -641,20 +672,16 @@ In a future release it will be integrated in the settings page.
- *gmoccapy.spc_rapid.value* _(float OUT)_ - Value of the widget
- *gmoccapy.spc_rapid.scaled-value* _(float OUT)_ - Scaled value of the widget
-The float pins do accept values from 0.0 to 1.0, being the percentage value
-you want to set the slider value.
+The float pins do accept values from 0.0 to 1.0, being the percentage value you want to set the slider value.
[WARNING]
-If you use both connection types, do not connect the same slider to
-both pin, as the influences between the two has not been tested! Different
-sliders may be connected to the one or other HAL connection type.
+If you use both connection types, do not connect the same slider to both pin as the influences between the two has not been tested!
+Different sliders may be connected to the one or other HAL connection type.
[IMPORTANT]
Please be aware that the jog velocity depends on the turtle button state.
-It will lead to different slider scales depending on the mode
-(turtle or rabbit). Please take also a look at
-<<gmoccapy:jog-velocity,jog velocities and turtle-jog HAL pin>> for more
-details.
+It will lead to different slider scales depending on the mode (turtle or rabbit).
+Please take also a look at <<gmoccapy:jog-velocity,jog velocities and turtle-jog HAL pin>> for more details.
.Setting a slider value
====
@@ -670,8 +697,7 @@ value to set = 45 % +
=== Jog HAL Pins
-All axes given in the INI file have a jog-plus and a jog-minus pin, so
-hardware momentary switches can be used to jog the axes.
+All axes given in the INI file have a jog-plus and a jog-minus pin, so hardware momentary switches can be used to jog the axes.
[NOTE]
Naming of these HAL pins have changed in GMOCCAPY 2.
@@ -698,13 +724,12 @@ For a C-axis you will see:
[[gmoccapy:jog-velocity]]
=== Jog Velocities and Turtle-Jog HAL Pin
-The jog velocity can be selected with the corresponding slider. The scale of
-the slider will be modified if the turtle button (the one showing a rabbit or a
-turtle) has been toggled. If the button is not visible, it might have been
-disabled on the <<gmoccapy:turtle-jog,settings page>>. If the button shows the
-rabbit-icon, the scale is from min to max machine velocity. If it shows the
-turtle, the scale will reach only 1/20 of max velocity by default. The used
-divider can be set on the <<gmoccapy:turtle-jog,settings page>>.
+The jog velocity can be selected with the corresponding slider.
+The scale of the slider will be modified if the turtle button (the one showing a rabbit or a turtle) has been toggled.
+If the button is not visible, it might have been disabled on the <<gmoccapy:turtle-jog,settings page>>.
+If the button shows the rabbit-icon, the scale is from min to max machine velocity.
+If it shows the turtle, the scale will reach only 1/20 of max velocity by default.
+The used divider can be set on the <<gmoccapy:turtle-jog,settings page>>.
So using a touch screen it is much easier to select smaller velocities.
@@ -720,12 +745,9 @@ The jog increments given in the INI file like
[DISPLAY]
INCREMENTS = 5mm 1mm .5mm .1mm .05mm .01mm
----
-are selectable through HAL pins, so a selection hardware
-switch can be used to select the increment to use. There will be a maximum
-of 10 HAL pins for the increments given in the INI file.
-If you give more
-increments in your INI file, they will be not reachable from the GUI as they
-will not be displayed.
+are selectable through HAL pins, so a selection hardware switch can be used to select the increment to use.
+There will be a maximum of 10 HAL pins for the increments given in the INI file.
+If you give more increments in your INI file, they will be not reachable from the GUI as they will not be displayed.
If you have 6 increments in your INI file like in the example above, you will get *7* pins:
@@ -752,16 +774,14 @@ To use this pin, you need to activate it on the settings page.
=== Error/Warning Pins
-- *gmoccapy.error* _(bit OUT)_ - Indicates an error, so a light can lit or even the machine may
-be stopped. It will be reset with the pin `gmoccapy.delete-message`.
+- *gmoccapy.error* _(bit OUT)_ - Indicates an error, so a light can lit or even the machine may be stopped. It will be reset with the pin `gmoccapy.delete-message`.
- *gmoccapy.delete-message* _(bit IN)_ - Will delete the first error and reset the `gmoccapy.error` pin to false after the last error has been cleared.
- *gmoccapy.warning-confirm* _(bit IN)_ - Confirms warning dialog like click on OK
[NOTE]
====
-Messages or user infos will not affect the `gmoccapy.error` pin, but the `gmoccapy.delete-message`
-pin will delete the last message if no error is shown!
+Messages or user infos will not affect the `gmoccapy.error` pin, but the `gmoccapy.delete-message` pin will delete the last message if no error is shown!
====
[[gmoccapy:user-created-message]]
@@ -782,11 +802,11 @@ GMOCCAPY may be configured to react to external errors, using 3 different user m
- *gmoccapy.messages.yesnodialog* _(bit IN)_ - Triggers the dialog.
- *gmoccapy.messages.yesnodialog-waiting* _(bit OUT)_ - Will be '1' as long as the dialog is open. Closing the message will reset the this pin.
-- *gmoccapy.messages.yesnodialog-response* _(bit OUT)_ - This pin will change to '1' if the user clicks OK and in all
- other cases it will be '0'. This pin will remain '1' until the dialog is called again.
+- *gmoccapy.messages.yesnodialog-response* _(bit OUT)_ - This pin will change to '1' if the user clicks OK and in all other cases it will be '0'.
+ This pin will remain '1' until the dialog is called again.
-To add a user created message you need to add the message to the INI file in the
-DISPLAY section. See <<sub:gmocccapy-configuration-user-messages,Configuration of User Created Messages>>.
+To add a user created message you need to add the message to the INI file in the DISPLAY section.
+See <<sub:gmocccapy-configuration-user-messages,Configuration of User Created Messages>>.
.User Message Example (INI file)
[source,{ini}]
@@ -826,21 +846,19 @@ There are two pins for spindle feedback:
There are three pins giving information about the program progress:
-- *gmoccapy.program.length* _(s32 OUT)_ - Shows the total number of lines of the program
-- *gmoccapy.program.current-line* _(s32 OUT)_ - Indicates the current working line of the program
-- *gmoccapy.program.progress* _(float OUT)_ - Gives the program progress in percentage
+- *gmoccapy.program.length* _(s32 OUT)_ - Shows the total number of lines of the program.
+- *gmoccapy.program.current-line* _(s32 OUT)_ - Indicates the current working line of the program.
+- *gmoccapy.program.progress* _(float OUT)_ - Gives the program progress in percentage.
-The values may not be very accurate if you are working with subroutines or
-large remap procedures. Also loops will cause different values.
+The values may not be very accurate if you are working with subroutines or large remap procedures.
+Also loops will cause different values.
=== Tool Related Pins
.Tool Change Pins
-These pins are provided to use GMOCCAPY's internal tool change dialog, similar to
-the one known from AXIS, but with several modifications. So you will not only
-get the message to change to 'tool number 3', but also the description of that
-tool like '7.5 mm 3 flute cutter'. The information is taken from the tool
-table, so it is up to you what to display.
+These pins are provided to use GMOCCAPY's internal tool change dialog, similar to the one known from AXIS, but with several modifications.
+So you will not only get the message to change to 'tool number 3', but also the description of that tool like '7.5 mm 3 flute cutter'.
+The information is taken from the tool table, so it is up to you what to display.
.GMOCCAPY tool change dialog
image::images/gmoccapy_manual_toolchange.png["Manual tool change",align="left"]
@@ -864,8 +882,8 @@ net tool-prep-loop iocontrol.0.tool-prepare <= iocontrol.0.tool-prepared
Please take care, that this connections have to be done in the postgui HAL file.
.Tool Offset Pins
-These pins allow you to show the active tool offset values for X and Z in the
-tool information frame. You should know that they are only active after G43 has been sent.
+These pins allow you to show the active tool offset values for X and Z in the tool information frame.
+You should know that they are only active after G43 has been sent.
.Tool information area
image::images/gmoccapy_tool_info.png["Tool information",align="left"]
@@ -874,8 +892,7 @@ image::images/gmoccapy_tool_info.png["Tool information",align="left"]
- *gmoccapy.tooloffset-z* _(float IN)_
[NOTE]
-The tooloffset-x line is not needed on a mill,
-and will not be displayed on a mill with trivial kinematics.
+The tooloffset-x line is not needed on a mill, and will not be displayed on a mill with trivial kinematics.
To display the current offsets, the pins have to be connected like this in the postgui HAL file:
@@ -886,22 +903,18 @@ net tooloffset-z gmoccapy.tooloffset-z <= motion.tooloffset.z
----
[IMPORTANT]
-Please note, that GMOCCAPY takes care of its own to update the offsets,
-sending an G43 after any tool change, *but not in auto mode!* +
-So writing a program makes you responsible to include an G43 after
-each tool change!
+Please note, that GMOCCAPY takes care of its own to update the offsets, sending an G43 after any tool change, *but not in auto mode!* +
+So writing a program makes you responsible to include an G43 after each tool change!
[[gmoccapy:auto-tool-measurement]]
== Auto Tool Measurement
-GMOCCAPY offers an integrated auto tool measurement. To use this feature, you
-will need to do some additional settings and you may want to use the
-offered HAL pin to get values in your own NGC remap procedure.
+GMOCCAPY offers an integrated auto tool measurement.
+To use this feature, you will need to do some additional settings and you may want to use the offered HAL pin to get values in your own NGC remap procedure.
[IMPORTANT]
-Before starting the first test, do not forget to enter the probe
-height and probe velocities on the settings page! See
-<<gmoccapy:tool-measurement,Settings Page Tool Measurement>>
+Before starting the first test, do not forget to enter the probe height and probe velocities on the settings page!
+See <<gmoccapy:tool-measurement,Settings Page Tool Measurement>>.
It might be also a good idea to take a look at the tool measurement video:
see <<gmoccapy:tool-measurement-videos,tool measurement related videos>>.
@@ -920,23 +933,21 @@ Here is a small sketch:
.Tool measurement data
image::images/sketch_auto_tool_measurement.png[align="left"]
-With the first given tool change the tool will be measured and the offset will
-be set automatically to fit the block height. The advantage of the GMOCCAPY
-way is, that you do not need a reference tool.
+With the first given tool change the tool will be measured and the offset will be set automatically to fit the block height.
+The advantage of the GMOCCAPY way is, that you do not need a reference tool.
[NOTE]
====
-Your program must contain a tool change at the beginning! The tool will be
-measured, even it has been used before, so there is no danger, if the block
-height has changed. There are several videos showing the way to do that on
-YouTube.
+Your program must contain a tool change at the beginning! The tool will be measured,
+even it has been used before, so there is no danger, if the block height has changed.
+There are several videos showing the way to do that on YouTube.
====
=== Tool Measurement Pins
-GMOCCAPY offers five pins for tool measurement purposes. These pins are mostly used
-to be read from a G-code subroutine, so the code can react to different values.
+GMOCCAPY offers five pins for tool measurement purposes.
+These pins are mostly used to be read from a G-code subroutine, so the code can react to different values.
- *gmoccapy.toolmeasurement* _(bit OUT)_ - Enable or not tool measurement
- *gmoccapy.blockheight* _(float OUT)_ - The measured value of the top face of the workpiece
@@ -961,11 +972,9 @@ REMAP=M6 modalgroup=6 prolog=change_prolog ngc=change epilog=change_epilog
[NOTE]
Make sure INI_VARS and HAL_PIN_VARS are not set to 0. They are set to 1 by default.
-
.The Tool Sensor Section
The position of the tool sensor and the start position of the probing movement,
-all values are absolute coordinates, except MAXPROBE, which must be given in
-relative movement.
+all values are absolute coordinates, except MAXPROBE, which must be given in relative movement.
[source,{ini}]
----
@@ -977,9 +986,8 @@ MAXPROBE = -20
----
.The Change Position Section
-This is not named TOOL_CHANGE_POSITION on purpose - *canon uses that name and
-will interfere otherwise.* The position to move the machine before giving the
-change tool command. All values are in absolute coordinates.
+This is not named TOOL_CHANGE_POSITION on purpose - *canon uses that name and will interfere otherwise.*
+The position to move the machine before giving the change tool command. All values are in absolute coordinates.
[source,{ini}]
----
@@ -1015,11 +1023,9 @@ From `<your_linuxcnc-dev_directory>/configs/sim/gmoccapy/macros` copy
- `on_abort.ngc`
- `change.ngc`
-to the directory specified as `SUBROUTINE_PATH`, see
-<<gmocappy:rs274ngc,RS274NGC Section>>.
+to the directory specified as `SUBROUTINE_PATH`, see <<gmocappy:rs274ngc,RS274NGC Section>>.
-Open `change.ngc` with a editor and uncomment the following lines
-(49 and 50):
+Open `change.ngc` with a editor and uncomment the following lines (49 and 50):
[source,{ngc}]
@@ -1067,11 +1073,8 @@ net tool-prep-loop iocontrol.0.tool-prepare <= iocontrol.0.tool-prepared
[[gmoccapy:settings-page]]
== The Settings Page
-To enter the page you will have to click on
-image:images/gmoccapy_settings_button.png[align="left"]
-and give an unlock code, which is *123* by default. If you want to change it
-at this time you will have to edit the hidden preference file, see
-<<gmoccapy:display-section,the display section>> for details.
+To enter the page you will have to click on image:images/gmoccapy_settings_button.png[align="left"] and give an unlock code, which is *123* by default.
+If you want to change it at this time you will have to edit the hidden preference file, see <<gmoccapy:display-section,the display section>> for details.
The page is separated in three main tabs:
@@ -1084,16 +1087,15 @@ On this tab you will find the following options:
.Main Window
-Here you can select how you wish the GUI to start. The main reason for this was the wish to get an easy
-way for the user to set the starting options without the need to touch code.
+Here you can select how you wish the GUI to start.
+The main reason for this was the wish to get an easy way for the user to set the starting options without the need to touch code.
You have three options:
* _Start as full screen_
* _Start maximized_
* _Start as window_ - If you select start as window the spinboxes to set the position and size will get active.
One time set, the GUI will start every time on the place and with the size selected.
- Nevertheless the user can change the size and position using the mouse, but that will
- not have any influence on the settings.
+ Nevertheless the user can change the size and position using the mouse, but that will not have any influence on the settings.
* _hide the cursor_ - Does allow to hide the cursor, what is very useful if you use a touch screen.
.Keyboard
@@ -1115,18 +1117,16 @@ If this section is not sensitive, you have not installed a virtual keyboard, sup
* _Show keyboard on EDIT_
* _Show keyboard on load file_
-If the keyboard layout is not correct, i.e. clicking Y gives Z, than the
-layout has not been set properly, related to your locale settings. For
-onboard it can be solved with a small batch file with the following content:
+If the keyboard layout is not correct, i.e. clicking Y gives Z, than the layout has not been set properly, related to your locale settings.
+For onboard it can be solved with a small batch file with the following content:
----
#!/bin/bash
setxkbmap -model pc105 -layout de -variant basic
----
-The letters "de" are for German, you will have to set them according to your
-locale settings. Just execute this file before starting LinuxCNC, it can be
-done also adding a starter to your local folder.
+The letters "de" are for German, you will have to set them according to your locale settings.
+Just execute this file before starting LinuxCNC, it can be done also adding a starter to your local folder.
----
./config/autostart
@@ -1134,16 +1134,14 @@ done also adding a starter to your local folder.
So that the layout is set automatically on starting.
-For matchbox-keyboard you will have to make your own layout, for a German
-layout ask in the forum.
+For matchbox-keyboard you will have to make your own layout, for a German layout ask in the forum.
.GMOCCAPY with Onboard keyboard in edit mode
image:images/gmoccapy_keyboard_edit_mode_mid.png["Onboard keyboard",align="left",link="images/gmoccapy_keyboard_edit_mode.png"]
.On Touch Off
-This gives the option whether to show the preview tab or the offset page tab when
- you enter the touch off mode by clicking the corresponding bottom button.
+This gives the option whether to show the preview tab or the offset page tab when you enter the touch off mode by clicking the corresponding bottom button.
* _show preview_
* _show offsets_
@@ -1165,9 +1163,9 @@ The foreground color of the DRO can be selected with:
* unhomed color = red
[NOTE]
-You can change through the DRO modes (absolute, relative, distance
-to go) by clicking the number on the DRO!
-If you click on the left side letter of the DRO a popup window will allow you to set the value of the axes, making it easier to set the value, as you will not need to go over the touch off bottom button.
+You can change through the DRO modes (absolute, relative, distance to go) by clicking the number on the DRO!
+If you click on the left side letter of the DRO a popup window will allow you to set the value of the axes,
+making it easier to set the value, as you will not need to go over the touch off bottom button.
size::
Allows to set the size of the DRO font, default is 28, if you use a bigger screen you may want to increase the size up to 56.
@@ -1194,15 +1192,11 @@ toggle DRO mode::
NOTE: The grid will not be shown in perspective view.
-- _Show DRO_ - Will show the a DRO also in the preview pane, it will be always
-shown in fullsize preview.
-- _Show DTG_ - Will show the DTG (direct distance to end point) in the
-preview pane if Show DRO is active. Otherwise only in full size preview.
-- _Show Offsets_ - Will show the offsets in the preview pane when Show DRO is
-active. Otherwise only in full size preview.
+- _Show DRO_ - Will show the a DRO also in the preview pane, it will be always shown in fullsize preview.
+- _Show DTG_ - Will show the DTG (direct distance to end point) in the preview pane if Show DRO is active. Otherwise only in full size preview.
+- _Show Offsets_ - Will show the offsets in the preview pane when Show DRO is active. Otherwise only in full size preview.
-- _Mouse Button Mode_ - This combobox allows you to select the button behavior of the
- mouse to rotate, move or zoom within the preview:
+- _Mouse Button Mode_ - This combobox allows you to select the button behavior of the mouse to rotate, move or zoom within the preview:
+
* left rotate, middle move, right zoom
* left zoom, middle move, right rotate
@@ -1217,31 +1211,29 @@ The mouse wheel will still zoom the preview in every mode.
[TIP]
====
-If you select an element in the preview, the selected element will be
-taken as rotation center point and in auto mode the corresponding code line will be highlighted.
+If you select an element in the preview,
+the selected element will be taken as rotation center point and in auto mode the corresponding code line will be highlighted.
====
.File to load on start up
-Select the file you want to be loaded on start up. If a file is loaded, it can
-be set by pressing the current button. To avoid that any program is loaded at
-start up, just press the None button.
+Select the file you want to be loaded on start up.
+If a file is loaded, it can be set by pressing the current button.
+To avoid that any program is loaded at start up, just press the None button.
The file selection screen will use the filters you have set in the INI file,
-if there aren't any filters given, you will only see *NGC files*. The path
-will be set according to the INI settings in `[DISPLAY] PROGRAM_PREFIX`.
+if there aren't any filters given, you will only see *NGC files*.
+The path will be set according to the INI settings in `[DISPLAY] PROGRAM_PREFIX`.
.Jump to dir
-You can set here the directory to jump to if you press the corresponding button
-in the file selection dialog.
+You can set here the directory to jump to if you press the corresponding button in the file selection dialog.
// image::images/gmoccapy_file_selection_dialog_with_keyboard.png["Directory selection",align="left"]
.Themes and Sounds
-This lets the user select what desktop theme to apply and what error and
-messages sounds should be played.
+This lets the user select what desktop theme to apply and what error and messages sounds should be played.
By default "Follow System Theme" is set.
It further allows to change the icon theme.
@@ -1260,11 +1252,11 @@ image::images/gmoccapy_settings_hardware.png["Hardware settings",align="left"]
.Hardware MPG Scale
For the different HAL pins to connect MPG wheels to, you may select individual scales to be applied.
-The main reason for this was my own test to solve this through HAL connections, resulting in a very
-complex HAL file. Imagine a user having an MPG Wheel with 100 ipr and he wants to slow down the max.
-vel. from 14000 to 2000 mm/min, that needs 12000 impulses, resulting in 120 turns of the wheel!
-Or an other user having a MPG Wheel with 500 ipr and he wants to set the spindle override witch has
-limits from 50 to 120 % so he goes from min to max within 70 impulses, meaning not even 1/4 turn.
+The main reason for this was my own test to solve this through HAL connections, resulting in a very complex HAL file.
+Imagine a user having an MPG Wheel with 100 ipr and he wants to slow down the max. vel. from 14000 to 2000 mm/min,
+that needs 12000 impulses, resulting in 120 turns of the wheel!
+Or an other user having a MPG Wheel with 500 ipr and he wants to set the spindle override
+which has limits from 50 to 120 % so he goes from min to max within 70 impulses, meaning not even 1/4 turn.
By default all scales are set using the calculation:
@@ -1274,7 +1266,8 @@ By default all scales are set using the calculation:
.Keyboard shortcuts
-Some users want to jog there machine using the keyboard buttons and there are others that will never allow this. So everybody can select whether to use them or not. +
+Some users want to jog there machine using the keyboard buttons and there are others that will never allow this.
+So everybody can select whether to use them or not. +
Keyboard shortcuts are disabled by default.
[WARNING]
@@ -1318,8 +1311,7 @@ There are three options to unlock the settings page:
* _Use unlock code_ - The user must give a code to get in
* _Do not use unlock code_ - There will be no security check
-* _Use HAL pin to unlock_ - Hardware pin must be high to unlock the settings,
- see <<gmoccapy:hardware-unlock, hardware unlock pin>>
+* _Use HAL pin to unlock_ - Hardware pin must be high to unlock the settings, see <<gmoccapy:hardware-unlock, hardware unlock pin>>.
Default is _use unlock code_ (default = *123*)
@@ -1327,13 +1319,10 @@ Default is _use unlock code_ (default = *123*)
* _Starting RPM_ - Sets the rpm to be used if the spindle is started and no S value has been set.
+
[NOTE]
-This value will be presetted according to your settings in
-`[DISPLAY] DEFAULT_SPINDLE_SPEED` of your INI file. If you change the settings on the
-settings page, that value will be default from that moment, your INI file will
-not be modified.
+This value will be presetted according to your settings in `[DISPLAY] DEFAULT_SPINDLE_SPEED` of your INI file.
+If you change the settings on the settings page, that value will be default from that moment, your INI file will not be modified.
-* _Spindle bar min_ and _Spindle bar max_ - Sets the limits of the spindle bar shown in
-the INFO frame on the main screen.
+* _Spindle bar min_ and _Spindle bar max_ - Sets the limits of the spindle bar shown in the INFO frame on the main screen.
+
====
Default values are: +
@@ -1342,22 +1331,20 @@ MAX = 6000
====
+
[NOTE]
-It is no error giving wrong values. If you
-give a maximum of 2000 and your spindle makes 4000 rpm, only the bar level will
-be wrong on higher speeds than 2000 rpm.
+It is no error giving wrong values.
+If you give a maximum of 2000 and your spindle makes 4000 rpm, only the bar level will be wrong on higher speeds than 2000 rpm.
[[gmoccapy:turtle-jog]]
.Turtle Jog
This settings will have influence on the jog velocities.
-* _Hide turtle jog button_ - Will hide the button right of the jog velocity
- slider. If you hide this button, please take care that the "rabbit
- mode" is activated, otherwise you will not be able to jog faster than the turtle jog
- velocity, which is calculated using the turtle jog factor.
-* _Turtle jog factor_ - Sets the scale to apply for turtle jog mode (button pressed,
-showing the turtle). If you set a factor of 20, the turtle max. jog velocity will
-be 1/20 of the max. velocity of the machine.
+* _Hide turtle jog button_ - Will hide the button right of the jog velocity slider.
+ If you hide this button, please take care that the "rabbit mode" is activated,
+ otherwise you will not be able to jog faster than the turtle jog velocity,
+ which is calculated using the turtle jog factor.
+* _Turtle jog factor_ - Sets the scale to apply for turtle jog mode (button pressed, showing the turtle).
+ If you set a factor of 20, the turtle max. jog velocity will be 1/20 of the max. velocity of the machine.
[NOTE]
This button can be controlled using the <<gmoccapy:jog-velocity,Turtle-Jog HAL Pin>>.
@@ -1373,19 +1360,16 @@ image::images/gmoccapy_settings_advanced.png["Advanced settings",align="left"]
Please check <<gmoccapy:auto-tool-measurement,Auto Tool Measurement>>
[NOTE]
-If this part is not sensitive, you do not have a valid INI file configuration
-to use tool measurement.
+If this part is not sensitive, you do not have a valid INI file configuration to use tool measurement.
-* _Use auto tool measurement_ - If checked, after each tool change, a tool
- measurement will be done, the result will be stored in the tool table and a
- G43 will be executed after the change.
+* _Use auto tool measurement_ - If checked, after each tool change, a tool measurement will be done,
+ the result will be stored in the tool table and a G43 will be executed after the change.
Probe Information::
+
--
-The following information is taken from your INI file and must be given
-in absolute coordinates.
+The following information is taken from your INI file and must be given in absolute coordinates.
* _X Pos._ - The X position of the tool switch.
* _Y Pos._ - The Y position of the tool switch.
@@ -1399,13 +1383,11 @@ in absolute coordinates.
Probe velocities::
+
--
-* _Search Vel._ - The velocity to search for the tool switch. After contact
- the tool will go up again and then goes towards the probe again with probe
- vel, so you will get better results.
-* _Probe Vel._ - The velocity for the second movement to the switch. It
- should be slower to get better touch results. (In simulation mode, this is
- commented out in macros/change.ngc, otherwise the user would have to click
- twice on the probe button.)
+* _Search Vel._ - The velocity to search for the tool switch.
+ After contact the tool will go up again and then goes towards the probe again with probe vel, so you will get better results.
+* _Probe Vel._ - The velocity for the second movement to the switch.
+ It should be slower to get better touch results.
+ In simulation mode, this is commented out in macros/change.ngc, otherwise the user would have to click twice on the probe button.
--
// TODO: check if this option is accidentally gone in 2.9
// Tool Changer::
@@ -1436,40 +1418,32 @@ Reload Tool::
.Run From Line Option
-You can allow or disallow the run from line. This will set the corresponding
-button insensitive (grayed out), so the user will not be able to use this
-option. The default is disable run from line.
+You can allow or disallow the run from line.
+This will set the corresponding button insensitive (grayed out), so the user will not be able to use this option.
+The default is disable run from line.
[WARNING]
-It is not recommend to use run from line, as LinuxCNC will not take care of
-any previous lines in the code before the starting line. So errors or crashes
-are fairly likely.
+It is not recommend to use run from line, as LinuxCNC will not take care of any previous lines in the code before the starting line.
+So errors or crashes are fairly likely.
[[gmoccapy:message-behavior]]
.Message Behavior And Appearance
-This will display small pop up windows displaying a message or error text,
-similar to the ones known from AXIS. You can delete a specific
-message by clicking on its close button. If you want to delete the last one,
-just hit the `WINDOWS` key on your keyboard, or delete all messages at once
-with `Control + Space`.
+This will display small pop up windows displaying a message or error text, similar to the ones known from AXIS.
+You can delete a specific message by clicking on its close button.
+If you want to delete the last one, just hit the `WINDOWS` key on your keyboard, or delete all messages at once with `Control + Space`.
You are able to set some options:
-* _X Pos_ - The position of the top left corner of the message in X counted
- in pixel from the top left corner of the screen.
-* _Y Pos_ - The position of the top left corner of the message in Y counted
- in pixel from the top left corner of the screen.
+* _X Pos_ - The position of the top left corner of the message in X counted in pixel from the top left corner of the screen.
+* _Y Pos_ - The position of the top left corner of the message in Y counted in pixel from the top left corner of the screen.
* _Width_ - The width of the message box.
* _Max Messages_ - The maximum number of messages you want to see at once.
- If you set this to 10, the 11^th^ message will delete the first one, so you
- will only see the last 10.
+ If you set this to 10, the 11^th^ message will delete the first one, so you will only see the last 10.
* _Font_ - The font and size you want to use to display the messages.
-* _Use frames_ - If you activate the checkbox, each message will be displayed
- in a frame, so it is much easier to distinguish the messages. But you will
- need a little bit more space.
-* _Launch test message_-button - It will show a message, so you can see the
- changes of your settings without the need to generate an error.
+* _Use frames_ - If you activate the checkbox, each message will be displayed in a frame,
+ so it is much easier to distinguish the messages. But you will need a little bit more space.
+* _Launch test message_-button - It will show a message, so you can see the changes of your settings without the need to generate an error.
[[gmoccapy:icon-theme-section]]
== Icon Theme
@@ -1492,10 +1466,12 @@ GMOCCAPY scans the following directories for icon themes:
=== Custom Icon Theme
-Creating a custom icon theme is pretty easy. All you need is a text editor and of course the desired icons as pixel or vector graphics.
+Creating a custom icon theme is pretty easy.
+All you need is a text editor and of course the desired icons as pixel or vector graphics.
Details about how exactly an icon theme is built can be found at the https://specifications.freedesktop.org/icon-theme-spec/icon-theme-spec-latest.html[Freedesktop Icon Theme Specification].
-Start by creating an empty directory with the name of the icon theme. Place the directory in one of GMOCCAPY's icon theme directories.
+Start by creating an empty directory with the name of the icon theme.
+Place the directory in one of GMOCCAPY's icon theme directories.
Then we need a file called index.theme in the root folder of our icon theme which contains the required metadata for the theme.
That's a simple text file with at least the following sections:
@@ -1542,23 +1518,26 @@ Basically that's everything needed to create a custom icon theme.
=== Symbolic Icons
-Symbolic icons are a special type of icon, usually a monochrome image. The special feature of symbolic icons is that the icons are automatically colored at runtime to match the desktop theme.
-That way, icon themes can be created that work well with dark and also light desktop themes (in fact, that's not always the best option, that's why a dedicated "material-light" theme exists).
+Symbolic icons are a special type of icon, usually a monochrome image.
+The special feature of symbolic icons is that the icons are automatically colored at runtime to match the desktop theme.
+That way, icon themes can be created that work well with dark and also light desktop themes
+(in fact, that's not always the best option, that's why a dedicated "material-light" theme exists).
image::images/gmoccapy_icon_theme_symbolic.png[align="center"]
-To make use of the symbolic feature, a icon file has to have the suffix .symbolic.$ext (where $ext is the regular file extension like png) for example "power_on.symbolic.png".
+To make use of the symbolic feature,
+a icon file has to have the suffix .symbolic.$ext (where $ext is the regular file extension like png) for example "power_on.symbolic.png".
With that name, GTK treats this image as symbolic icon and applies some recoloring when loading the icon.
There are only four colors allowed to use:
[frame="none",grid="none",cols="10,10,40",options="header"]
|===
-|Color |Hex Code |Description
-|black |#000000 |Primary color, gets changed to match the desktop themes primary color.
-|red |#ff0000 |Success: this color indicates "success" (usually something green'ish).
-|green |#00ff00 |Warning: this color indicates "warning" (usually something yellow/orange'ish).
-|blue |#0000ff |Error: this color indicates "error" (usually something red'ish).
+|Color |Hex Code |Description
+|black m|#000000 |Primary color, gets changed to match the desktop themes primary color.
+|red m|#ff0000 |Success: this color indicates "success" (usually something green'ish).
+|green m|#00ff00 |Warning: this color indicates "warning" (usually something yellow/orange'ish).
+|blue m|#0000ff |Error: this color indicates "error" (usually something red'ish).
|===
[TIP]
@@ -1568,9 +1547,8 @@ Examples of symbolic icons can be found at `linuxcnc/share/gmoccapy/icons/materi
[[gmoccapy:lathe-section]]
== Lathe Specific Section
-If in the INI file `LATHE = 1` is given, the GUI will change its appearance
-to the special needs for a lathe. Mainly the Y axis will be hidden and the
-jog buttons will be arranged in a different order.
+If in the INI file `LATHE = 1` is given, the GUI will change its appearance to the special needs for a lathe.
+Mainly the Y axis will be hidden and the jog buttons will be arranged in a different order.
.Normal Lathe
image::images/gmoccapy_lathe.png[align="left"]
@@ -1578,13 +1556,13 @@ image::images/gmoccapy_lathe.png[align="left"]
.Back Tool Lathe
image::images/gmoccapy_back_tool_lathe.png[align="left"]
-As you see the R DRO has a black background and the D DRO is gray. This will
-change according to the active G-code G7 or G8. The active mode is visible by
-the black background, meaning in the shown images G8 is active.
+As you see the R DRO has a black background and the D DRO is gray.
+This will change according to the active G-code G7 or G8.
+The active mode is visible by the black background, meaning in the shown images G8 is active.
The next difference to the standard screen is the location of the jog buttons.
-X and Z have changed places and Y is gone. You will note that the X+ and X-
-buttons changes there places according to normal or back tool lathe.
+X and Z have changed places and Y is gone.
+You will note that the X+ and X- buttons changes there places according to normal or back tool lathe.
Also the keyboard behavior will change:
@@ -1602,14 +1580,13 @@ Back Tool Lathe:
* _Arrow_up_ or _NumPad_Up_ - Jog X plus
* _Arrow_Down_ or _NumPad_Down_ - Jog X minus
-The tool information frame will show not only the Z offset, but also the X
-offset and the tool table is showing all lathe relevant information.
+The tool information frame will show not only the Z offset, but also the X offset and the tool table is showing all lathe relevant information.
== Plasma Specific Section
image::images/gmoccapy_plasma.png["Plasma GUI",align="left"]
-There is a very good WIKI, which is actually growing, maintained by Marius
+There is a very good WIKI, which is actually growing, maintained by Marius,
see https://wiki.linuxcnc.org/cgi-bin/wiki.pl?Gmoccapy_plasma[Plasma wiki page].
== Videos on YouTube
@@ -1659,8 +1636,8 @@ If you get strange numbers in the info area of GMOCCAPY like:
image::images/strange_numbers.png["Strange numbers",align="left"]
You have made your config file using an older version of StepConfWizard.
-It has made a wrong entry in the INI file under the [TRAJ] named
-MAX_LINEAR_VELOCITY = xxx. Change that entry to MAX_VELOCITY = xxx.
+It has made a wrong entry in the INI file under the [TRAJ] named MAX_LINEAR_VELOCITY = xxx.
+Change that entry to MAX_VELOCITY = xxx.
[[sub:NOT_ENDING_MACROS]]
=== Not ending macro
@@ -1682,9 +1659,9 @@ o<zeroxy> endsub
m2
---------
-GMOCCAPY will not see the end of the macro, because the interpreter needs to
-change its state to IDLE, but the macro does not even set the interpreter to
-a new state. To avoid that just add a G4 P0.1 line to get the needed signal.
+GMOCCAPY will not see the end of the macro, because the interpreter needs to change its state to IDLE,
+but the macro does not even set the interpreter to a new state.
+To avoid that just add a G4 P0.1 line to get the needed signal.
The correct macro would be:
[source,{ngc}]
diff --git a/docs/src/gui/image-to-gcode.adoc b/docs/src/gui/image-to-gcode.adoc
index d8ba8e35a4..bd20eaac95 100644
--- a/docs/src/gui/image-to-gcode.adoc
+++ b/docs/src/gui/image-to-gcode.adoc
@@ -125,8 +125,8 @@ Possible scan directions are:
=== Depth (units)
-The top of material is always at 'Z = 0'. The deepest cut into the
-material is _Z = -depth_.
+The top of material is always at 'Z = 0'.
+The deepest cut into the material is at _Z = -depth_.
=== Step Over (pixels)
diff --git a/docs/src/gui/panelui_handler.py b/docs/src/gui/panelui_handler.py
index 0cd435f4f9..0d179d069b 100644
--- a/docs/src/gui/panelui_handler.py
+++ b/docs/src/gui/panelui_handler.py
@@ -6,8 +6,8 @@ def get_handlers(linuxcnc_stat, linucnc_cmd, commands, master):
class HandlerClass:
# This will be pretty standard to gain access to everything
- # linuxcnc_stat: is the python status instance of linuxcnc
- # linuxcnc_cmd: is the python command instance of linuxcnc
+ # linuxcnc_stat: is the python status instance of LinuxCNC
+ # linuxcnc_cmd: is the python command instance of LinuxCNC
# commands: is the command instance so one can call the internal routines
# master: give access to the master functions/data
@@ -26,12 +26,12 @@ class HandlerClass:
print(m) # print the argument(s)
print(wname.metadata) # Print the calling widgets internal metadata (from config file)
- # call a mdi command to print a msg in linuxcnc
- # This requires linuxcnc to be homed, but does not check for that.
+ # Call a mdi command to print a msg in LinuxCNC.
+ # This requires LinuxCNC to be homed, but does not check for that.
# parent commands expect a widget_instance - None is substituted
self.parent.mdi(None,'(MSG, Hello Linuxcnc World!)')
- # Each call to this function will cycle the mode of linuxcnc
+ # Each call to this function will cycle the mode of LinuxCNC.
def cycle_mode(self, wname, m):
if self.current_mode == 0:
self.current_mode = 1
diff --git a/docs/src/gui/pyvcp.adoc b/docs/src/gui/pyvcp.adoc
index 59ab43fbc7..8ac29b05b8 100644
--- a/docs/src/gui/pyvcp.adoc
+++ b/docs/src/gui/pyvcp.adoc
@@ -615,7 +615,7 @@ The syntax is the same as 'number' except the name which is <u32>.
.Bar
A bar widget displays the value of a FLOAT signal both graphically using a bar display and numerically.
-The color of the bar can be set as one color throughout its range (default using fillcolor) orlset to change color,
+The color of the bar can be set as one color throughout its range (default using fillcolor) or set to change color,
dependent upon the value of the halpin (range1, range2 range3 must all be set, if you only want 2 ranges, set 2 of them to the same color).
* `<halpin>"my-bar"</halpin>` (text), derives and sets the pin name: `pyvcp.my-bar`.
diff --git a/docs/src/gui/qtdragon.adoc b/docs/src/gui/qtdragon.adoc
index 8e5ed939fd..38c008a7ec 100644
--- a/docs/src/gui/qtdragon.adoc
+++ b/docs/src/gui/qtdragon.adoc
@@ -17,15 +17,13 @@ LinuxCNC's version is adapted from Persei8's Github versions.
It is primarily meant for 3/4 axes machines such as mills or routers.
It works well with a touchscreen and/or mouse.
QtDragon supports multiple ways to touch off tools and probing work pieces.
-You can use LinuxCNC's external offsets capability to automatically raise the
-spindle during a pause.
-If you the VersaProbe option and remap code you can add auto tool length probing
-at tool changes.
+You can use LinuxCNC's external offsets capability to automatically raise the spindle during a pause.
+If you the VersaProbe option and remap code you can add auto tool length probing at tool changes.
[NOTE]
QtDragon and QtVCP are relatively new programs added into LinuxCNC.
-Bugs and oddities are possible. Please test carefully when using a
-dangerous machine. Please forward reports to the forum or maillist.
+Bugs and oddities are possible. Please test carefully when using a dangerous machine.
+Please forward reports to the forum or maillist.
=== QtDragon
@@ -33,28 +31,24 @@ dangerous machine. Please forward reports to the forum or maillist.
image::images/silverdragon.png["QtDragon Router",scale="25%"]
QtDragon is resizable from a resolution of 1280x768 to 1680x1200.
-It will work in window mode on any monitor with higher resolution but not
-on monitors with lower resolution.
+It will work in window mode on any monitor with higher resolution but not on monitors with lower resolution.
=== QtDragon_hd
.QtDragon_hd - 3 or 4 Axis Sample for larger monitors (1920x1056) in dark theme
image::images/qtdragon_hd.png["QtDragon_hd",scale="25%"]
-QtDragon_hd is a similar design as QtDragon but modified to utilize the extra
-space of modern larger monitors.
+QtDragon_hd is a similar design as QtDragon but modified to utilize the extra space of modern larger monitors.
There are some small differences in layout and utility.
QtDragon_hd has a resolution of 1920x1056 and is not resizeable.
-It will work in window mode on any monitor with higher resolution but not on
-monitors with lower resolution.
+It will work in window mode on any monitor with higher resolution but not on monitors with lower resolution.
== Getting Started - The INI file
If your configuration is not currently set up to use QtDragon,
you can change it by editing the INI file [DISPLAY] section.
-For an exhaustive list of options, see the
-<<sub:ini:sec:display,display section>> of INI file documentation.
+For an exhaustive list of options, see the <<sub:ini:sec:display,display section>> of INI file documentation.
=== Display
@@ -149,9 +143,8 @@ DEFAULT_LINEAR_VELOCITY = 50.0
=== User message dialog system
Optional popup custom message dialogs, controlled by HAL pins.
MESSAGE_TYPE can be 'okdialog' or 'yesnodialog'.
-See qtvcp/library/messages for more information
-This example shows how to make a dialog that requires the user to select
- 'ok' to acknowledge and hide.
+See qtvcp/library/messages for more information.
+This example shows how to make a dialog that requires the user to select 'ok' to acknowledge and hide.
[source,{ini}]
----
@@ -184,9 +177,9 @@ EMBED_TAB_LOCATION = tabWidget_utilities
=== Preview Control
Magic comments can be used to control the G-code preview. +
-On very large programs the preview can take a long time to load. You can control
-what is shown and what is hidden the the graphics screen by adding the appropriate
-comments from this list into your G-code:
+On very large programs the preview can take a long time to load.
+You can control what is shown and what is hidden the the graphics screen
+by adding the appropriate comments from this list into your G-code:
----
(PREVIEW,stop)
@@ -196,10 +189,8 @@ comments from this list into your G-code:
=== Program Extensions/Filters
-You can control what programs are displayed in the filemanager window with
-program extensions:
-Create a line with the . endings you wish to use separated by commas, then a
-space and the description.
+You can control what programs are displayed in the filemanager window with program extensions:
+Create a line with the . endings you wish to use separated by commas, then a space and the description.
You can add multiple lines for different selections in the combo box.
[source,{ini}]
@@ -209,20 +200,19 @@ PROGRAM_EXTENSION = .ngc,.nc,.tap G-Code File (*.ngc,*.nc,*.tap)
----
QtDragon has the ability to send loaded files through a 'filter program'.
-This filter can do any desired task: Something as simple as making sure
-the file ends with 'M2', or something as complicated as generating
-G-Code from an image.
+This filter can do any desired task: Something as simple as making sure the file ends with 'M2',
+or something as complicated as generating G-Code from an image.
See <<cha:filter,Filter Programs>> for more information.
The '[FILTER]' section of the INI file controls how filters work.
First, for each type of file, write a 'PROGRAM_EXTENSION' line.
Then, specify the program to execute for each type of file.
This program is given the name of the input file as its first argument,
-and must write rs274ngc code to standard output. This output is what
-will be displayed in the text area, previewed in the display area, and
-executed by LinuxCNC when 'Run'. The following lines add support for the
-`image-to-gcode` converter included with LinuxCNC and running Python based
-filter programs:
+and must write rs274ngc code to standard output.
+This output is what will be displayed in the text area, previewed in the display area,
+and executed by LinuxCNC when 'Run'.
+The following lines add support for the `image-to-gcode` converter
+included with LinuxCNC and running Python based filter programs:
[source,{ini}]
----
@@ -237,28 +227,13 @@ py = python
=== Probe/Touchplate/Laser Settings
-QtDragon has custom INI entries for required setup.
-
-[source,{ini}]
-----
-[TOOLSENSOR]
-MAXPROBE = 40
-SEARCH_VEL = 200
-PROBE_VEL = 50
-TOUCH = 29.7
-
-[LASER]
-X = 106.9
-Y = -16.85
-----
-
-QtDragon has two optional probing tab screens available.
+QtDragon has INI entries for two optional probing tab screens available.
Comment/uncomment which ever you prefer.
-'Versa probe' is a Qtvcp ported version of a popular Gladevcp probing panel.
-'Basic Probe' is a Qtvcp ported version based on the third party basic probe
-screen.
-Both do similar probing routines.
+* 'Versa probe' is a Qtvcp ported version of a popular GladeVCP probing panel.
+* 'Basic Probe' is a Qtvcp ported version based on the third party basic probe screen.
+
+Both do similar probing routines.
[source,{ini}]
----
@@ -272,11 +247,9 @@ USE_PROBE = basicprobe
QtDragon has up to ten convenience macro buttons.
In the sample configurations they are labelled for moving between
current user system origin (zero point) and Machine system origin.
-User origin is the first MDI command in the INI list, machine origin is the
-second.
+User origin is the first MDI command in the INI list, machine origin is the second.
These could also call OWord routines if desired.
-This example shows how to move Z axis up first. The commands are separated by
-the ';'
+This example shows how to move Z axis up first. The commands are separated by the ';'
The label is set after the comma. The symbols '\n' adds a line break.
[source,{ini}]
@@ -316,15 +289,13 @@ POSTGUI_HALCMD = loadusr halmeter
=== Builtin Sample Configurations
-The sample configurations 'sim/qtvcp_screens/qtdragon/qtdragon_xyza.ini' is
-already configured to use QtDragon as its front-end. +
+The sample configurations 'sim/qtvcp_screens/qtdragon/qtdragon_xyza.ini' is already configured to use QtDragon as its front-end. +
There are several others, to demonstrate different machine configurations.
== Key Bindings
QtDragon is not intended to primarily use a keyboard for machine control.
-It lacks many keyboard short cuts that for instance AXIS has - but you can use
-a mouse.
+It lacks many keyboard short cuts that for instance AXIS has - but you can use a mouse.
There are several key presses that will control the machine for convenience.
----
@@ -344,23 +315,20 @@ This is controlled by the stylesheet/theme +
== Virtual Keyboard
QtDragon includes a virtual keyboard for use with touchscreens. +
-To enable the keyboard, check the Use Virtual Keyboard checkbox in the Settings
-page. +
-Clicking on any input field, such as probe parameters or tool table entries,
-will show the keyboard. +
+To enable the keyboard, check the Use Virtual Keyboard checkbox in the Settings page. +
+Clicking on any input field, such as probe parameters or tool table entries, will show the keyboard. +
To hide the keyboard, do one of the following:
- click the MAIN page button
- The currently selected page button.
- go into AUTO mode
-It should be noted that keyboard jogging is disabled when using the virtual
-keyboard.
+It should be noted that keyboard jogging is disabled when using the virtual keyboard.
== HAL Pins
-These pins are specific to the QtDragon screen, There are of course are many
-more HAL pins that must be connected for LinuxCNC to function.
+These pins are specific to the QtDragon screen.
+There are of course are many more HAL pins that must be connected for LinuxCNC to function.
If you need a manual tool change prompt, add these lines in your postgui file.
@@ -454,14 +422,14 @@ qtdragon.versaprobe-searchvel
== HAL files
-The HAL files supplied are for simulation only. A real machine needs its own
-custom HAL files. The QtDragon screen works with 3 or 4 axes with one joint per
-axis or 3 or 4 axes in a gantry configuration (2 joints on 1 axis).
+The HAL files supplied are for simulation only.
+A real machine needs its own custom HAL files.
+The QtDragon screen works with 3 or 4 axes with one joint per axis or 3 or 4 axes in a gantry configuration
+(2 joints on 1 axis).
== Manual Tool Changes
-If your machine requires manual tool changes, QtDragon can pop a message box to
-direct you.
+If your machine requires manual tool changes, QtDragon can pop a message box to direct you.
You must connect the proper HAL pin in the postgui HAL file.
For example:
@@ -475,19 +443,15 @@ net tool-prep-number hal_manualtoolchange.number <= iocontrol.0.tool-prep-num
== Spindle
The screen is intended to interface to a VFD, but will still work without it.
-There are a number of VFD drivers included
-in the LinuxCNC distribution. It is up to the end user to supply the appropriate
-driver and HAL file connections according to his own machine setup.
+There are a number of VFD drivers included in the LinuxCNC distribution.
+It is up to the end user to supply the appropriate driver and HAL file connections according to his own machine setup.
== Auto Raise Z Axis on Spindle Pause
-QtDragon can be set up to automatically raise and lower the Z axis when the
-spindle is paused.
-When a program is paused, then you press the 'Spindle Pause' button to stop the
-spindle and raise it in Z.
+QtDragon can be set up to automatically raise and lower the Z axis when the spindle is paused.
+When a program is paused, then you press the 'Spindle Pause' button to stop the spindle and raise it in Z.
Press the button again to start spindle and lower it, then unpause program.
-The amount to raise and lower is set in the 'Settings' tab under the heading
-'Z Ext Offset'.
+The amount to raise and lower is set in the 'Settings' tab under the heading 'Z Ext Offset'.
This requires additions to the INI and the qtdragon_post_gui file.
In the INI, under the AXIS_Z heading.
@@ -516,30 +480,26 @@ setp axis.z.eoffset-scale 1.0
== Z level compensation
-QtDragon_hd can be set up to probe and compensate for Z level height changes
-by utilizing the external program 'G-code Ripper'.
+QtDragon_hd can be set up to probe and compensate for Z level height changes by utilizing the external program 'G-code Ripper'.
[NOTE]
This is only available in the QtDragon_hd version.
-Z level compensation is a bed levelling/distortion correction function
-typically used in 3D printing or engraving. It uses a HAL user space
-component which utilizes the external offsets feature of LinuxCNC. The
-component has a HAL pin that specifies an interpolation type, which must
-be one of cubic, linear or nearest (0,1,2 respectively). If none is
-specified or if an invalid number is specified, the default is assumed
-to be cubic.
-
-When Z LEVEL COMP is enabled, the compensation component reads a probe
-data file, which must be called 'probe_points.txt'. The file can be
-modified or updated at any time while compensation is disabled. When
-next enabled, the file will be reread and the compensation map is
-recalculated. This file is expected to be in the configuration directory.
-
-The probe data file is generated by a probing program which itself is
-generated by an external python program called gcode_ripper,
-which can be launched from the file manager tab using the 'G-code Ripper'
-button.
+Z level compensation is a bed levelling/distortion correction function typically used in 3D printing or engraving.
+It uses a HAL user space component which utilizes the external offsets feature of LinuxCNC.
+The component has a HAL pin that specifies an interpolation type,
+which must be one of cubic, linear or nearest (0,1,2 respectively).
+If none is specified or if an invalid number is specified, the default is assumed to be cubic.
+
+When Z LEVEL COMP is enabled, the compensation component reads a probe data file,
+which must be called 'probe_points.txt'.
+The file can be modified or updated at any time while compensation is disabled.
+When next enabled, the file will be reread and the compensation map is recalculated.
+This file is expected to be in the configuration directory.
+
+The probe data file is generated by a probing program,
+which itself is generated by an external python program called gcode_ripper,
+which can be launched from the file manager tab using the 'G-code Ripper' button.
=== Using G-code Ripper for Z level Compensation
@@ -551,22 +511,22 @@ G-code Ripper offers many functions that we will not go in to here.
This is only available in the QtDragon_hd version.
* In Qtdragon_hd switch to the file tab and press the load G-code Ripper button.
-* set origin to match the origin of the gcode file to be probed
-* under G-Code Operations, check Auto Probe
+* Set origin to match the origin of the gcode file to be probed.
+* Under G-Code Operations, check Auto Probe.
* File -> Open G-Code File (The file you will run after compensation)
-* if necessary, make adjustments and press Recalculate
-* press Save G-Code File - Probe Only
-* save the generated file to the nc_files folder
-* exit gcode_ripper
+* If necessary, make adjustments and press Recalculate.
+* Press Save G-Code File - Probe Only.
+* Save the generated file to the nc_files folder.
+* Exit gcode_ripper.
* There should now be a file in the nc_files folder called {something}-probe-only.ngc. Set the file filter to G-Code Files, navigate to the nc_files directory and load this file.
* Without changing the offsets, run this program. Make sure the probe tool is installed. When complete, there will be a file in the config directory called 'probe_points.txt'.
-* In Qtdragon_hd press the 'Enable Z Comp' button to enable compensation.
-Look at the status line for indication of success or failure.
+* In Qtdragon_hd press the 'Enable Z Comp' button to enable compensation.
+Look at the status line for indication of success or failure.
Active compensation will be displayed beside the label: 'Z Level Comp'
While jogging that display should change based on the compensation component.
[NOTE]
-If you use auto raise Z to lift the spindle on pause, you must combine the two
+If you use auto raise Z to lift the spindle on pause, you must combine the two
with a HAL component and feed that to LinuxCNC's motion component.
sample postgui HAL file for combined spindle raise and Z Level compensation
@@ -595,7 +555,7 @@ setp axis.z.eoffset-enable True
# external offsets for spindle pause function
########################################################################
-net eoffset-spindle-count <= qtdragon.eoffset-spindle-count
+net eoffset-spindle-count <= qtdragon.eoffset-spindle-count
# Z level compensation
########################################################################
@@ -616,12 +576,10 @@ net eoffset-counts scaled-s32-sums.0.out-s
== Probing
-The probe screen has been through basic testing but there could still be some
-minor bugs.
-When running probing routines, use extreme caution until you are familiar with
-how everything works.
-Probe routines run without blocking the main GUI. This gives the operator the
-opportunity to watch the DROs and stop the routine at any time.
+The probe screen has been through basic testing but there could still be some minor bugs.
+When running probing routines, use extreme caution until you are familiar with how everything works.
+Probe routines run without blocking the main GUI.
+This gives the operator the opportunity to watch the DROs and stop the routine at any time.
[NOTE]
Probing is very unforgiving to mistakes; be sure to check settings before using.
@@ -629,30 +587,29 @@ Probing is very unforgiving to mistakes; be sure to check settings before using.
.QtDragon - Versa Probe Option
image::images/qtdragon_versaprobe.png["QtDragon Probe",scale="25%"]
-QtDragon has 2 methods for setting Z0. The first is a touchplate, where
-a metal plate of known thickness is placed on top of the workpiece and then the
-tool is lowered until it touches the plate, triggering the probe signal. Z0 is
-set to probe height - plate thickness.
+QtDragon has 2 methods for setting Z0. The first is a touchplate,
+where a metal plate of known thickness is placed on top of the workpiece
+and then the tool is lowered until it touches the plate, triggering the probe signal.
+Z0 is set to probe height - plate thickness.
The second method uses a tool setter in a fixed position and a known height
-above the table where the probe signal will be triggered. In order to set Z0 to
-the top of the workpiece, it has to know how far above the table the probe
-trigger point is (tool setter height) and how far above the table the top of the
-workpiece is. This operation has to be done every time the tool is changed as
-the tool length is not saved.
+above the table where the probe signal will be triggered.
+In order to set Z0 to the top of the workpiece,
+it has to know how far above the table the probe trigger point is (tool setter height)
+and how far above the table the top of the workpiece is.
+This operation has to be done every time the tool is changed as the tool length is not saved.
-For touching off with a touch probe, whether you use the touchplate operation
-with thickness set to 0 or use a probing routine, the height from table to top
-of workpiece parameter is not taken into account and can be ignored. It is only
-for the tool setter.
+For touching off with a touch probe,
+whether you use the touchplate operation with thickness set to 0 or use a probing routine,
+the height from table to top of workpiece parameter is not taken into account and can be ignored.
+It is only for the tool setter.
=== Basic probe
.QtDragon - Basic Probe Option
image::images/silverdragon_probe.png["QtDragon Probe",scale="25%"]
-Basic probe is used to semi-automatically probe work pieces to find edges, centers
-and angles. +
+Basic probe is used to semi-automatically probe work pieces to find edges, centers and angles. +
The combo box allows selecting the basic type of probing buttons shown:
* Outside Corners
@@ -664,7 +621,7 @@ The combo box allows selecting the basic type of probing buttons shown:
You must carefully set the 'Probing Parameters':
-* 'Probe Tool': will only allow probing if this tool number is in the spindle
+* 'Probe Tool': will only allow probing if this tool number is in the spindle
* 'Probe Diameter': the size of the probe tip
* 'Probe Rapid': the speed of rapid moves in machine units
* 'Probe Search': the speed of the first 'rough' search in machine units
@@ -698,67 +655,58 @@ Pressing the stop button or the keyboard escape key, will abort the probing.
.QtDragon - Touch Plate
image::images/qtdragon_touchplate.png["QtDragon Touch Plate",scale="25%"]
-You can use a conductive touch plate or equivalent to auto touch off (zero the
-user coordinate) for the Z position of a tool.
+You can use a conductive touch plate or equivalent to auto touch off (zero the user coordinate) for the Z position of a tool.
There must be a tool loaded prior to probing.
-In the tool tab or settings tab, set the touch plate height, search and probe
-velocity and Max probing distance.
+In the tool tab or settings tab, set the touch plate height, search and probe velocity and Max probing distance.
[NOTE]
-When using a conductive plate the search and probe velocity should be the same
-and slow.
-If using a tool setter that has spring loaded travel then you can set search
-velocity faster.
-LinuxCNC ramps speed down at the maximum acceleration rate, so there can be
-travel after the probe trip if the speed is set to high.
+When using a conductive plate the search and probe velocity should be the same and slow.
+If using a tool setter that has spring loaded travel then you can set search velocity faster.
+LinuxCNC ramps speed down at the maximum acceleration rate,
+so there can be travel after the probe trip if the speed is set to high.
Place the plate on top of the surface you wish to zero Z on.
-Connect the probe input wire to the tool (if using a conductive plate)
+Connect the probe input wire to the tool (if using a conductive plate).
There is a LED to confirm the probe connection is reliable prior to probing.
Move the tool manually within the max probe distance.
Press the 'Touch Plate' button.
-The machine will probe down twice and the current user offset (G5X) will be
-zeroed at the bottom of the plate by calculation from the touchplate height
-setting.
+The machine will probe down twice and the current user offset (G5X) will be zeroed at the bottom of the plate
+by calculation from the touchplate height setting.
== Auto Tool Measurement
-QtDragon can be setup to do integrated auto tool measurement using the
-Versa Probe widget and remap code.
-To use this feature, you will need to do some additional settings and you may
-want to use the offered HAL pin to get values in your own ngc remap procedure.
+QtDragon can be setup to do integrated auto tool measurement using the Versa Probe widget and remap code.
+To use this feature, you will need to do some additional settings
+and you may want to use the offered HAL pin to get values in your own ngc remap procedure.
[IMPORTANT]
-Before starting the first test, do not forget to enter the probe
-height and probe velocities on the versa probe settings page.
+Before starting the first test, do not forget to enter the probe height and probe velocities
+on the versa probe settings page.
Tool Measurement in QtDragon is done with the following steps:
* Touch of you workpiece in X and Y.
-* Measure the height of your block from the base where your tool switch is
- located, to the upper face of the block (including chuck etc.).
+* Measure the height of your block from the base, where your tool switch is located,
+ to the upper face of the block (including chuck etc.).
* In the Versa probe tab, enter the measured value for block height.
* Make sure the use tool measurement button in the Vesa probe tab is enabled.
* Go to auto mode and start your program.
[NOTE]
-When fist setting up auto tool measurement, please use caution until you confirm
-tool change and probe locations - it's easy to break a tool/probe. Abort will
-be honoured while the probe is in motion.
+When fist setting up auto tool measurement,
+please use caution until you confirm tool change and probe locations - it's easy to break a tool/probe.
+Abort will be honoured while the probe is in motion.
.Auto tool measurement
image::images/sketch_auto_tool_measurement.png[align="left"]
-With the first given tool change the tool will be measured and the offset will
-be set automatically to fit the block height.
+With the first given tool change the tool will be measured and the offset will be set automatically to fit the block height.
The advantage of this way is, that you do not need a reference tool.
[NOTE]
Your program must contain a tool change at the beginning.
-The tool will be measured, even it has been used before, so there is no danger
-if the block height has changed.
-There are several videos on you tube that demonstrate the technique using
-GMOCCAPY.
+The tool will be measured, even it has been used before, so there is no danger if the block height has changed.
+There are several videos on you tube that demonstrate the technique using GMOCCAPY.
The GMOCCAPY screen pioneered the technique.
=== Work Piece Height Probing
@@ -809,20 +757,18 @@ This is only available in the QtDragon_hd version.
* Units are irrelevant in this program. The probed values are not saved and only the difference is reported.
[CAUTION]
-Setting incorrect values can lead to crashes into fixtures on the machine work surface. Initial testing with no tool and safe heights is recommended.
+Setting incorrect values can lead to crashes into fixtures on the machine work surface.
+Initial testing with no tool and safe heights is recommended.
=== Tool Measurement Pins
-Versaprobe offers 5 pins for tool measurement purpose. The pins are used
-to be read from a remap G-code subroutine, so the code can react to different
-values.
+Versaprobe offers 5 pins for tool measurement purpose.
+The pins are used to be read from a remap G-code subroutine, so the code can react to different values.
* `qtversaprobe.toolmeasurement` (HAL_BIT) enable or not tool measurement
-* `qtversaprobe.blockheight` (HAL_FLOAT) the measured value of the top face of the
- workpiece
+* `qtversaprobe.blockheight` (HAL_FLOAT) the measured value of the top face of the workpiece
* `qtversaprobe.probeheight` (HAL_FLOAT) the probe switch height
-* `qtversaprobe.searchvel` (HAL_FLOAT) the velocity to search for the tool probe
- switch
+* `qtversaprobe.searchvel` (HAL_FLOAT) the velocity to search for the tool probe switch
* `qtversaprobe.probevel` (HAL_FLOAT) the velocity to probe tool length
=== Tool Measurement INI File Modifications
@@ -882,8 +828,7 @@ m2
==== The Tool Sensor Section
The position of the tool sensor and the start position of the probing movement,
-all values are absolute (G53) coordinates, except MAXPROBE, what must be given
-in relative movement.
+all values are absolute (G53) coordinates, except MAXPROBE, what must be given in relative movement.
All values are in machine native units.
[source,{ini}]
@@ -897,9 +842,9 @@ MAXPROBE = -20
==== The Change Position Section
-This is not named TOOL_CHANGE_POSITION on purpose - *canon uses that name and
-will interfere otherwise.* The position to move the machine before giving the
-change tool command. All values are in absolute coordinates.
+This is not named TOOL_CHANGE_POSITION on purpose - *canon uses that name and will interfere otherwise*.
+The position to move the machine before giving the change tool command.
+All values are in absolute coordinates.
All values are in machine native units.
[source,{ini}]
@@ -913,7 +858,7 @@ Z = -2
==== The Python Section
The Python section sets up what files LinuxCNC's Python interpreter looks for.
-ie. 'toplevel.py' file in the 'python' folder in the configuration directory:
+I.e., 'toplevel.py' file in the 'python' folder in the configuration directory:
[source,{ini}]
----
@@ -926,7 +871,7 @@ TOPLEVEL = python/toplevel.py
=== Needed Files
-You must copy the following files to your config directory
+You must copy the following files to your config directory:
First create a folder named 'python' in your machine's configuration folder.
@@ -935,13 +880,13 @@ From 'YOUR-LINUXCNC-DIRECTORY/configs/sim/QtDragon/python', copy 'toplevel.py'
and 'remap.py' to your configuration's new 'python' folder.
if using an installed version of LinuxCNC: +
-from '/usr/share/doc/linuxcnc/examples/sample-configs/sim/qtvcp_screens/qtdragon/python/'
-, copy 'toplevel.py' and 'remap.py' to your configuration's new 'python' folder.
+from '/usr/share/doc/linuxcnc/examples/sample-configs/sim/qtvcp_screens/qtdragon/python/',
+copy 'toplevel.py' and 'remap.py' to your configuration's new 'python' folder.
Alternately, you can make new files in your 'python' folder that you made in your configuration folder,
with a text editor.
-One named 'remap.py' saved with this text:
+One named 'remap.py' saved with this text:
[source,python]
----
from stdglue import *
@@ -953,28 +898,24 @@ One named 'toplevel.py' saved with this text:
import remap
----
-Make a symbolic link or copy the following files into the 'python' folder
-described above.
+Make a symbolic link or copy the following files into the 'python' folder described above.
-In`~/linuxcnc/nc_files/examples/remap_subroutine/` folder
+In `~/linuxcnc/nc_files/examples/remap_subroutine/` folder.
-In `~/linuxcnc/nc_files/examples/remap_lib/python_stdglue/` folder
+In `~/linuxcnc/nc_files/examples/remap_lib/python_stdglue/` folder.
[NOTE]
-These file names and location could be different depending on installed verses
-development (RIP) version of LinuxCNC.
+These file names and location could be different depending on installed verses development (RIP) version of LinuxCNC.
For instance `~/linuxcnc/nc_files/macros` is `~/linuxcnc/nc_files/examples/macros`
in installed versions of LinuxCNC.
You could use customized versions of the same files or name them differently.
-The entries in the '[RS274NGC]' section dictate to LinuxCNC what and where to
-look.
+The entries in the '[RS274NGC]' section dictate to LinuxCNC what and where to look.
The names and location quoted should be available in either system by default.
=== Needed HAL Connections
Make sure to connect the tool probe input in your HAL file:
-If connected properly, you should be able to toggle the probe LED in QtDragon
-if you press the probe stylus.
+If connected properly, you should be able to toggle the probe LED in QtDragon if you press the probe stylus.
[source,{hal}]
----
@@ -983,36 +924,27 @@ net probe motion.probe-input <= <your_input_pin>
== Run from Line
-A G-code program can be started at any line by clicking on the desired line in
-the G-code display while in AUTO mode.
-It is the operator's responsibility to ensure the machine is in the desired
-operational mode.
+A G-code program can be started at any line by clicking on the desired line in the G-code display while in AUTO mode.
+It is the operator's responsibility to ensure the machine is in the desired operational mode.
A dialog will be shown allowing the spindle direction and speed to be preset.
-The start line is indicated in the box labelled LINE, next to the CYCLE START
-button.
+The start line is indicated in the box labelled LINE, next to the CYCLE START button.
The run from line feature can be disabled in the settings page.
[NOTE]
-LinuxCNC's run-from-line is not very user friendly. E.g., it does not start the
-spindle or confirm the proper tool.
-Also, it does not handle subroutines well. If used it is best to start on a rapid
-move.
+LinuxCNC's run-from-line is not very user friendly.
+E.g., it does not start the spindle or confirm the proper tool.
+Also, it does not handle subroutines well. If used it is best to start on a rapid move.
== Laser buttons
-The LASER ON/OFF button in intended to turn an output on or off which is
-connected to a small laser crosshair projector.
-When the crosshair is positioned over a desired reference point on the workpiece,
-the REF LASER button can be pushed which then sets
-the X and Y offsets to the values indicated by the LASER OFFSET fields in the
-Settings page and the INI file.
+The LASER ON/OFF button in intended to turn an output on or off which is connected to a small laser crosshair projector.
+When the crosshair is positioned over a desired reference point on the workpiece, the REF LASER button can be pushed,
+which then sets the X and Y offsets to the values indicated by the LASER OFFSET fields in the Settings page.
== Tabs Description
-Tabs allow the user to select the most appropriate info/control on the top three
-panels. +
-If the on screen keyboard is showing and the user wishes to hide it but keep the
-current tab, +
+Tabs allow the user to select the most appropriate info/control on the top three panels. +
+If the on screen keyboard is showing and the user wishes to hide it but keep the current tab, +
they can do that by pressing the current show tab.
=== Main tab
@@ -1026,12 +958,12 @@ The side buttons will control the display.
* '+', '-': Zoom controls
* 'C': Clear graphics of tool movement lines
-In QtDragon_hd there are also macro buttons available on the right side. +
+In QtDragon_hd there are also macro buttons available on the right side.
Up to tens buttons can be defined in the INI.
=== File Tab
-You can use this tab to load or transfer programs. +
+You can use this tab to load or transfer programs.
Editing of G-code programs can be selected from this tab.
With qtdragon_hd, this is where you can load 'Gcode Ripper'
@@ -1056,34 +988,30 @@ Pressing this tool button will drop down a when menu of options:
=== Status Tab
-A time-stamped log of important machine or system events will be shown here. +
-Machine events would be more suited to an operator, where the system events may
-help in debugging problems.
+A time-stamped log of important machine or system events will be shown here.
+Machine events would be more suited to an operator, where the system events may help in debugging problems.
=== Probe Tab
-Probing routines options are displayed on this tab. Depending on INI options,
-this could be +
-VersaProbe or BasicProbe style. They are functionally similar. +
+Probing routines options are displayed on this tab.
+Depending on INI options, this could be VersaProbe or BasicProbe style.
+They are functionally similar.
QtDragon_hd will also show a smaller graphics display window.
=== Camview Tab
-If the recognized webcam is connected, this tab will display the video image
-overlayed with a cross-hair +
-, circle and degree readout. This can be adjusted to suit a part feature for
-such things as touchoff. +
+If the recognized webcam is connected, this tab will display the video image overlayed with a cross-hair,
+circle and degree readout. This can be adjusted to suit a part feature for such things as touchoff.
The underlying library uses openCV Python module to connect to the webcam.
=== G-codes Tab
-This tab will display a list of LinuxCNC's G-code. +
+This tab will display a list of LinuxCNC's G-code.
if you click on a line, a description of the code will be displayed.
=== Setup Tab
-It's possible to load HTML or PDF file (.html / .pdf ending) with setup
-notes.
+It's possible to load HTML or PDF file (.html / .pdf ending) with setup notes.
HTML/PDF docs will be displayed in the setup tab.
Some program, such as Fusion 360 and Aspire will create these files for you.
If you load a G-code program and there is an HTML/PDF file of the same name, it will load automatically.
@@ -1095,28 +1023,25 @@ image::images/silverdragon_setup.png["QtDragon Setup Tab",scale="25%"]
=== Settings Tab
-The settings tab is used to set running options, probing/touchplate/laser/camera
-offsets and load debugging external programs.
+The settings tab is used to set running options,
+probing/touchplate/laser/camera offsets and load debugging external programs.
=== Utilities Tab
-This tabs will display another stab election of G-code utility programs. +
+This tabs will display another stab election of G-code utility programs:
-* 'Facing': allows quick face milling of a definable area at angles of 0,45 and
- 90 degrees
-* 'Hole Circle': allows quick setting of a program to drill a bolt circle of
- definable diameter and number of holes.
+* 'Facing': allows quick face milling of a definable area at angles of 0,45 and 90 degrees
+* 'Hole Circle': allows quick setting of a program to drill a bolt circle of definable diameter and number of holes.
* 'NGCGUI': is a QtVCP version of the popular G-code subroutine builder/selector.
Custom QtVCP panels can be displayed here by setting the EMBED_TAB_LOCATION option to 'tabWidget_utilities'
== Styles
-Nearly all aspects of the GUI appearance are configurable via the QtDragon.qss
-stylesheet file. The file can be edited manually or
-through the stylesheet dialog widget in the GUI. To call up the dialog, press
-F12 on the main window. New styles can be applied
-temporarily and then saved to a new qss file, or overwrite the current qss file.
+Nearly all aspects of the GUI appearance are configurable via the QtDragon.qss stylesheet file.
+The file can be edited manually or through the stylesheet dialog widget in the GUI.
+To call up the dialog, press F12 on the main window.
+New styles can be applied temporarily and then saved to a new qss file, or overwrite the current qss file.
.QtDragon - Two Style Examples
image::images/style-comparison.png["QtDragon styles",scale="25%"]
@@ -1127,15 +1052,12 @@ A general overview of <<cha:qtvcp:modifying-screens,Customizing Stock Screens>>
=== Stylesheets
-Stylesheets can be leveraged to do a fair amount of customization, but you
-usually need to know a bit about the widget names.
-Pressing F12 will display a stylesheet editor dialog to load/test/save
-modification. Some times these lines will be present and you can change them
-sometimes yo need to add them.
+Stylesheets can be leveraged to do a fair amount of customization,
+but you usually need to know a bit about the widget names.
+Pressing F12 will display a stylesheet editor dialog to load/test/save modification.
+Some times these lines will be present and you can change them sometimes yo need to add them.
-For instance:
-
-To change the DRO font (look for this entry and change the font name):
+For instance, to change the DRO font (look for this entry and change the font name):
[source,{ini}]
----
@@ -1156,7 +1078,7 @@ DROLabel {
qproperty-imperial_template: '%9.5f';
qproperty-metric_template: '%10.4f';
qproperty-angular_template: '%11.2f';
-}
+}
----
To change the text of the mist button to 'air' (add these lines)
@@ -1184,7 +1106,7 @@ OriginOffsetView {
font: 12pt "Lato Heavy";
qproperty-imperial_template: '%9.1f';
qproperty-metric_template: '%10.1f';
-}
+}
----
To stop the blur effect with dialogs:
@@ -1198,14 +1120,12 @@ To stop the blur effect with dialogs:
=== Qt Designer and Python code
-All aspects of the GUI are fully customization through Qt Designer and/or
-Python code.
+All aspects of the GUI are fully customization through Qt Designer and/or Python code.
This capability is included with the QtVCP development environment.
-The extensive use of QtVCP widgets keeps the amount of required Python code to
-a minimum, allowing relatively easy modifications.
-The LinuxCNC website has extensive documentation on the installation and use of
-QtVCP libraries.
-<<cha:qtvcp,QtVCP Overview>> for more information
+The extensive use of QtVCP widgets keeps the amount of required Python code to a minimum,
+allowing relatively easy modifications.
+The LinuxCNC website has extensive documentation on the installation and use of QtVCP libraries.
+See <<cha:qtvcp,QtVCP Overview>> for more information.
.QtDragon - Customized QtDragon
image::images/silverdragon_custom.png["QtDragon customized",scale=25]
diff --git a/docs/src/gui/qtvcp-code-snippets.adoc b/docs/src/gui/qtvcp-code-snippets.adoc
index 0d0894653c..e9a3ab9ac6 100644
--- a/docs/src/gui/qtvcp-code-snippets.adoc
+++ b/docs/src/gui/qtvcp-code-snippets.adoc
@@ -147,14 +147,13 @@ The function
* creates a Python `dict` with:
** *`NAME`* - needs to be set to the _dialogs unique launch name_. +
- `NAME` sets which dialog to request. +
- `ENTRY` or `CALCULATOR` allows entering numbers.
+`NAME` sets which dialog to request. +
+`ENTRY` or `CALCULATOR` allows entering numbers.
//FIXME Is that a user defined unique name or a dialog type ?
-** *`ID`* - needs to be set to a _unique name that the function supplies_. +
- `ID` should be a unique key.
+** *`ID`* - needs to be set to a _unique name that the function supplies_.
+`ID` should be a unique key.
** *`TITLE`* sets the dialog title.
-** *Arbitrary data* can be added to the `dict`. +
- The dialog will ignore them but send them back to the return code.
+** *Arbitrary data* can be added to the `dict`. The dialog will ignore them but send them back to the return code.
* Sends the `dict` as a *`dialog-request`* `STATUS` message
.Add message data processing function in the `CALLBACKS FROM STATUS SECTION`
@@ -564,8 +563,8 @@ For this we _register_ with `STATUS` to:
########################
# **** INITIALIZE **** #
########################
-# widgets allows access to widgets from the QtVCP files
-# at this point the widgets and hal pins are not instantiated
+# Widgets allow access to widgets from the QtVCP files.
+# At this point the widgets and HAL pins are not instantiated.
def __init__(self,halcomp,widgets,paths):
self.hal = halcomp
self.w = widgets
@@ -731,8 +730,7 @@ def update_periodic(self):
== External Control With ZMQ
-_QtVCP can automatically set up_ *ZMQ messaging* _to send and/or receive
-remote messages from external programs_.
+_QtVCP can automatically set up_ *ZMQ messaging* _to send and/or receive remote messages from external programs_.
It uses ZMQ's *publish/subscribe messaging pattern*.
@@ -743,8 +741,7 @@ As always, consider *security* before letting programs interface though messagin
Sometimes you want to *control the screen with a separate program*.
.Enable reception of ZMQ messages
-In the `ScreenOptions` widget, you can select the property
-*`use_receive_zmq_option`*. +
+In the `ScreenOptions` widget, you can select the property *`use_receive_zmq_option`*. +
You can also set this property directly _in the handler file_, as in this sample.
We assume the `ScreenOptions` widget is called `screen_options` in Qt Designer:
@@ -800,7 +797,7 @@ x = { # <1>
"FUNCTION": "test_zmq_function",
"ARGS": [True,200]
}
-# convert to json object
+# convert to JSON object
m1 = json.dumps(x)
# prebuild message 2
@@ -808,7 +805,7 @@ x = { # <1>
"FUNCTION": "test_zmq_function",
"ARGS": [False,0],
}
-# convert to json object
+# convert to JSON object
m2 = json.dumps(x)
if __name__ == '__main__':
@@ -824,19 +821,19 @@ if __name__ == '__main__':
<1> Set the *function to call* and the *arguments to send* to that function.
-You will need to know the _signature_ of the function you wish to call. +
-Also note that the _message is converted to a json object_. +
-This is because ZMQ sends byte messages not Python objects. +
+You will need to know the _signature_ of the function you wish to call.
+Also note that the _message is converted to a JSON object_.
+This is because ZMQ sends byte messages not Python objects.
`json` converts Python objects to bytes and will be converted back when received.
=== ZMQ Messages Writing
You may also want to *communicate with an external program from the screen*.
-In the `ScreenOptions` widget, you can select the property *`use_send_zmq_message`*. +
+In the `ScreenOptions` widget, you can select the property *`use_send_zmq_message`*.
You can also set this property directly _in the handler file_, as in this sample.
-We assume the `ScreenOptions` widget is called `screen_options` in Qt Designer: +
+We assume the `ScreenOptions` widget is called `screen_options` in Qt Designer:
.Enable sending of ZMQ messages
[source,python]
@@ -865,7 +862,7 @@ Also, something needs to be added to call this function, such as a button click.
# general functions #
#####################
def send_zmq_message(self):
- # This could be any Python object json can convert
+ # This could be any Python object JSON can convert
message = {"name": "John", "age": 30}
self.w.screen_options.send_zmq_message(message)
----
@@ -915,7 +912,7 @@ You can also use the `Status` library to send a message to the `notify`
library if it is enabled (usually set in `ScreenOptions` widget):
this will send the message to the statusbar and the *desktop notify dialog*.
-The messages are also recorded until the user erases them using controls. +
+The messages are also recorded until the user erases them using controls.
The users can recall any recorded messages.
There are several options:
@@ -934,8 +931,8 @@ There are several options:
STATUS.emit('error', STATUS.OPERATOR_ERROR, 'message')
----
-You can send messages thru LinuxCNC's operator message functions. +
-These are usually caught by the notify system, so are equal to above. +
+You can send messages thru LinuxCNC's operator message functions.
+These are usually caught by the notify system, so are equal to above.
They would be printed to the terminal as well.
[source,python]
@@ -984,7 +981,7 @@ This is because _some QtVCP widgets are built from multiple_ *_sub-widgets_*
and the latter actually get the focus; so we need to *check the parent* of those sub-widgets.
Other times the main widget is what gets the focus,
-e.g. the G-code display widget can be set to accept the focus,
+e.g., the G-code display widget can be set to accept the focus.
In that case there are no sub-widgets in it,
so comparing to the `widget.parent()` would get you the container that holds the G-code widget.
diff --git a/docs/src/gui/qtvcp-libraries.adoc b/docs/src/gui/qtvcp-libraries.adoc
index 4c1a976d98..1b1958cc2d 100644
--- a/docs/src/gui/qtvcp-libraries.adoc
+++ b/docs/src/gui/qtvcp-libraries.adoc
@@ -10,12 +10,12 @@
:hal: {basebackend@docbook:'':hal}
:ngc: {basebackend@docbook:'':ngc}
-Libraries are *prebuilt Python modules that give added features to QtVCP*. +
-In this way you can select what features you want - yet don't have to build common ones yourself. +
+Libraries are *prebuilt Python modules that give added features to QtVCP*.
+In this way you can select what features you want - yet don't have to build common ones yourself.
== `Status`
-*`Status`* is a library that *sends GObject messages based on LinuxCNC's current state*. +
+*`Status`* is a library that *sends GObject messages based on LinuxCNC's current state*.
It is an _extension of GladeVCP's <<cha:gstat,GStat>> object_.
It also has some functions to report status on such things as internal jog rate.
@@ -54,8 +54,8 @@ STATUS = Status()
For example, you can catch machine on and off messages.
[NOTE]
-The example below shows the _two common ways of connecting signals_, one of them _using lambda_. +
-*`lambda`* is _used to strip off or manipulate arguments_ from the status message before calling the function. +
+The example below shows the _two common ways of connecting signals_, one of them _using lambda_.
+*`lambda`* is _used to strip off or manipulate arguments_ from the status message before calling the function.
You can see the difference in the called function signature:
The one that uses lambda does not accept the status object - lambda did not pass it to the function.
@@ -205,7 +205,7 @@ There are some _helper functions_ - mostly used for widget support:
from qtvcp.core import Info
----
-* *Instantiate `Info` module* +
+* *Instantiate `Info` module*. +
Add this Python code to your instantiate section:
+
[source,python]
@@ -569,8 +569,7 @@ WIDGETS = VCPWindow()
== `Aux_program_loader`
//FIXME Aux_program_loader: load (into QtVCP) or launch ?
-*`Aux_program_loader`* module allows an easy way to
-*load auxiliary programs LinuxCNC often uses*.
+*`Aux_program_loader`* module allows an easy way to *load auxiliary programs LinuxCNC often uses*.
=== Helpers
@@ -690,8 +689,7 @@ from qtvcp.lib.keybindings import Keylookup
.Instantiate `Keylookup` module
-To instantiate `Keylookup` module* so you can use it, add this
-Python code to your instantiate section:
+To instantiate `Keylookup` module* so you can use it, add this Python code to your instantiate section:
[source,python]
----
@@ -705,10 +703,9 @@ KEYBIND = Keylookup()
.Add Key Bindings
NOTE: `Keylookup` requires code under the `processed_key_event` function to call `KEYBIND.call()`. +
- Most handler files already have this code.
+Most handler files already have this code.
-In the handler file, under the _initialized function_ use this general
-syntax to *create keybindings*:
+In the handler file, under the _initialized function_ use this general syntax to *create keybindings*:
[source,python]
----
@@ -761,38 +758,32 @@ These messages are:
=== Properties
-*`_BOLDTEXT`*::
- Generally is a title.
-*`_TEXT`*::
- Text below title, and usually longer.
-*`_DETAIL`*::
- Text hidden unless clicked on.
-*`_PINNAME`*::
- Basename of the HAL pin(s).
-*`_TYPE`*::
- Specifies whether it is a:
+*`_BOLDTEXT`*:: Generally is a title.
+*`_TEXT`*:: Text below title, and usually longer.
+*`_DETAIL`*:: Text hidden unless clicked on.
+*`_PINNAME`*:: Basename of the HAL pin(s).
+*`_TYPE`*:: Specifies whether it is a:
* *Status message* - shown in the _status bar and the notify dialog_. +
- Requires no user intervention.
+Requires no user intervention.
* *OK message* - _requiring the user to click OK to close the dialog_. +
- OK messages have _two HAL pins_:
+OK messages have _two HAL pins_:
** One HAL pin to launch the dialog, and
** One to signify it's waiting for response.
* *Yes/No message* - _requiring the user to select yes or no buttons to close the dialog_. +
- Yes/No messages have _three HAL pins_:
+Yes/No messages have _three HAL pins_:
** One to show the dialog,
** One for waiting, and
** one for the answer.
//FIXME Messages: means STATUS messages will be generated each
// time a focus_overlay is called or an alert sound emitted ?
-By default it will send `STATUS` messages for `focus_overlay` and alert sound. +
+By default it will send `STATUS` messages for `focus_overlay` and alert sound.
//FIXME Messages: Usage
=== Examples
-Here are sample INI message definition code blocks that would be found
-under the `[DISPLAY]` heading:
+Here are sample INI message definition code blocks that would be found under the `[DISPLAY]` heading:
* Status bar and desktop notify pop up message:
+
@@ -1125,27 +1116,19 @@ qtvcp vismach_5axis_gantry
Provides the *basic building blocks of a simulated machine*.
-*`Collection`*::
- A `collection` is an *object of individual machine parts*.
+*`Collection`*:: A `collection` is an *object of individual machine parts*.
+
-This holds a *hierarchical list* of primitive shapes or _STL objects_
-that operations can be applied to.
+This holds a *hierarchical list* of primitive shapes or _STL objects_ that operations can be applied to.
//TODO Can't a collection hold other collections ?
-*`Translate`*::
- This object will perform an *OpenGL translation* calculation
- _on a Collection object_.
+*`Translate`*:: This object will perform an *OpenGL translation* calculation _on a Collection object_.
//TODO Not on primitives ?
+
-Translation refers to _moving an object in straight line_ to a different
-position on screen.
+Translation refers to _moving an object in straight line_ to a different position on screen.
-*`Scale`*::
- This object will perform an *OpenGL scale* function _on a collection object_.
+*`Scale`*:: This object will perform an *OpenGL scale* function _on a collection object_.
-*`HalTranslate`*::
- This object will perform an *OpenGL translation* calculation
- _on a Collection object_, *offset by the HAL pin value*.
+*`HalTranslate`*:: This object will perform an *OpenGL translation* calculation _on a Collection object_, *offset by the HAL pin value*.
+
Translation refers to moving an object in straight line to a different position on screen.
+
@@ -1154,20 +1137,15 @@ You can either:
* _read a pin from a component owned by the Vismach object_, or
* _read a HAL system pin directly_ if the component argument is set to `None`.
-*`Rotate`*::
- This object will perform an *OpenGL rotation* calculation
- _on a Collection object_.
-
-*`HalRotate`*::
- This object will perform an *OpenGL rotation* calculation _on a Collection object_, *offset by the HAL pin value*.
+*`Rotate`*:: This object will perform an *OpenGL rotation* calculation _on a Collection object_.
+*`HalRotate`*:: This object will perform an *OpenGL rotation* calculation _on a Collection object_, *offset by the HAL pin value*.
+
You can either:
+
* _read a pin from a component owned by the vismach_ object, or
* _read a HAL system pin directly_ if the component argument is set to `None`.
-*`HalToolCylinder`*::
- This object will build a _CylinderZ object_ that will *change size and length based on loaded tool dimensition* (from the tool table) +
+*`HalToolCylinder`*:: This object will build a _CylinderZ object_ that will *change size and length based on loaded tool dimensition* (from the tool table) +
+
It reads the `halui.tool.diameter` and `motion.tooloffset.z` _HAL pins_.
+
@@ -1188,11 +1166,9 @@ tool = Collection([
+
Base object to _hold coordinates for primitive shapes_.
-*`CylinderX`, `CylinderY`, `CylinderZ`*::
- *Build a cylinder on the X, Y or Z axis* by giving _endpoint_ (X, Y, or Z) and _radii_ coordinates.
+*`CylinderX`, `CylinderY`, `CylinderZ`*:: *Build a cylinder on the X, Y or Z axis* by giving _endpoint_ (X, Y, or Z) and _radii_ coordinates.
-*`Sphere`*::
- *Build a sphere* from _center_ and _radius_ coordinates.
+*`Sphere`*:: *Build a sphere* from _center_ and _radius_ coordinates.
//FIXME Vismach: Triangle: Don't coordinates need 2 axes and not be limited to Z !?
*`TriangleXY`, `TriangleXZ`, `TriangleYZ`*::
@@ -1209,8 +1185,7 @@ Base object to _hold coordinates for primitive shapes_.
*Build a box centered on origin* by specifying the _width in X and Y_, and the _height in Z_.
*`BoxCenteredXY`*::
- *Build a box centered in X and Y, and running from Z=0*,
- by specifying the _width in X and Y_, and running up or down to the specified _height in Z_.
+ *Build a box centered in X and Y, and running from Z=0*, by specifying the _width in X and Y_, and running up or down to the specified _height in Z_.
*`Capture`*::
*Capture current transformation matrix of a collection*.
@@ -1252,16 +1227,16 @@ Instantiate the simulation widget and add it to the screen's main layout:
[source,python]
----
- ##########################################
- # Special Functions called from QtVCP
- ##########################################
+##########################################
+# Special Functions called from QtVCP
+##########################################
- # At this point:
- # * the widgets are instantiated,
- # * the HAL pins are built but HAL is not set ready.
- def initialized__(self):
- machine = MILL.Window()
- self.w.mainLayout.addWidget(machine)
+# At this point:
+# * the widgets are instantiated,
+# * the HAL pins are built but HAL is not set ready.
+def initialized__(self):
+ machine = MILL.Window()
+ self.w.mainLayout.addWidget(machine)
----
=== More Information
diff --git a/docs/src/gui/qtvcp-vismach.adoc b/docs/src/gui/qtvcp-vismach.adoc
index a29b106de6..a9c9e49660 100644
--- a/docs/src/gui/qtvcp-vismach.adoc
+++ b/docs/src/gui/qtvcp-vismach.adoc
@@ -6,8 +6,8 @@
*Vismach* is a set of *Python functions that can be used to create and animate models of machines*.
-This chapter is about the Qt embedded version of <<cha:vismach,Vismach>>.
-Also see: https://sa-cnc.com/linuxcnc-vismach/
+This chapter is about the Qt embedded version of <<cha:vismach,Vismach>>,
+also see: https://sa-cnc.com/linuxcnc-vismach/ .
[[sec:qtvcp:vismach:intro]]
== Introduction
@@ -223,18 +223,17 @@ rotation axis is created at the origin (but moves with the Part).
=== Rotating Model Parts
*`part1 = Rotate([part1], theta, x, y, z)`*::
- Rotate the part by angle theta degrees about an axis between the origin and
+ Rotate the part by angle theta [degrees] about an axis between the origin and
x, y, z.
[[sec:qtvcp:vismach:animate]]
== Animating Parts
//FIXME 2 or 3 functions ? HalToolCylinder not documented here ?
-To *animate the model controlled by the values of HAL pins* there are
-four functions `HalTranslate`, `HalRotate`, `HalToolCylinder` and 'HalToolTriangle'.
+To *animate the model controlled by the values of HAL pins* there are four functions:
+`HalTranslate`, `HalRotate`, `HalToolCylinder` and `HalToolTriangle`.
-_For parts to move inside an assembly they need to have their HAL motions
-defined before being assembled with the "Collection" command_.
+_For parts to move inside an assembly they need to have their HAL motions defined before being assembled with the "Collection" command_.
The *rotation axis and translation vector move with the part*:
@@ -282,8 +281,7 @@ Otherwise the component instance would be specified and the pin name of that com
=== 'HalToolCylinder'
*`tool = HalToolCylinder()`*::
- Make a cylinder to represent a cylindrical mill tool, based on the tool table
- and current loaded tool.
+ Make a cylinder to represent a cylindrical mill tool, based on the tool table and current loaded tool.
[source,python]
----
@@ -297,8 +295,7 @@ toolshape = Color([1, .5, .5, .5], [HalToolCylinder()])
=== 'HalToolTriangle'
*`tool = HalToolTriangle()`*::
- Make a triangle to represent a triangular lathe tool, based on the tool table
- and current loaded tool.
+ Make a triangle to represent a triangular lathe tool, based on the tool table and current loaded tool.
[source,python]
----
@@ -322,9 +319,9 @@ For example to create a moving head milling machine with a rotating spindle and
* Create the spindle at the origin.
* Define the rotation.
* Move the head to the spindle or spindle to the head.
-* Create the draw bar
-* Define the motion of the draw bar
-* Assemble the three parts into a head assembly
+* Create the draw bar.
+* Define the motion of the draw bar.
+* Assemble the three parts into a head assembly.
* Define the motion of the head assembly.
In this example the spindle rotation is indicated by rotation of a set of drive dogs:
@@ -395,20 +392,21 @@ model = Collection([base, saddle, head, carousel])
This sets the current position in the model.
*`main(model, tooltip, work, size=10, hud=myhud, rotation_vectors=None, lat=0, lon=0)`*::
- This is the command that makes it all happen, creates the display, etc. if invoked directly from Python. +
+ This is the command that makes it all happen, creates the display, etc. if invoked directly from Python.
Usually this file is imported by QtVCP and the `window()` object is instantiated and embedded into another screen.
`_model_`;; Should be a collection that contains all the machine parts.
- `_tooltip_` and `_work_`;; Need to be created by `Capture()` to visualize their motion in the backplot. +
+ `_tooltip_` and `_work_`;; Need to be created by `Capture()` to visualize their motion in the backplot.
See `mill_xyz.py` for an example of how to connect the tool tip to a tool and the tool to the model.
`_size_`;; Sets the extent of the volume visualized in the initial view. +
hud refers to a head-up display of axis positions.
- `_rotation_vectors_` or `_lat, lon_`;; Can be used to set the original viewpoint. +
+ `_rotation_vectors_` or `_lat, lon_`;; Can be used to set the original viewpoint.
It is advisable to do as the default initial viewpoint is rather unhelpful from immediately overhead.
== Tips
-create an axes origin marker to be able to see parts relative to it, for
-construction purposes. You can remove it when you are done.
+
+Create an axes origin marker to be able to see parts relative to it, for construction purposes.
+You can remove it when you are done.
[source,python]
----
@@ -429,8 +427,8 @@ v.model = Collection([origin, model, world])
----
Start from the cutting tip and work your way back.
-add each collection to the model at the origin and run the script to confirm
-the location, then rotate/translate and run the script to confirm again.
+Add each collection to the model at the origin and run the script to confirm the location,
+then rotate/translate and run the script to confirm again.
[[sec:qtvcp:vismach:structure]]
== Basic structure of a `QtVismach` script
diff --git a/docs/src/gui/qtvcp-widgets.adoc b/docs/src/gui/qtvcp-widgets.adoc
index 3a611b5954..68157ae43d 100644
--- a/docs/src/gui/qtvcp-widgets.adoc
+++ b/docs/src/gui/qtvcp-widgets.adoc
@@ -206,11 +206,9 @@ self.w.halpadname.set_highlight(self.w.halpadname.LEFTRIGHT)
.`HALPad` Properties
*`pin_name`*::
- Optional name to use for the _HAL pins basename_. +
- If left blank, the Qt Designer widget name will be used.
+ Optional name to use for the _HAL pins basename_. If left blank, the Qt Designer widget name will be used.
*`pin_type`*::
- Select the _HAL output pin type_.
- This property is only used at startup.
+ Select the _HAL output pin type_. This property is only used at startup.
Selection can be set in Qt Designer:
+
** `NONE`
@@ -226,7 +224,7 @@ self.w.halpadname.set_highlight(self.w.halpadname.LEFTRIGHT)
*`top_image_path`*::
*`bottom_image_path`*::
File or resource path to an image to display in the described button location. +
- If the reset button is pressed in the Qt Designer editor property, the image will not be displayed. (allowing optional text)
+ If the reset button is pressed in the Qt Designer editor property, the image will not be displayed (allowing optional text).
*`left_text`*::
*`right_text`*::
*`center_text`*::
@@ -450,8 +448,8 @@ These buttons are used for *control actions on the machine controller*.
They are built on top of `IndicatedPushButton` so can have LEDs overlaid.
[NOTE]
-If you left double click on this widget you can launch a dialog to set any of these actions. +
-The dialogs will help to set the right related data to the selected action. +
+If you left double click on this widget you can launch a dialog to set any of these actions.
+The dialogs will help to set the right related data to the selected action.
You can also change these properties directly in the property editor.
.Actions
@@ -562,7 +560,7 @@ MDI_COMMAND = G53 G0 Z0;G53 G0 X0 Y0, Goto\nMachn\nZero
//FIXME add link to Indicated_PushButton section
Action buttons are subclassed from
-<<sub:qtvcp:widgets:indicatedpushbutton>>[`IndicatedPushButton`]. +
+<<sub:qtvcp:widgets:indicatedpushbutton>>[`IndicatedPushButton`].
See the following sections for more information about:
* <<sub:qtvcp:widgets:indicatedpushbutton:led,LED Indicator option>>
@@ -665,11 +663,11 @@ This will *display the current position of an axis*.
Format of display, e.g. `%10.3f`.
*`imperial_template`*::
format of display, e.g. `%9.4f`.
-*`angular_template `*::
+*`angular_template`*::
Format of display, e.g. `%Rotational: 10.1f`.
-The `DROLabel` widget holds a property *`isHomed`* that can be used with a stylesheet
-to change the _color of the `DRO_Label` based on homing state of the joint_ number in LinuxCNC.
+The `DROLabel` widget holds a property *`isHomed`* that can be used with a stylesheet to change the _color of the `DRO_Label`
+based on homing state of the joint_ number in LinuxCNC.
Here is a sample stylesheet entry that:
@@ -695,7 +693,7 @@ DROLabel[isHomed=true] {
}
----
-Here is how you specify a particular widget by it's `objectName` in Qt Designer.
+Here is how you specify a particular widget by it's `objectName` in Qt Designer:
[source,{css}]
----
@@ -726,7 +724,8 @@ It has a _signal_ *`percentDone(int)`* that can be connected to a slot (such as
*`auto_show_manual_status`*::
Set true to have the widget switch to machine log when in Manual mode.
-The `GcodeDisplay` properties can be set in a stylesheet with the following code added to the .qss file (the following color choices are random).
+The `GcodeDisplay` properties can be set in a stylesheet with the following code added to the .qss file
+(the following color choices are random).
[source,{css}]
----
@@ -1187,11 +1186,11 @@ These states are selectable:
This uses _Python formatting rules_ to set the text output. +
One can use `%s` for no conversion, `%d` for integer conversion, `%f` for float conversion, etc. +
You can also use _Qt rich text_ code. +
- Typical template used for formatting imperial float numbers to text would be `%9.4f` or `%9.4f inch`.
+ Typical template used for formatting imperial float numbers to text would be `%9.4f` or `%9.4f inch`.
*`alt_textTemplate`*::
This is usually used for *metric (`G21`) numerical settings*. +
This uses _Python formatting rules_ to set the text output. +
- Typical template used for formatting metric float to text would be `%10.3f` or `%10.3f mm`.
+ Typical template used for formatting metric float to text would be `%10.3f` or `%10.3f mm`.
It is based on PyQt's _QLabel_.
@@ -1227,11 +1226,11 @@ Selecting image paths can be done by selecting the `pixmap` property and selecti
NOTE: The `pixmap` setting is for test display only and will be ignored outside of Qt Designer.
-* Right click the image name and you should see 'Copy path'
-* Click 'Copy path'
+* Right click the image name and you should see 'Copy path'.
+* Click 'Copy path'.
* Now double click the 'image list' property so the dialog shows.
-* Click the 'New' button
-* Paste the image path in the entry box
+* Click the 'New' button.
+* Paste the image path in the entry box.
Do that again for the next image. +
_Use a clear image to represent a hidden icon._
@@ -2348,7 +2347,7 @@ It is based on PyQt's _QMessagebox_.
=== `OriginOffsetDialog` - Origin Offset Setting Dialog Widget
.QtVCP `OriginOffsetDialog`: Origin Offset Setting Widget
-image::images/qtvcp_offsetpage.png["QtVCP `OriginOffsetDialog``: Origin Offset Setting Widget",scale="25%"]
+image::images/qtvcp_offsetpage.png["QtVCP `OriginOffsetDialog`: Origin Offset Setting Widget",scale="25%"]
This widget allows one to *modify User System origin offsets directly* in a dialog form.
diff --git a/docs/src/gui/qtvcp.adoc b/docs/src/gui/qtvcp.adoc
index c5258fa434..5ba4fff8d1 100644
--- a/docs/src/gui/qtvcp.adoc
+++ b/docs/src/gui/qtvcp.adoc
@@ -196,11 +196,12 @@ QtVCP can also be customized with _Qt stylesheets (QSS)_ using CSS.
=== Local Files
-If present, local UI/QSS/python files in the configuration folder will be loaded
-instead of the stock UI files.
+//FIXME Does that applies to .ui files only or handler.py and qss too ?
+//FIXME How does overriding/inheritance actually works ?
-Local UI/QSS/python files allow you to use your customized designs rather than the
-default screens.
+If present, local UI files in the configuration folder will be loaded instead of the stock UI files.
+
+Local UI files allow you to use your customized designs rather than the default screens.
QtVCP will look for a folder named _<screen_name>_ (in the launched configuration folder that holds the INI file).
diff --git a/docs/src/hal/canonical-devices.adoc b/docs/src/hal/canonical-devices.adoc
index bd47f231c5..41cb2383b9 100644
--- a/docs/src/hal/canonical-devices.adoc
+++ b/docs/src/hal/canonical-devices.adoc
@@ -107,32 +107,24 @@ of values. Examples are digital to analog converters or PWM generators.
[[sub:hal-cdi:ao:parameters]]
=== Parameters(((HAL Analog Output Parameters)))
-(float) *offset*:: This will be added to the *value* before the
- hardware is updated.
-(float) *scale*:: This should be set so that an input of 1 on the
- *value* pin will cause the analog output pin to read 1 volt.
-(float) *high_limit* (optional):: When calculating the value to
- output to the hardware, if *value* + *offset* is greater than
- *high_limit*, then *high_limit* will be used instead.
-(float) *low_limit* (optional):: When calculating the value to output
- to the hardware, if *value* + *offset* is less than *low_limit*, then
- *low_limit* will be used instead.
-(float) *bit_weight* (optional):: The value of one least significant
- bit (LSB), in volts (or mA, for current outputs).
-(float) *hw_offset* (optional):: The actual voltage (or current)
- that will be output if 0 is written to the hardware.
+(float) *offset*:: This will be added to the *value* before the hardware is updated.
+(float) *scale*:: This should be set so that an input of 1 on the *value* pin will cause the analog output pin to read 1 volt.
+(float) *high_limit* (optional):: When calculating the value to output to the hardware,
+ if *value* + *offset* is greater than *high_limit*, then *high_limit* will be used instead.
+(float) *low_limit* (optional):: When calculating the value to output to the hardware,
+ if *value* + *offset* is less than *low_limit*, then *low_limit* will be used instead.
+(float) *bit_weight* (optional):: The value of one least significant bit (LSB), in volts (or mA, for current outputs).
+(float) *hw_offset* (optional):: The actual voltage (or current) that will be output if 0 is written to the hardware.
[[sub:hal-cdi:ao:functions]]
=== Functions(((HAL Analog Output Functions)))
(funct) *write*::
- This causes the calculated value to be output to
- the hardware. If enable is false, then the output will be 0,
- regardless of *value*, *scale*, and *offset*.
- The meaning of "0" is dependent on the hardware. For example, a
- bipolar 12-bit A/D may need to write 0x1FF (mid scale) to the D/A get 0
- volts from the hardware pin. If enable is true, read scale, offset and
- value and output to the adc (*scale* * *value*) + *offset*. If enable
- is false, then output 0.
+ This causes the calculated value to be output to the hardware.
+ If enable is false, then the output will be 0, regardless of *value*, *scale*, and *offset*.
+ The meaning of "0" is dependent on the hardware.
+ For example, a bipolar 12-bit A/D may need to write 0x1FF (mid scale) to the D/A get 0 volts from the hardware pin.
+ If enable is true, read scale, offset and value and output to the adc (*scale* * *value*) + *offset*.
+ If enable is false, then output 0.
// vim: set syntax=asciidoc:
diff --git a/docs/src/hal/comp.adoc b/docs/src/hal/comp.adoc
index 63add4bf94..82ba831a16 100644
--- a/docs/src/hal/comp.adoc
+++ b/docs/src/hal/comp.adoc
@@ -74,47 +74,37 @@ To test your component you can follow the examples in the
== Definitions
-* 'component' - A component is a single real-time module, which is loaded with
- 'halcmd loadrt'. One '.comp' file specifies one component. The component
- name and file name must match.
-
-* 'instance' - A component can have zero or more instances. Each instance of a
- component is created equal (they all have the same pins, parameters,
- functions, and data) but behave independently when their pins,
- parameters, and data have different values.
-
-* 'singleton' - It is possible for a component to be a "singleton", in which case
- exactly one instance is created. It seldom makes sense to write a
- 'singleton' component, unless there can literally only be a single
- object of that
- kind in the system (for instance, a component whose purpose is to
- provide a pin with the current UNIX time, or a hardware driver for the
- internal PC speaker)
+* 'component' - A component is a single real-time module, which is loaded with 'halcmd loadrt'.
+ One '.comp' file specifies one component. The component name and file name must match.
+
+* 'instance' - A component can have zero or more instances.
+ Each instance of a component is created equal (they all have the same pins, parameters,
+ functions, and data) but behave independently when their pins, parameters, and data have different values.
+
+* 'singleton' - It is possible for a component to be a "singleton", in which case exactly one instance is created.
+ It seldom makes sense to write a 'singleton' component,
+ unless there can literally only be a single object of that kind in the system
+ (for instance, a component whose purpose is to provide a pin with the current UNIX time,
+ or a hardware driver for the internal PC speaker)
== Instance creation
-For a singleton, the one instance is created when the component is
-loaded.
+For a singleton, the one instance is created when the component is loaded.
-For a non-singleton, the 'count' module parameter determines how
-many numbered instances are created. If 'count' is not specified, the
-'names' module parameter determines how many named instances are created.
-If neither 'count' nor 'names' is specified, a single numbered instance
-is created.
+For a non-singleton, the 'count' module parameter determines how many numbered instances are created.
+If 'count' is not specified, the 'names' module parameter determines how many named instances are created.
+If neither 'count' nor 'names' is specified, a single numbered instance is created.
== Implicit Parameters
-Functions are implicitly passed the 'period' parameter which is the time in
-nanoseconds of the last period to execute the component. Functions which use
-floating-point can also refer to 'fperiod' which is the floating-point time in
-seconds, or (period*1e-9). This can be useful in components that need the timing
-information.
+Functions are implicitly passed the 'period' parameter which is the time in nanoseconds of the last period to execute the component.
+Functions which use floating-point can also refer to 'fperiod' which is the floating-point time in seconds, or (period*1e-9).
+This can be useful in components that need the timing information.
== Syntax
-A '.comp' file consists of a number of declarations, followed by ';;'
-on a line of its own, followed by C code implementing the module's
-functions.
+A '.comp' file consists of a number of declarations, followed by ';;' on a line of its own,
+followed by C code implementing the module's functions.
Declarations include:
@@ -132,40 +122,30 @@ Declarations include:
* 'author AUTHOR;'
* 'include HEADERFILE;'
-Parentheses indicate optional items. A vertical bar indicates
-alternatives. Words in 'CAPITALS' indicate variable text, as follows:
+Parentheses indicate optional items. A vertical bar indicates alternatives.
+Words in 'CAPITALS' indicate variable text, as follows:
* 'NAME' - A standard C identifier
-
-* 'STARREDNAME' - A C identifier with zero or more * before it. This syntax can be used
- to declare instance variables that are pointers. Note that because of the
- grammar, there may not be whitespace between the * and the variable name.
-
+* 'STARREDNAME' - A C identifier with zero or more * before it.
+ This syntax can be used to declare instance variables that are pointers.
+ Note that because of the grammar, there may not be whitespace between the * and the variable name.
* 'HALNAME' - An extended identifier.
- When used to create a HAL identifier, any underscores are replaced
- with dashes, and any trailing dash or period is removed, so that
- "this_name_" will be turned into "this-name", and if the name is "_",
- then a trailing period is removed as well, so that "function _" gives
- a HAL function name like "component.<num>" instead of "component.<num>."
+ When used to create a HAL identifier, any underscores are replaced with dashes, and any trailing dash or period is removed,
+ so that "this_name_" will be turned into "this-name", and if the name is "_", then a trailing period is removed as well,
+ so that "function _" gives a HAL function name like "component.<num>" instead of "component.<num>."
+
-If present, the prefix 'hal_' is removed from the beginning of the
-component name when creating pins, parameters and functions.
+If present, the prefix 'hal_' is removed from the beginning of the component name when creating pins, parameters and functions.
-In the HAL identifier for a pin or parameter, # denotes an array item,
-and must be used in conjunction with a '[SIZE]' declaration. The hash
-marks are replaced with a 0-padded number with
-the same length as the number of # characters.
+In the HAL identifier for a pin or parameter, # denotes an array item, and must be used in conjunction with a '[SIZE]' declaration.
+The hash marks are replaced with a 0-padded number with the same length as the number of # characters.
-When used to create a C identifier, the following changes are applied
-to the HALNAME:
+When used to create a C identifier, the following changes are applied to the HALNAME:
-. Any "#" characters, and any ".", "_" or "-" characters immediately
- before them, are removed.
+. Any "#" characters, and any ".", "_" or "-" characters immediately before them, are removed.
. Any remaining "." and "-" characters are replaced with "_".
. Repeated "\_" characters are changed to a single "\_" character.
-A trailing "_" is retained, so that HAL identifiers which would otherwise
-collide with reserved names or keywords (e.g., 'min') can be used.
+A trailing "_" is retained, so that HAL identifiers which would otherwise collide with reserved names or keywords (e.g., 'min') can be used.
[width="90%",options="header"]
|===
@@ -177,26 +157,21 @@ collide with reserved names or keywords (e.g., 'min') can be used.
|x.## | x(MM) | x.MM
|===
-* 'if CONDITION' - An expression involving the variable 'personality' which is nonzero
- when the pin or parameter should be created
+* 'if CONDITION' - An expression involving the variable 'personality' which is nonzero when the pin or parameter should be created.
-* 'SIZE' - A number that gives the size of an array. The array items are numbered
- from 0 to 'SIZE'-1.
+* 'SIZE' - A number that gives the size of an array. The array items are numbered from 0 to 'SIZE'-1.
-* 'MAXSIZE : CONDSIZE' - A number that gives the maximum size of the array followed by an
- expression involving the variable 'personality' and which always
- evaluates to less than 'MAXSIZE'. When the array is created its size
- will be 'CONDSIZE'.
+* 'MAXSIZE : CONDSIZE' - A number that gives the maximum size of the array,
+ followed by an expression involving the variable 'personality' and which always evaluates to less than 'MAXSIZE'.
+ When the array is created its size will be 'CONDSIZE'.
-* 'DOC' - A string that documents the item. String can be a C-style "double
- quoted" string, like:
+* 'DOC' - A string that documents the item. String can be a C-style "double quoted" string, like:
+
----
"Selects the desired edge: TRUE means falling, FALSE means rising"
----
+
-or a Python-style "triple quoted" string, which
-may include embedded newlines and quote characters, such as:
+or a Python-style "triple quoted" string, which may include embedded newlines and quote characters, such as:
+
----
"""The effect of this parameter, also known as "the orb of zot",
@@ -206,79 +181,59 @@ Hopefully these paragraphs have allowed you to understand "zot"
better."""
----
+
-Or a string may be preceded by the literal character 'r', in which
-case the string is interpreted like a Python raw-string.
+Or a string may be preceded by the literal character 'r', in which case the string is interpreted like a Python raw-string.
+
-The documentation string is in "groff -man" format. For more
-information on this markup format, see 'groff_man(7)'. Remember that
-'halcompile' interprets backslash escapes in strings, so for instance
-to set the italic font for the word 'example', write:
+The documentation string is in "groff -man" format.
+For more information on this markup format, see 'groff_man(7)'.
+Remember that 'halcompile' interprets backslash escapes in strings, so for instance to set the italic font for the word 'example', write:
+
----
"\\fIexample\\fB"
----
+
-In this case, r-strings are particularly useful, because the backslashes
-in an r-string need not be doubled:
+In this case, r-strings are particularly useful, because the backslashes in an r-string need not be doubled:
+
----
r"\fIexample\fB"
----
-* 'TYPE' - One of the HAL types: 'bit', 'signed', 'unsigned', or 'float'. The old
- names 's32' and 'u32' may also be used, but 'signed' and 'unsigned' are
- preferred.
-
-* 'PINDIRECTION' - One of the following: 'in', 'out', or 'io'. A component sets a value
- for an 'out' pin, it reads a value from an 'in' pin, and it may read or
- set the value of an 'io' pin.
-
-* 'PARAMDIRECTION' - One of the following: 'r' or 'rw'. A component sets a value for a 'r'
- parameter, and it may read or set the value of a 'rw' parameter.
-
-* 'STARTVALUE' - Specifies the initial value of a pin or parameter. If it is not
- specified, then the default is '0' or 'FALSE', depending on the type of
- the item.
-
-* 'HEADERFILE' - The name of a header file, either in double-quotes
- (`include "myfile.h";`) or in angle brackets (`include
- <systemfile.h>;`). The header file will be included (using
- C's #include) at the top of the file, before pin and parameter
- declarations.
+* 'TYPE' - One of the HAL types: 'bit', 'signed', 'unsigned', or 'float'.
+ The old names 's32' and 'u32' may also be used, but 'signed' and 'unsigned' are preferred.
+* 'PINDIRECTION' - One of the following: 'in', 'out', or 'io'.
+ A component sets a value for an 'out' pin, it reads a value from an 'in' pin, and it may read or set the value of an 'io' pin.
+* 'PARAMDIRECTION' - One of the following: 'r' or 'rw'. A component sets a value for a 'r' parameter,
+ and it may read or set the value of a 'rw' parameter.
+* 'STARTVALUE' - Specifies the initial value of a pin or parameter.
+ If it is not specified, then the default is '0' or 'FALSE', depending on the type of the item.
+* 'HEADERFILE' - The name of a header file, either in double-quotes (`include "myfile.h";`) or in angle brackets (`include <systemfile.h>;`).
+ The header file will be included (using C's #include) at the top of the file, before pin and parameter declarations.
=== HAL functions
* 'fp' - Indicates that the function performs floating-point calculations.
-
-* 'nofp' - Indicates that it only performs integer calculations. If neither is
- specified, 'fp' is assumed. Neither 'halcompile' nor gcc can detect the use of
- floating-point calculations in functions that are tagged 'nofp', but use of
- such operations results in undefined behavior.
+* 'nofp' - Indicates that it only performs integer calculations.
+ If neither is specified, 'fp' is assumed.
+ Neither 'halcompile' nor gcc can detect the use of floating-point calculations in functions that are tagged 'nofp',
+ but use of such operations results in undefined behavior.
=== Options
The currently defined options are:
* 'option singleton yes' - (default: no)
- Do not create a 'count' module parameter, and always create a single
- instance. With 'singleton', items are named 'component-name.item-name'
- and without 'singleton', items for numbered instances are named
- 'component-name.<num>.item-name'.
-
+ Do not create a 'count' module parameter, and always create a single instance.
+ With 'singleton', items are named 'component-name.item-name' and without 'singleton',
+ items for numbered instances are named 'component-name.<num>.item-name'.
* 'option default_count number' - (default: 1)
- Normally, the module parameter 'count' defaults to 1. If specified,
- the 'count' will default to this value instead.
-
+ Normally, the module parameter 'count' defaults to 1. If specified, the 'count' will default to this value instead.
* 'option count_function yes' - (default: no)
- Normally, the number of instances to create is specified in the
- module parameter 'count'; if 'count_function' is specified, the value
- returned by the function 'int get_count(void)' is used instead,
+ Normally, the number of instances to create is specified in the module parameter 'count';
+ if 'count_function' is specified, the value returned by the function 'int get_count(void)' is used instead,
and the 'count' module parameter is not defined.
-
* 'option rtapi_app no' - (default: yes)
- Normally, the functions `rtapi_app_main()` and `rtapi_app_exit()` are
- automatically defined. With 'option rtapi_app no', they are not, and
- must be provided in the C code. Use the following prototypes:
+ Normally, the functions `rtapi_app_main()` and `rtapi_app_exit()` are automatically defined.
+ With 'option rtapi_app no', they are not, and must be provided in the C code.
+ Use the following prototypes:
+
----
`int rtapi_app_main(void);`
@@ -286,80 +241,66 @@ The currently defined options are:
`void rtapi_app_exit(void);`
----
+
-When implementing your own `rtapi_app_main()`, call the function `int
-export(char *prefix, long extra_arg)` to register the pins,
+When implementing your own `rtapi_app_main()`, call the function `int export(char *prefix, long extra_arg)` to register the pins,
parameters, and functions for `prefix`.
-* 'option data TYPE' - (default: none) *deprecated*
- If specified, each instance of the component will have an associated
- data block of type 'TYPE' (which can be a simple type like 'float' or the
- name of a type created with 'typedef').
+* 'option data TYPE' - (default: none) *deprecated* +
+ If specified, each instance of the component will have an associated data block of type 'TYPE'
+ (which can be a simple type like 'float' or the name of a type created with 'typedef').
In new components, 'variable' should be used instead.
-* 'option extra_setup yes' - (default: no)
- If specified, call the function defined by 'EXTRA_SETUP' for each
- instance. If using the automatically defined 'rtapi_app_main',
- 'extra_arg' is the number of this instance.
-
-* 'option extra_cleanup yes' - (default: no)
- If specified, call the function defined by 'EXTRA_CLEANUP' from the
- automatically defined 'rtapi_app_exit', or if an error is detected
- in the automatically defined 'rtapi_app_main'.
-
-* 'option userspace yes' - (default: no)
- If specified, this file describes a userspace (i.e., non-realtime) component, rather
- than a regular (i.e., realtime) one. A userspace component may not have functions
- defined by the 'function' directive. Instead, after all the
- instances are constructed, the C function `void user_mainloop(void);`
- is called. When this function returns, the component exits.
- Typically, 'user_mainloop()' will use 'FOR_ALL_INSTS()' to
- perform the update action for each instance, then sleep for
- a short time. Another common action in 'user_mainloop()' may
- be to call the event handler loop of a GUI toolkit.
-
-* 'option userinit yes' - (default: no)
- This option is ignored if the option 'userspace' (see above) is set to
- 'no'. If 'userinit' is specified, the function 'userinit(argc,argv)'
- is called before 'rtapi_app_main()' (and thus before the call to
- 'hal_init()' ). This function may process the commandline arguments or
- take other actions. Its return type is 'void'; it may call 'exit()'
- if it wishes to terminate rather than create a HAL component (for
- instance, because the commandline arguments were invalid).
-
-* 'option extra_link_args "..."' - (default: "")
- This option is ignored if the option 'userspace' (see above) is set to
- 'no'. When linking a userspace component, the arguments given are inserted
- in the link line. Note that because compilation takes place in a temporary
- directory, "-L." refers to the temporary directory and not the directory where
- the .comp source file resides.
-
-* 'option extra_compile_args "..."' - (default: "")
- This option is ignored if the option 'userspace' (see above) is set to
- 'no'. When compiling a userspace component, the arguments given are inserted
- in the compiler command line.
-
-* 'option homemod yes' - (default: no)
+* 'option extra_setup yes' - (default: no) +
+ If specified, call the function defined by 'EXTRA_SETUP' for each instance.
+ If using the automatically defined 'rtapi_app_main', 'extra_arg' is the number of this instance.
+
+* 'option extra_cleanup yes' - (default: no) +
+ If specified, call the function defined by 'EXTRA_CLEANUP' from the automatically defined 'rtapi_app_exit',
+ or if an error is detected in the automatically defined 'rtapi_app_main'.
+
+* 'option userspace yes' - (default: no) +
+ If specified, this file describes a userspace (i.e., non-realtime) component, rather than a regular (i.e., realtime) one.
+ A userspace component may not have functions defined by the 'function' directive.
+ Instead, after all the instances are constructed, the C function `void user_mainloop(void);` is called.
+ When this function returns, the component exits.
+ Typically, 'user_mainloop()' will use 'FOR_ALL_INSTS()' to perform the update action for each instance, then sleep for a short time.
+ Another common action in 'user_mainloop()' may be to call the event handler loop of a GUI toolkit.
+
+* 'option userinit yes' - (default: no) +
+ This option is ignored if the option 'userspace' (see above) is set to 'no'.
+ If 'userinit' is specified, the function 'userinit(argc,argv)' is called before 'rtapi_app_main()' (and thus before the call to 'hal_init()' ).
+ This function may process the commandline arguments or take other actions.
+ Its return type is 'void'; it may call 'exit()' if it wishes to terminate rather than create a HAL component
+ (e.g., because the commandline arguments were invalid).
+
+* 'option extra_link_args "..."' - (default: "") +
+ This option is ignored if the option 'userspace' (see above) is set to 'no'.
+ When linking a userspace component, the arguments given are inserted in the link line.
+ Note that because compilation takes place in a temporary directory,
+ "-L." refers to the temporary directory and not the directory where the .comp source file resides.
+
+* 'option extra_compile_args "..."' - (default: "") +
+ This option is ignored if the option 'userspace' (see above) is set to 'no'.
+ When compiling a userspace component, the arguments given are inserted in the compiler command line.
+
+* 'option homemod yes' - (default: no) +
Module is a custom Homing module loaded using [EMCMOT]HOMEMOD=modulename
-* 'option tpmod yes' - (default: no)
+* 'option tpmod yes' - (default: no) +
Module is a custom Trajectory Planning (tp) module loaded using [TRAJ]TPMOD=modulename
-If an option's VALUE is not specified, then it is equivalent to
-specifying 'option … yes'. +
+If an option's VALUE is not specified, then it is equivalent to specifying 'option … yes'. +
The result of assigning an inappropriate value to an option is undefined. +
The result of using any other option is undefined. +
=== License and Authorship
-* 'LICENSE' - Specify the license of the module for the documentation and for the
- MODULE_LICENSE() module declaration. For example, to specify that the
- module's license is GPL v2 or later:
+* 'LICENSE' - Specify the license of the module for the documentation and for the MODULE_LICENSE() module declaration.
+ For example, to specify that the module's license is GPL v2 or later:
+
license "GPL"; // indicates GPL v2 or later
+
-For additional information on the meaning of MODULE_LICENSE() and
-additional license identifiers, see '<linux/module.h>' or the manual page
-'rtapi_module_param(3)'.
+For additional information on the meaning of MODULE_LICENSE() and additional license identifiers,
+see '<linux/module.h>' or the manual page 'rtapi_module_param(3)'.
+
This declaration is *required*.
@@ -373,15 +314,12 @@ This declaration is *required*.
variable CTYPE STARREDNAME[SIZE] = DEFAULT;`
+
Declare a per-instance variable 'STARREDNAME' of type 'CTYPE',
-optionally as an array of 'SIZE' items, and optionally with a default
-value 'DEFAULT'. +
-Items with no 'DEFAULT' are initialized to all-bits-zero. +
-'CTYPE' is a simple one-word C type, such as 'float', 'u32', 's32',
-int, etc. +
+optionally as an array of 'SIZE' items, and optionally with a default value 'DEFAULT'.
+Items with no 'DEFAULT' are initialized to all-bits-zero.
+'CTYPE' is a simple one-word C type, such as 'float', 'u32', 's32', int, etc.
Access to array variables uses square brackets.
-If a variable is to be of a pointer type, there may not be any space
-between the "*" and the variable name. +
+If a variable is to be of a pointer type, there may not be any space between the "*" and the variable name.
Therefore, the following is acceptable:
----
@@ -403,11 +341,9 @@ are both supported in the declaration section.
== Restrictions
-Though HAL permits a pin, a parameter, and a function to have the same
-name, 'halcompile' does not.
+Though HAL permits a pin, a parameter, and a function to have the same name, 'halcompile' does not.
-Variable and function names that can not be used or are likely to cause
-problems include:
+Variable and function names that can not be used or are likely to cause problems include:
* Anything beginning with '__comp_'.
* 'comp_id'
@@ -419,56 +355,34 @@ problems include:
== Convenience Macros
-Based on the items in the declaration section, 'halcompile' creates a C
-structure called `struct __comp_state`. However, instead of referring to the
-members of this structure (e.g., `*(inst->name)`), they will generally
-be referred to using the macros below. The
-details of `struct __comp_state` and these macros may change from one version
-of 'halcompile' to the next.
-
-* 'FUNCTION(name)' - Use this macro to begin the definition of a realtime function which
- was previously declared with 'function NAME'. The function includes a
- parameter 'period' which is the integer number of nanoseconds
- between calls to the
- function.
-
-* 'EXTRA_SETUP()' - Use this macro to begin the definition of the function called to
- perform extra setup of this instance. Return a negative Unix 'errno'
- value to indicate failure (e.g., 'return -EBUSY' on failure to reserve
- an I/O port), or 0 to indicate success.
-
-* 'EXTRA_CLEANUP()' - Use this macro to begin the definition of the function called to
- perform extra cleanup of the component. Note that this function must
- clean up all instances of the component, not just one. The "pin_name",
- "parameter_name", and "data" macros may not be used here.
+Based on the items in the declaration section, 'halcompile' creates a C structure called `struct __comp_state`.
+However, instead of referring to the members of this structure (e.g., `*(inst->name)`),
+they will generally be referred to using the macros below.
+The details of `struct __comp_state` and these macros may change from one version of 'halcompile' to the next.
+
+* 'FUNCTION(name)' - Use this macro to begin the definition of a realtime function, which was previously declared with 'function NAME'.
+ The function includes a parameter 'period' which is the integer number of nanoseconds between calls to the function.
+* 'EXTRA_SETUP()' - Use this macro to begin the definition of the function called to perform extra setup of this instance.
+ Return a negative Unix 'errno' value to indicate failure (e.g., 'return -EBUSY' on failure to reserve an I/O port), or 0 to indicate success.
+* 'EXTRA_CLEANUP()' - Use this macro to begin the definition of the function called to perform extra cleanup of the component.
+ Note that this function must clean up all instances of the component, not just one.
+ The "pin_name", "parameter_name", and "data" macros may not be used here.
* 'pin_name' or 'parameter_name' - For each pin 'pin_name' or param 'parameter_name'
- there is a macro which allows the name to be used on its own to refer
- to the pin or parameter.
- When 'pin_name' or 'parameter_name' is an array, the macro is of the
- form 'pin_name(idx)' or 'param_name(idx)' where 'idx' is the index
- into the pin array. When the array is a variable-sized
- array, it is only legal to refer to items up to its 'condsize'.
+ there is a macro which allows the name to be used on its own to refer to the pin or parameter.
+ When 'pin_name' or 'parameter_name' is an array, the macro is of the form 'pin_name(idx)' or 'param_name(idx)',
+ where 'idx' is the index into the pin array. When the array is a variable-sized array,
+ it is only legal to refer to items up to its 'condsize'.
+
-When the item is a conditional item, it is only legal to refer to it
-when its 'condition' evaluated to a nonzero value.
-
-* 'variable_name' - For each variable 'variable_name' there is a macro which allows the
- name to be used on its own to refer
- to the variable. When 'variable_name' is an array, the normal C-style
- subscript is used: 'variable_name[idx]'.
-
-* 'data' - If "option data" is specified, this macro allows access to the
- instance data.
-
-* 'fperiod' - The floating-point number of seconds between calls to this realtime
- function.
+When the item is a conditional item, it is only legal to refer to it when its 'condition' evaluated to a nonzero value.
-* 'FOR_ALL_INSTS() {...}' - For userspace components. This macro
- iterates over all the defined instances. Inside the
- body of the
- loop, the 'pin_name', 'parameter_name', and 'data' macros work as they
- do in realtime functions.
+* 'variable_name' - For each variable 'variable_name' there is a macro which allows the name to be used on its own to refer to the variable.
+ When 'variable_name' is an array, the normal C-style subscript is used: 'variable_name[idx]'.
+* 'data' - If "option data" is specified, this macro allows access to the instance data.
+* 'fperiod' - The floating-point number of seconds between calls to this realtime function.
+* 'FOR_ALL_INSTS() {...}' - For userspace components.
+ This macro iterates over all the defined instances.
+ Inside the body of the loop, the 'pin_name', 'parameter_name', and 'data' macros work as they do in realtime functions.
== Components with one function
@@ -479,31 +393,24 @@ taken to be the body of the component's single function. See the
== Component Personality
-If a component has any pins or parameters with an "if condition" or
-"[maxsize : condsize]", it is called a component with 'personality'.
-The 'personality' of each instance is specified when the module is
-loaded. 'Personality' can be used to create pins only when needed.
-For instance, personality is used in the 'logic' component, to allow
-for a variable number of input pins to each logic gate and to allow
-for a selection of any of the basic boolean logic functions 'and',
-'or', and 'xor'.
+If a component has any pins or parameters with an "if condition" or "[maxsize : condsize]", it is called a component with 'personality'.
+The 'personality' of each instance is specified when the module is loaded. 'Personality' can be used to create pins only when needed.
+For instance, personality is used in the 'logic' component,
+to allow for a variable number of input pins to each logic gate
+and to allow for a selection of any of the basic boolean logic functions 'and', 'or', and 'xor'.
-The default number of allowed 'personality' items is a
-compile-time setting (64). The default applies to numerous
-components included in the distribution that are built using
-halcompile.
+The default number of allowed 'personality' items is a compile-time setting (64).
+The default applies to numerous components included in the distribution that are built using halcompile.
-To alter the allowed number of personality items for user-built
-components, use the '--personality' option with halcompile. For
-example, to allow up to 128 personality times:
+To alter the allowed number of personality items for user-built components, use the '--personality' option with halcompile.
+For example, to allow up to 128 personality times:
----
[sudo] halcompile --personality=128 --install ...
----
-When using components with personality, normal usage is to
-specify a personality item for *each* specified component
-instance. Example for 3 instances of the logic component:
+When using components with personality, normal usage is to specify a personality item for *each* specified component instance.
+Example for 3 instances of the logic component:
[source,{hal}]
----
@@ -511,40 +418,34 @@ loadrt logic names=and4,or3,nand5, personality=0x104,0x203,0x805
----
[NOTE]
-If a loadrt line specifies more instances than personalities, the
-instances with unspecified personalities are assigned a
-personality of 0. If the requested number of instances
-exceeds the number of allowed personalities, personalities are
-assigned by indexing modulo the number of allowed personalities.
+If a loadrt line specifies more instances than personalities,
+the instances with unspecified personalities are assigned a personality of 0.
+If the requested number of instances exceeds the number of allowed personalities,
+personalities are assigned by indexing modulo the number of allowed personalities.
A message is printed denoting such assignments.
== Compiling
-Place the '.comp' file in the source directory
-'linuxcnc/src/hal/components' and re-run 'make'.
+Place the '.comp' file in the source directory 'linuxcnc/src/hal/components' and re-run 'make'.
'Comp' files are automatically detected by the build system.
-If a '.comp' file is a driver for hardware, it may be placed in
-'linuxcnc/src/hal/drivers' and will be built unless LinuxCNC is
-configured as a userspace simulator.
+If a '.comp' file is a driver for hardware, it may be placed in 'linuxcnc/src/hal/drivers'
+and will be built unless LinuxCNC is configured as a userspace simulator.
== Compiling realtime components outside the source tree
-'halcompile' can process, compile, and install a realtime component
-in a single step, placing 'rtexample.ko' in the LinuxCNC realtime
-module directory:
+'halcompile' can process, compile, and install a realtime component in a single step,
+placing 'rtexample.ko' in the LinuxCNC realtime module directory:
----
[sudo] halcompile --install rtexample.comp
----
[NOTE]
-sudo (for root permission) is needed when using LinuxCNC from
-a deb package install. When using a Run-In-Place (RIP) build,
-root privileges should not be needed.
+sudo (for root permission) is needed when using LinuxCNC from a deb package install.
+When using a Run-In-Place (RIP) build, root privileges should not be needed.
-Or, it can process and compile in one step, leaving 'example.ko' (or
-'example.so' for the simulator) in the current directory:
+Or, it can process and compile in one step, leaving 'example.ko' (or 'example.so' for the simulator) in the current directory:
----
halcompile --compile rtexample.comp
@@ -556,15 +457,13 @@ Or it can simply process, leaving 'example.c' in the current directory:
halcompile rtexample.comp
----
-'halcompile' can also compile and install a component written in C, using
-the '--install' and '--compile' options shown above:
+'halcompile' can also compile and install a component written in C, using the '--install' and '--compile' options shown above:
----
[sudo] halcompile --install rtexample2.c
----
-man-format documentation can also be created from the information in
-the declaration section:
+man-format documentation can also be created from the information in the declaration section:
----
halcompile --document rtexample.comp
@@ -611,14 +510,12 @@ FUNCTION(_) { out = value; }
=== sincos
-This component computes the sine and cosine of an input angle in
-radians. It has different capabilities than the "sine" and "cosine"
-outputs of siggen, because the input is an angle, rather than running
-freely based on a "frequency" parameter.
+This component computes the sine and cosine of an input angle in radians.
+It has different capabilities than the "sine" and "cosine" outputs of siggen,
+because the input is an angle, rather than running freely based on a "frequency" parameter.
-The pins are declared with the names 'sin_' and 'cos_' in the source
-code so that they do not interfere with the functions 'sin()' and
-'cos()'. The HAL pins are still called 'sincos.<num>.sin'.
+The pins are declared with the names 'sin_' and 'cos_' in the source code so that they do not interfere with the functions 'sin()' and 'cos()'.
+The HAL pins are still called 'sincos.<num>.sin'.
[source,c]
----
@@ -635,14 +532,10 @@ FUNCTION(_) { sin_ = sin(theta); cos_ = cos(theta); }
=== out8
-This component is a driver for a 'fictional' card called "out8",
-which has 8 pins of digital output which are
-treated as a single 8-bit value. There can be a varying number of such
-cards in the system, and they can be at various addresses. The pin is
-called 'out_' because 'out' is an identifier used in '<asm/io.h>'. It
-illustrates the use of 'EXTRA_SETUP' and 'EXTRA_CLEANUP' to request an
-I/O region and then free it in case of error or when
-the module is unloaded.
+This component is a driver for a 'fictional' card called "out8", which has 8 pins of digital output which are treated as a single 8-bit value.
+There can be a varying number of such cards in the system, and they can be at various addresses.
+The pin is called 'out_' because 'out' is an identifier used in '<asm/io.h>'.
+It illustrates the use of 'EXTRA_SETUP' and 'EXTRA_CLEANUP' to request an I/O region and then free it in case of error or when the module is unloaded.
[source,c]
----
@@ -700,14 +593,12 @@ component hal_loop;
pin out float example;
----
-This fragment of a component illustrates the use of the 'hal_' prefix
-in a component name. 'loop' is the name of a standard Linux kernel
-module, so a 'loop' component might not successfully load if the Linux
-'loop' module was also present on the system.
+This fragment of a component illustrates the use of the 'hal_' prefix in a component name.
+'loop' is the name of a standard Linux kernel module,
+so a 'loop' component might not successfully load if the Linux 'loop' module was also present on the system.
-When loaded, 'halcmd show comp' will show a component called
-'hal_loop'. However, the pin shown by 'halcmd show pin' will be
-'loop.0.example', not 'hal-loop.0.example'.
+When loaded, 'halcmd show comp' will show a component called 'hal_loop'.
+However, the pin shown by 'halcmd show pin' will be 'loop.0.example', not 'hal-loop.0.example'.
=== arraydemo
@@ -728,8 +619,7 @@ out(0) = in;
=== rand
-This userspace component changes the value on its output pin to a new
-random value in the range (0,1) about once every 1ms.
+This userspace component changes the value on its output pin to a new random value in the range (0,1) about once every 1&#8239;ms.
[source,c]
----
@@ -751,8 +641,7 @@ void user_mainloop(void) {
=== logic
-This realtime component shows how to use "personality" to create
-variable-size arrays and optional pins.
+This realtime component shows how to use "personality" to create variable-size arrays and optional pins.
[source,c]
----
@@ -798,10 +687,8 @@ loadrt logic count=3 personality=0x102,0x305,0x503
which creates the following pins:
- A 2-input AND gate: logic.0.and, logic.0.in-00, logic.0.in-01
-- 5-input AND and OR gates: logic.1.and, logic.1.or, logic.1.in-00,
- logic.1.in-01, logic.1.in-02, logic.1.in-03, logic.1.in-04,
-- 3-input AND and XOR gates: logic.2.and, logic.2.xor, logic.2.in-00,
- logic.2.in-01, logic.2.in-02
+- 5-input AND and OR gates: logic.1.and, logic.1.or, logic.1.in-00, logic.1.in-01, logic.1.in-02, logic.1.in-03, logic.1.in-04,
+- 3-input AND and XOR gates: logic.2.and, logic.2.xor, logic.2.in-00, logic.2.in-01, logic.2.in-02
=== General Functions
diff --git a/docs/src/hal/components.adoc b/docs/src/hal/components.adoc
index 1bc72a8eca..90f7c6cbb4 100644
--- a/docs/src/hal/components.adoc
+++ b/docs/src/hal/components.adoc
@@ -27,16 +27,16 @@ link:../man/[directory listing].
==== Machine Control
[{tab_options}]
|===
-| link:../man/man1/axis.1.html[axis] |AXIS LinuxCNC (The Enhanced Machine Controller) GUI ||
-| link:../man/man1/axis-remote.1.html[axis-remote] |AXIS Remote Interface ||
-| link:../man/man1/gmoccapy.1.html[gmoccapy] |Touchy LinuxCNC Graphical User Interface ||
-| link:../man/man1/gscreen.1.html[gscreen] |Touchy LinuxCNC Graphical User Interface ||
-| link:../man/man1/halui.1.html[halui] |Observe HAL pins and command LinuxCNC through NML ||
-| link:../man/man1/mdro.1.html[mdro] |manual only Digital Read Out (DRO) ||
-| link:../man/man1/ngcgui.1.html[ngcgui] |Framework for conversational G-code generation on the controller ||
-| link:../man/man1/panelui.1.html[panelui] |Short description ||
-| link:../man/man1/pyngcgui.1.html[pyngcgui] |Python implementation of NGCGUI ||
-| link:../man/man1/touchy.1.html[touchy] |AXIS - TOUCHY LinuxCNC Graphical User Interface ||
+| link:../man/man1/axis.1.html[axis] |AXIS LinuxCNC (The Enhanced Machine Controller) GUI ||
+| link:../man/man1/axis-remote.1.html[axis-remote] |AXIS Remote Interface ||
+| link:../man/man1/gmoccapy.1.html[gmoccapy] |Touchy LinuxCNC Graphical User Interface ||
+| link:../man/man1/gscreen.1.html[gscreen] |Touchy LinuxCNC Graphical User Interface ||
+| link:../man/man1/halui.1.html[halui] |Observe HAL pins and command LinuxCNC through NML ||
+| link:../man/man1/mdro.1.html[mdro] |manual only Digital Read Out (DRO) ||
+| link:../man/man1/ngcgui.1.html[ngcgui] |Framework for conversational G-code generation on the controller ||
+| link:../man/man1/panelui.1.html[panelui] |Short description ||
+| link:../man/man1/pyngcgui.1.html[pyngcgui] |Python implementation of NGCGUI ||
+| link:../man/man1/touchy.1.html[touchy] |AXIS - TOUCHY LinuxCNC Graphical User Interface ||
|===
==== Virtual Control Panels (VCP)
@@ -55,29 +55,29 @@ link:../man/[directory listing].
==== Vismach Virtual Machines
[{tab_options}]
|===
-| link:../man/man1/5axisgui.1.html[5axisgui] |Vismach Virtual Machine GUI ||
-| link:../man/man1/hbmgui.1.html[hbmgui] |Vismach Virtual Machine GUI ||
-| link:../man/man1/hexagui.1.html[hexagui] |Vismach Virtual Machine GUI ||
-| link:../man/man1/lineardelta.1.html[lineardelta] |Vismach Virtual Machine GUI ||
-| link:../man/man1/maho600gui.1.html[maho600gui] |hexagui - Vismach Virtual Machine GUI ||
-| link:../man/man1/max5gui.1.html[max5gui] |hexagui - Vismach Virtual Machine GUI ||
-| link:../man/man1/puma560gui.1.html[puma560gui] |puma560agui - Vismach Virtual Machine GUI ||
-| link:../man/man1/pumagui.1.html[pumagui] |Vismach Virtual Machine GUI ||
-| link:../man/man1/rotarydelta.1.html[rotarydelta] |Vismach Virtual Machine GUI ||
-| link:../man/man1/scaragui.1.html[scaragui] |Vismach Virtual Machine GUI ||
-| link:../man/man1/xyzac-trt-gui.1.html[xyzac-trt-gui] |Vismach Virtual Machine GUI ||
-| link:../man/man1/xyzbc-trt-gui.1.html[xyzbc-trt-gui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/5axisgui.1.html[5axisgui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/hbmgui.1.html[hbmgui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/hexagui.1.html[hexagui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/lineardelta.1.html[lineardelta] |Vismach Virtual Machine GUI ||
+| link:../man/man1/maho600gui.1.html[maho600gui] |hexagui - Vismach Virtual Machine GUI ||
+| link:../man/man1/max5gui.1.html[max5gui] |hexagui - Vismach Virtual Machine GUI ||
+| link:../man/man1/puma560gui.1.html[puma560gui] |puma560agui - Vismach Virtual Machine GUI ||
+| link:../man/man1/pumagui.1.html[pumagui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/rotarydelta.1.html[rotarydelta] |Vismach Virtual Machine GUI ||
+| link:../man/man1/scaragui.1.html[scaragui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/xyzac-trt-gui.1.html[xyzac-trt-gui] |Vismach Virtual Machine GUI ||
+| link:../man/man1/xyzbc-trt-gui.1.html[xyzbc-trt-gui] |Vismach Virtual Machine GUI ||
|===
=== Motion (Userspace)
[{tab_options}]
|===
-| link:../man/man1/io.1.html[io] |iocontrol - interacts with HAL or G-code in userspace ||
-| link:../man/man1/iocontrol.1.html[iocontrol] |Interacts with HAL or G-code in userspace ||
-| link:../man/man1/iov2.1.html[iov2] |Interacts with HAL or G-code in userspace ||
-| link:../man/man1/mdi.1.html[mdi] |Send G-code commands from the terminal to the running LinuxCNC instance ||
-| link:../man/man1/milltask.1.html[milltask] |Userspace task controller for LinuxCNC ||
-| link:../man/man9/motion.9.html[motion] |Accepts NML motion commands, interacts with HAL in realtime ||
+| link:../man/man1/io.1.html[io] |iocontrol - interacts with HAL or G-code in userspace ||
+| link:../man/man1/iocontrol.1.html[iocontrol] |Interacts with HAL or G-code in userspace ||
+| link:../man/man1/iov2.1.html[iov2] |Interacts with HAL or G-code in userspace ||
+| link:../man/man1/mdi.1.html[mdi] |Send G-code commands from the terminal to the running LinuxCNC instance ||
+| link:../man/man1/milltask.1.html[milltask] |Userspace task controller for LinuxCNC ||
+| link:../man/man9/motion.9.html[motion] |Accepts NML motion commands, interacts with HAL in realtime ||
|===
=== Hardware Drivers
@@ -110,15 +110,15 @@ link:../man/[directory listing].
|===
| hal_ppmc | Pico Systems <<cha:pico-drivers,driver>> for analog servo, PWM and Stepper controller ||
| link:../man/man9/hal_bb_gpio.9.html[hal_bb_gpio] |Driver for beaglebone GPIO pins ||
-| link:../man/man9/hm2_7i43.9.html[hm2_7i43] |Mesa Electronics driver for the 7i43 EPP Anything IO board with HostMot2. (See the man page for more information) ||
-| link:../man/man9/hm2_7i90.9.html[hm2_7i90] |LinuxCNC HAL driver for the Mesa Electronics 7i90 EPP Anything IO board with HostMot2 firmware ||
+| link:../man/man9/hm2_7i43.9.html[hm2_7i43] |Mesa Electronics driver for the 7I43 EPP Anything IO board with HostMot2. (See the man page for more information) ||
+| link:../man/man9/hm2_7i90.9.html[hm2_7i90] |LinuxCNC HAL driver for the Mesa Electronics 7I90 EPP Anything IO board with HostMot2 firmware ||
| link:../man/man9/hm2_eth.9.html[hm2_eth] |LinuxCNC HAL driver for the Mesa Electronics Ethernet Anything IO boards, with HostMot2 firmware ||
-| link:../man/man9/hm2_pci.9.html[hm2_pci] | Mesa Electronics driver for the 5i20, 5i22, 5i23, 4i65, and 4i68 Anything I/O boards, with HostMot2 firmware. (See the man page for more information) ||
+| link:../man/man9/hm2_pci.9.html[hm2_pci] | Mesa Electronics driver for the 5I20, 5I22, 5I23, 4I65, and 4I68 Anything I/O boards, with HostMot2 firmware. (See the man page for more information) ||
| link:../man/man9/hm2_rpspi.9.html[hm2_rpspi] |LinuxCNC HAL driver for the Mesa Electronics SPI Anything IO boards, with HostMot2 firmware ||
| link:../man/man9/hm2_spi.9.html[hm2_spi] |LinuxCNC HAL driver for the Mesa Electronics SPI Anything IO boards, with HostMot2 firmware ||
| link:../man/man9/hostmot2.9.html[hostmot2] |Mesa Electronics <<cha:mesa-hostmot2-driver,driver>> for the HostMot2 firmware. ||
| link:../man/man9/max31855.9.html[max31855] |Support for the MAX31855 Thermocouple-to-Digital converter using bitbanged SPI ||
-| link:../man/man9/mesa_7i65.9.html[mesa_7i65] |Mesa Electronics driver for the 7i65 eight-axis servo card. (See the man page for more information) ||
+| link:../man/man9/mesa_7i65.9.html[mesa_7i65] |Mesa Electronics driver for the 7I65 eight-axis servo card. (See the man page for more information) ||
| link:../man/man9/mesa_pktgyro_test.9.html[mesa_pktgyro_test] |PktUART simple test with Microstrain 3DM-GX3-15 gyro ||
| link:../man/man9/opto_ac5.9.html[opto_ac5] |Realtime driver for opto22 PCI-AC5 cards ||
| pluto_servo |Pluto-P <<cha:pluto-p-driver,driver>> and firmware for the parallel port FPGA, for servos ||
@@ -163,7 +163,7 @@ Smart-serial remote parameters can now be set in the HAL file in the normal way.
| link:../man/man9/and2.9.html[and2] |Two-input AND gate. For out to be true both inputs must be true. (link:../man/man9/and2.9.html[and2]) ||
| link:../man/man9/bitwise.9.html[bitwise] |Computes various bitwise operations on the two input values ||
| link:../man/man9/dbounce.9.html[dbounce] |Filter noisy digital inputs link:../man/man9/dbounce.9.html[Details] ||
-| link:../man/man9/debounce.9.html[debounce] |Filter noisy digital inputs link:../man/man9/debounce.9.html[Details] <<sec:debounce, Description>> ||
+| link:../man/man9/debounce.9.html[debounce] |Filter noisy digital inputs link:../man/man9/debounce.9.html[Details] <<sec:debounce,Description>> ||
| link:../man/man9/demux.9.html[demux] |Select one of several output pins by integer and/or or individual bits ||
| link:../man/man9/edge.9.html[edge] |Edge detector ||
| link:../man/man9/estop_latch.9.html[estop_latch] |E-stop latch ||
@@ -197,7 +197,7 @@ Smart-serial remote parameters can now be set in the HAL file in the normal way.
| link:../man/man9/blend.9.html[blend] |Perform linear interpolation between two values ||
| link:../man/man9/comp.9.html[comp] |Two input comparator with hysteresis ||
| link:../man/man9/constant.9.html[constant] |Uses parameter to set the value of a pin ||
-| link:../man/man9/counter.9.html[counter] |Counts input pulses (deprecated). Use the <<sec:encoder, encoder>> component. | |
+| link:../man/man9/counter.9.html[counter] |Counts input pulses (deprecated). Use the <<sec:encoder,encoder>> component. | |
| link:../man/man9/ddt.9.html[ddt] |Computes the derivative of the input function. ||
| link:../man/man9/deadzone.9.html[deadzone] |Returns the center if within the threshold. ||
| link:../man/man9/hypot.9.html[hypot] |Three-input hypotenuse (Euclidean distance) calculator. ||
@@ -298,9 +298,9 @@ the input is a position, this means that the 'position', 'velocity', and 'accele
| link:../man/man9/classicladder.9.html[classicladder] | Realtime software PLC based on ladder logic. See <<cha:classicladder,ClassicLadder>> chapter for more information. ||
| link:../man/man9/threads.9.html[threads] | Creates hard realtime HAL threads. ||
| link:../man/man9/charge_pump.9.html[charge_pump] | Creates a square-wave for the 'charge pump' input of some controller boards.
-The 'Charge Pump' should be added to the base thread function. When enabled the output is on for one period and off for one period.
-To calculate the frequency of the output 1/(period time in seconds x 2) = Hz. For example if you have a base period of 100,000 ns that
-is 0.0001 seconds and the formula would be 1/(0.0001 x 2) = 5,000 Hz or 5 kHz. ||
+The 'Charge Pump' should be added to the base thread function. When enabled the output is on for one period and off for one period.
+To calculate the frequency of the output 1/(period time in seconds x 2) = Hz.
+For example, if you have a base period of 100,000 ns that is 0.0001 seconds and the formula would be 1/(0.0001 x 2) = 5,000 Hz or 5 kHz. ||
| link:../man/man9/encoder_ratio.9.html[encoder_ratio] | Electronic gear to synchronize two axes. ||
| link:../man/man9/feedcomp.9.html[feedcomp] | Multiply the input by the ratio of current velocity to the feed rate. ||
| link:../man/man9/gladevcp.9.html[gladevcp (Realtime)] |displays Virtual control Panels built with GTK / GLADE||
diff --git a/docs/src/hal/tools.adoc b/docs/src/hal/tools.adoc
index 17ecc35e61..13324056a3 100644
--- a/docs/src/hal/tools.adoc
+++ b/docs/src/hal/tools.adoc
@@ -371,9 +371,8 @@ Questionable functions are tagged with a question mark "?".
Component pins that cannot be associated with a known thread
function report the function as "Unknown".
-`halreport` generates a connections report (without pin types,
-and current values) for a running HAL application to aid in
-designing and verifying connections.
+`halreport` generates a connections report (without pin types, and current values)
+for a running HAL application to aid in designing and verifying connections.
This helps with the understanding what the source of a pin value is.
Use this information with applications like `halshow`, `halmeter`,
`halscope` or the `halcmd show` command in a terminal.
diff --git a/docs/src/integrator/steppers.adoc b/docs/src/integrator/steppers.adoc
index 112f9c2df1..5bf0c7b195 100644
--- a/docs/src/integrator/steppers.adoc
+++ b/docs/src/integrator/steppers.adoc
@@ -7,180 +7,171 @@
== Stepper Motor Operation
Stepper motors operate by sequentially energising and de-energising several coils surrounding the rotor in such a
-way that the shaft is magnetically forced to rotate around in discrete steps. Steps of 0.9 - 1.8 degrees are quite
-common, giving 400 - 200 steps per full revolution of the shaft.
+way that the shaft is magnetically forced to rotate around in discrete steps.
+Steps of 0.9 - 1.8 degrees are quite common, giving 400 - 200 steps per full revolution of the shaft.
-As in real life, nothing can change from one state to another with absolutely no time delay. In the case of the
-stepper motor, the current passing through each coil, and thus the magnetic field that pulls the rotor around to
-each step of rotation takes some time to take effect. This is due to the coil having inductance (expressed in
-Henries, abbreviated to the letter H) which has a natural tendency to resist the flow of a rapidly changing
-current. More coil inductance results in a slower rate of current change and thus a slower rate of magnetic field
-expansion and contraction.
+As in real life, nothing can change from one state to another with absolutely no time delay.
+In the case of the stepper motor, the current passing through each coil,
+and thus the magnetic field that pulls the rotor around to each step of rotation takes some time to take effect.
+This is due to the coil having inductance (expressed in Henries, abbreviated to the letter H)
+which has a natural tendency to resist the flow of a rapidly changing current.
+More coil inductance results in a slower rate of current change and thus a slower rate of magnetic field expansion and contraction.
The maximum torque that the stepper motor can achieve is when the motor is stationary with one winding energised.
-This figure may be quoted on a stepper motor datasheet as the 'holding torque'. As the rate at which each coil is
-energised and de-energised increases to induce rotation in the shaft, the time that each coil can exert its full
-magnetic attraction on the rotor reduces, thereby reducing the overall torque. This relationship between speed and
-torque is largely inversely proportional.
+This figure may be quoted on a stepper motor datasheet as the 'holding torque'.
+As the rate at which each coil is energised and de-energised increases to induce rotation in the shaft,
+the time that each coil can exert its full magnetic attraction on the rotor reduces, thereby reducing the overall torque.
+This relationship between speed and torque is largely inversely proportional.
-In the below example, the charging time for three coils is shown when the applied voltage is stepped from 0V to
-40V. While all three coils can easily reach the full current limit of 5 amps, the time taken varies for each
-coil. The 4 milli-Henry coil (blue trace) takes twice as long to reach full current than the 2mH coil (green
-trace), and the 8mH (red trace) coil takes twice as long again:
+In the below example, the charging time for three coils is shown when the applied voltage is stepped from 0&#8239;V to 40&#8239;V.
+While all three coils can easily reach the full current limit of 5 amps (A), the time taken varies for each coil.
+The 4 milli-Henry (mH) coil (blue trace) takes twice as long to reach full current than the 2&#8239;mH coil (green trace),
+and the 8&#8239;mH (red trace) coil takes twice as long again:
image::images/inductance-step-response.png[align="center"]
If the rate at which step changes are applied to the coils is significantly shorter than the rise time, it's easy
to see that the winding has less time to attain full magnetic attraction on the rotor, and thus maximum torque is
-curtailed. In the below example the 2mH coil can achieve the full 5A limit before the step voltage is removed, but
-the 4mH and 8mH coils cannot:
+curtailed. In the below example the 2&#8239;mH coil can achieve the full 5&#8239;A limit before the step voltage is removed, but
+the 4&#8239;mH and 8&#8239;mH coils cannot:
image::images/inductance-pulse-response-slow-charge.png[align="center"]
-The accepted way of improving motor speed while maintaining torque is to increase the speed at which the magnetic
-field of the motor coils can expand and collapse. The easiest way to accomplish this is to increase the supply
-voltage to force the current in each winding to rise and fall much more rapidly. A quicker magnetising time
-equates to faster step rates while improving torque at higher speeds, both of which are obviously desirable in a
-CNC system.
+The accepted way of improving motor speed while maintaining torque is to increase the speed at which the magnetic field of the motor coils can expand and collapse.
+The easiest way to accomplish this is to increase the supply voltage to force the current in each winding to rise and fall much more rapidly.
+A quicker magnetising time equates to faster step rates while improving torque at higher speeds, both of which are obviously desirable in a CNC system.
-Using the same example as above, but increasing the step voltage to 80V it can be seen that all three coils can
-now reach the 5A maximum quite easily:
+Using the same example as above,
+but increasing the step voltage to 80&#8239;V it can be seen that all three coils can now reach the 5&#8239;A maximum quite easily:
image::images/inductance-pulse-response-fast-charge.png[align="center"]
However, careful management of a higher drive voltage is required, as a higher voltage will increase current
-flowing in each coil with a corresponding increase in temperature of the winding. Excessive temperature rise in
-the winding will lead to eventual overheating and failure of the motor.
-
-In most stepper-based CNC systems the voltage of the supply feeding the stepper driver is several orders of
-magnitude greater than the voltage of the motor itself. A typical NEMA23 stepper motor may have a rating of only a
-handful of volts, yet the power supply and driver could be operating at 48 VDC or more.
-
-Nearly all modern stepper motor drivers on the market today are constant-current types. That is, the current being
-applied to each winding is fixed irrespective of how much voltage is being applied. Most drivers accomplish this
-by monitoring the current being drawn through the motor windings and rapidly switching the outputs on and off at a
-very high frequency to maintain this current. Depending on the drivers being used, it may even be possible to hear
-this high frequency whistling in the motors themselves when stationary. Because the voltage is rapidly switched on
-and off to maintain the winding current at an approximate fixed value, these types of drivers are also known as
-'chopper drive'.
+flowing in each coil with a corresponding increase in temperature of the winding.
+Excessive temperature rise in the winding will lead to eventual overheating and failure of the motor.
+
+In most stepper-based CNC systems the voltage of the supply feeding the stepper driver is several orders of magnitude greater
+than the voltage of the motor itself.
+A typical NEMA23 stepper motor may have a rating of only a handful of volts,
+yet the power supply and driver could be operating at 48&#8239;VDC or more.
+
+Nearly all modern stepper motor drivers on the market today are constant-current types.
+That is, the current being applied to each winding is fixed irrespective of how much voltage is being applied.
+Most drivers accomplish this by monitoring the current being drawn through the motor windings
+and rapidly switching the outputs on and off at a very high frequency to maintain this current.
+Depending on the drivers being used, it may even be possible to hear this high frequency whistling in the motors themselves when stationary.
+Because the voltage is rapidly switched on and off to maintain the winding current at an approximate fixed value,
+these types of drivers are also known as 'chopper drive'.
== Selecting a Stepper Power Supply
-While a higher voltage is directly related to more speed and torque, obviously there comes a limit where
-increasing supply voltage is no longer beneficial. The first limitation to the maximum power supply voltage is
-likely to be what the stepper driver itself is capable of withstanding. This value should be provided in the
-datasheet for the stepper driver, and exceeding this voltage will result in the destruction of the driver. Ideally
-the power supply voltage should be chosen with a degree of headroom that falls under this maximum voltage limit of
-around 10%. If, for example a stepper driver has a V~max~ rating of 80 VDC, the maximum power supply voltage should
-be limited to 72 VDC.
-
-As mentioned above, excessive motor supply voltage also leads to excessive heat rise in the motor windings which
-can lead to eventual failure of the motor through overheating. A commonly used equation for providing a guideline
-in determining the maximum voltage to prevent excessive heat rise is to take the square-root of the winding
-inductance quoted in the motor datasheet (expressed in mill-Henries) and multiply by 32. For example, choosing a
-stepper with a coil inductance of 4mH will result in a maximum power supply voltage of 32 x SQRT (4) = 64 VDC.
-
-Many stepper motor datasheets will also provide speed/torque curves, often plotted using different supply
-voltages. By studying the graphs it may be determined that increasing the supply voltage by a factor of two will
-not result in a corresponding improvement in speed/torque by the same degree. If there is little to be gained in
-running a stepper motor at 64 VDC, this may help in narrowing down the proposed power supply to 32 VDC which will
-also help minimise excessive heat rise in the motor windings.
-
-The other factor to consider is the current rating of the power supply. This is based from the motor's winding
-current ratings and whether the motor windings are wired in series or parallel, both of which should be listed in
-the motor's datasheet. A good rule of thumb is to size the power supply current rating at 2/3 of the rated phase
-current of the stepper motor if the windings are in parallel, or 1/3 of the rated current if wired in series.
+While a higher voltage is directly related to more speed and torque,
+obviously there comes a limit where increasing supply voltage is no longer beneficial.
+The first limitation to the maximum power supply voltage is likely to be what the stepper driver itself is capable of withstanding.
+This value should be provided in the datasheet for the stepper driver, and exceeding this voltage will result in the destruction of the driver.
+Ideally the power supply voltage should be chosen with a degree of headroom that falls under this maximum voltage limit of around 10%.
+If, for example a stepper driver has a V~max~ rating of 80&#8239;VDC, the maximum power supply voltage should be limited to 72&#8239;VDC.
+
+As mentioned above, excessive motor supply voltage also leads to excessive heat rise in the motor windings,
+which can lead to eventual failure of the motor through overheating.
+A commonly used equation for providing a guideline in determining the maximum voltage to prevent excessive heat rise
+is to take the square-root of the winding inductance quoted in the motor datasheet (expressed in mill-Henries) and multiply by 32.
+For example, choosing a stepper with a coil inductance of 4&#8239;mH will result in a maximum power supply voltage of 32 x SQRT (4) = 64&#8239;VDC.
+
+Many stepper motor datasheets will also provide speed/torque curves, often plotted using different supply voltages.
+By studying the graphs it may be determined that increasing the supply voltage by a factor of two
+will not result in a corresponding improvement in speed/torque by the same degree.
+If there is little to be gained in running a stepper motor at 64&#8239;VDC,
+this may help in narrowing down the proposed power supply to 32 VDC which will also help minimise excessive heat rise in the motor windings.
+
+The other factor to consider is the current rating of the power supply.
+This is based from the motor's winding current ratings and whether the motor windings are wired in series or parallel,
+both of which should be listed in the motor's datasheet.
+A good rule of thumb is to size the power supply current rating at 2/3 of the rated phase current of the stepper motor if the windings are in parallel,
+or 1/3 of the rated current if wired in series.
Thus, for a stepper motor rated at 4 A wired in parallel, the power supply needs to have a current rating of at
-least 2.7 A, or 1.3 A if wired in series.
+least 2.7&#8239;A, or 1.3&#8239;A if wired in series.
The total current rating of the complete system is then the sum of all stepper motors' current requirements.
== Resonance
-Motor resonance occurs when the rate at which the steps are applied to the windings matches the natural frequency
-of the motor itself. Applying steps for a prolonged period of time at this rate results in the torque dropping
-dramatically, and the motor may stall or even rotate in random directions. Some stepper motor datasheets provide
-plots of the torque/speed relationship and show a dip in the graph where resonance is likely to occur. It should
-be noted that this resonant peak provided in the datasheet is only for the motor itself - as soon as the motor is
-coupled to other components (ie, installed in a CNC system) the resonant frequency may be altered, or even
-multiple new resonances introduced.
+Motor resonance occurs when the rate at which the steps are applied to the windings matches the natural frequency of the motor itself.
+Applying steps for a prolonged period of time at this rate results in the torque dropping dramatically,
+and the motor may stall or even rotate in random directions.
+Some stepper motor datasheets provide plots of the torque/speed relationship and show a dip in the graph where resonance is likely to occur.
+It should be noted that this resonant peak provided in the datasheet is only for the motor itself - as soon as the motor is coupled to other components (i.e., installed in a CNC system) the resonant frequency may be altered, or even multiple new resonances introduced.
-Several methods exist to help control the effects of resonance, all with varying degrees of complexity,
-effectiveness and side effects:
+Several methods exist to help control the effects of resonance, all with varying degrees of complexity, effectiveness and side effects:
* Microstepping can help reduce resonance by using smaller step changes in current between each step.
These smaller step changes cause less ringing in the motor and windings and thus cause less excitation at the point of resonance.
-* Ensuring the motor is never operated at a particular frequency for a sustained period is a very basic method of
- reducing resonance, always accelerating or decelerating through the resonant peak.
+* Ensuring the motor is never operated at a particular frequency for a sustained period is a very basic method of reducing resonance,
+ always accelerating or decelerating through the resonant peak.
* Increasing inertial load will damp unwanted resonances at the expense of some torque and potentially some accuracy.
Elastomeric motor mounts, shaft couplings or bearing mounts can be employed.
-* More advanced stepper motor drives may have the ability to switch between stepping modes such that the resonant
- peak is managed at certain rates of operation.
+* More advanced stepper motor drives may have the ability to switch between stepping modes such that the resonant peak is managed at certain rates of operation.
Other systems exist to place electrical load on the windings, which has a similar effect to mechanical damping, above.
== Microstepping
-A stepper motor operating with each winding being fully energised in a sequential fashion is operating in
-full-step mode. That is, the maximum rotation resolution possible for that motor is the same as the number of
-whole steps that motor is manufactured to perform at (eg, 200 steps per revolution for a 1.8 degree/step motor).
+A stepper motor operating with each winding being fully energised in a sequential fashion is operating in full-step mode.
+That is, the maximum rotation resolution possible for that motor is the same as the number of whole steps that motor is manufactured to perform at (e.g., 200 steps per revolution for a 1.8 degree/step motor).
As each winding is energised the rotor clocks around fully from one detent to the next.
-Additional rotational resolution from a stepper motor can be obtained by performing microstepping, whereby the
-current being driven into each winding can essentially be 'ramped' in discrete intermediate steps. This then
-causes the rotor to gradually straddle across each rotational detent rather than making the full jump from one
-step to the next.
+Additional rotational resolution from a stepper motor can be obtained by performing microstepping,
+whereby the current being driven into each winding can essentially be 'ramped' in discrete intermediate steps.
+This then causes the rotor to gradually straddle across each rotational detent rather than making the full jump from one step to the next.
-Microstepping is commonly performed in multiples of 2 (4x, 8x, 16x, 32x etc). For example, a drive set to 4x
-microstepping will divide each step into four discrete current levels in the motor windings, thus affording an
-improvement in rotational resolution by a factor of four. This obviously means that for a typical step/direction
-control interface there will need to be four times as many step pulses generated to make the motor move the same
-amount had it been operating in full-step mode. To make the motor rotate at the same speed the rate at which
-pulses need to be applied to the drive also needs to be four times as fast.
+Microstepping is commonly performed in multiples of 2 (4x, 8x, 16x, 32x etc).
+For example, a drive set to 4x microstepping will divide each step into four discrete current levels in the motor windings,
+thus affording an improvement in rotational resolution by a factor of four.
+This obviously means that for a typical step/direction control interface
+there will need to be four times as many step pulses generated to make the motor move the same amount had it been operating in full-step mode.
+To make the motor rotate at the same speed the rate at which pulses need to be applied to the drive also needs to be four times as fast.
-At low rotational speeds, microstepping actually results in slightly higher torque than when full stepping. This
-is due to the smaller changes in current between intermediate steps resulting in less energy being wasted exciting
-natural resonances in the motor. As RPM increases however, torque tends to fall off at a similar rate as full
-stepping.
+At low rotational speeds, microstepping actually results in slightly higher torque than when full stepping.
+This is due to the smaller changes in current between intermediate steps resulting in less energy being wasted exciting natural resonances in the motor.
+As RPM increases however, torque tends to fall off at a similar rate as full stepping.
However, continuing to increase the degree of microstepping will eventually lead to some real-life limitations.
-Step pulse generation, particularly when using the parallel port, is limited in frequency. This will inevitably
-limit the maximum speed at which the drive can be commanded to step at. With high degrees of microstepping this
-will result in unacceptably slow RPM of the motor.
-
-Excessively-high rates of microstepping have no real benefit if the resultant accuracy is too small to be
-mechanically useful. A 1.8 degree per step motor running at 16x microstepping is theoretically capable of 0.1125
-degrees per step. Coupled with a 20TPI leadscrew this should result in a positional resolution of 0.000016” or
-0.0004 mm. In reality it is incredibly difficult to achieve such fine degrees of control. All components in the CNC
-system will contain tolerances and countering forces (backlash in leadscrews, flex in gantries, runout in the
-spindle and cutting tool, static friction in the stepper motor itself, stepper detent error etc) that will render
-such small amounts of resolution completely meaningless. In practice, microstepping at rates in excess of 4x or 8x
-on a CNC machine fitted with leadscrews serves little purpose. In some cases it may even be more beneficial to run
-at lower degrees of microstepping or even full steps, and operate the stepper motor through a gear reduction to
-obtain the necessary resolution and torque gains.
+Step pulse generation, particularly when using the parallel port, is limited in frequency.
+This will inevitably limit the maximum speed at which the drive can be commanded to step at.
+With high degrees of microstepping this will result in unacceptably slow RPM of the motor.
+
+Excessively-high rates of microstepping have no real benefit if the resultant accuracy is too small to be mechanically useful.
+A 1.8 degree per step motor running at 16x microstepping is theoretically capable of 0.1125 degrees per step.
+Coupled with a 20&#8239;TPI leadscrew this should result in a positional resolution of 0.000016” or 0.0004&#8239;mm.
+In reality it is incredibly difficult to achieve such fine degrees of control.
+All components in the CNC system will contain tolerances and countering forces
+(backlash in leadscrews, flex in gantries, runout in the spindle and cutting tool,
+static friction in the stepper motor itself, stepper detent error , etc.) that will render such small amounts of resolution completely meaningless.
+In practice, microstepping at rates in excess of 4x or 8x on a CNC machine fitted with leadscrews serves little purpose.
+In some cases it may even be more beneficial to run at lower degrees of microstepping or even full steps,
+and operate the stepper motor through a gear reduction to obtain the necessary resolution and torque gains.
== Open and Closed Loop
-In the simplest CNC systems employing stepper motors, the host computer and/or stepper driver receives no feedback
-from the motor that it has achieved the desired outcome when commanded to begin stepping. The assumption by the
-software, driver and end user is that the motor operated correctly and the axis has moved to the expected new
-position. A system operating in this fashion is said to be running in 'open loop', where the device at the end of
-the signal chain (the stepper motor) does not provide any indication to the device at the start of the chain (the
-computer) that the target was reached.
-
-A further enhancement to the basic stepper motor is to run the system in a 'closed loop'. This is achieved by
-equipping the stepper motor with a rotary encoder whose positional signal is returned back to a device higher up
-in the signal chain. In this way the motors' actual position can be compared to the expected position at all
-times, and the drive parameters adjusted in real time to ensure that the motor does not fall behind. This enables
-closed loop stepper systems to be able to achieve better speed and torque performance than open loop systems, due
-to the system constantly compensating for any deviation to the stepper's performance under varying loads.
-
-Basic systems operating in this fashion may only close the loop between the motor and the driver, leaving the
-software on the host computer out of the loop. The software issues step/direction pulses to the downstream driver
-as it would normally when running in open loop. In these situations the drivers usually include an alarm output
-which signals the software to halt when the load placed on the stepper becomes too great for the driver to
-compensate without losing steps.
-
-More advanced implementations of closed loop operation bring the encoder signal all the way back to the host
-computer, but require that a much higher hardware and software overhead be installed to manage the encoder
-feedback and calculation and delivery of drive compensation.
+In the simplest CNC systems employing stepper motors,
+the host computer and/or stepper driver receives no feedback from the motor
+that it has achieved the desired outcome when commanded to begin stepping.
+The assumption by the software, driver and end user is that the motor operated correctly and the axis has moved to the expected new position.
+A system operating in this fashion is said to be running in 'open loop',
+where the device at the end of the signal chain (the stepper motor) does not provide any indication to the device at the start of the chain (the computer)
+that the target was reached.
+
+A further enhancement to the basic stepper motor is to run the system in a 'closed loop'.
+This is achieved by equipping the stepper motor with a rotary encoder whose positional signal is returned back to a device higher up in the signal chain.
+In this way the motors' actual position can be compared to the expected position at all times,
+and the drive parameters adjusted in real time to ensure that the motor does not fall behind.
+This enables closed loop stepper systems to be able to achieve better speed and torque performance than open loop systems,
+due to the system constantly compensating for any deviation to the stepper's performance under varying loads.
+
+Basic systems operating in this fashion may only close the loop between the motor and the driver,
+leaving the software on the host computer out of the loop.
+The software issues step/direction pulses to the downstream driver as it would normally when running in open loop.
+In these situations the drivers usually include an alarm output which signals the software to halt when the load placed on the stepper becomes too great for the driver to compensate without losing steps.
+
+More advanced implementations of closed loop operation bring the encoder signal all the way back to the host computer,
+but require that a much higher hardware and software overhead be installed to manage the encoder feedback and calculation and delivery of drive compensation.
// vim: set syntax=asciidoc:
diff --git a/docs/src/ladder/classic-ladder.adoc b/docs/src/ladder/classic-ladder.adoc
index 46fbf9c0e9..8988cdab8a 100644
--- a/docs/src/ladder/classic-ladder.adoc
+++ b/docs/src/ladder/classic-ladder.adoc
@@ -935,9 +935,8 @@ error. A timer could be used to stop the machine if timed out, etc.
== Debugging modbus problems
A good reference for the protocol:
-https://www.modbus.org/docs/Modbus_Application_Protocol_V1_1b.pdf
-If you run linuxcnc/classocladder from a terminal, it will print
-the Modbus commands and slave responses.
+https://www.modbus.org/docs/Modbus_Application_Protocol_V1_1b.pdf.
+If you run linuxcnc/classicladder from a terminal, it will print the Modbus commands and slave responses.
Here we set ClassicLadder to request slave 1,
to read holding registers (function code 3) starting at address 8448 (0x2100).
diff --git a/docs/src/man/man1/xhc-whb04b-6.1.adoc b/docs/src/man/man1/xhc-whb04b-6.1.adoc
index d2bf580cc3..34e845e256 100644
--- a/docs/src/man/man1/xhc-whb04b-6.1.adoc
+++ b/docs/src/man/man1/xhc-whb04b-6.1.adoc
@@ -112,8 +112,8 @@ Use the -H option to specify HAL mode and other options as required: +
Note:
For each button an output pin is provided even if no functionality is realized with that signal.
For example, to stop a running program the Stop button pin may be directly connected to `halui.program.stop`.
-However, to start/pause/resume a program, the corresponding button toggles besides `whb.button.start-pause`
-also the ``whb.halui.program.``{`run`,`pause`,`resume`} signals accordingly.
+However, to start/pause/resume a program,
+the corresponding button toggles besides `whb.button.start-pause` also the ``whb.halui.program.``{`run`,`pause`,`resume`} signals accordingly.
Note:
The Spindle+/Spindle- buttons do manipulate the spindle override.
@@ -125,7 +125,7 @@ The following tables list all in-/output pins and state which signals they are m
Signals utilized for moving axis.
-_<N>_ ... denotes the axis number, which is of {x, y, z, a, b, c}
+_<N>_ ... denotes the axis number, which is of {x, y, z, a, b, c}.
`whb.halui.home-all` (bit,out)::
connect to `halui.home-all`, driven by M-Home.
@@ -211,7 +211,7 @@ The feed rotary button can serve in
*Step:* In this mode the machine moves steps * wheel_counts at the currently selected step size and the current set feed rate in machine units.
If the commanded position is not reached the machine keeps moving even the jogwheel is not turning. +
*Lead:* Manipulates the spindle override. +
-*Mpg:* Manipulates the feedrate override.
+*MPG:* Manipulates the feedrate override.
Note:
As a consequence of 3 modes from manufacturer, switching the feed rotary button back from Lead revert to MPG mode, MPG mode is default mode at startup.
@@ -221,14 +221,11 @@ In MPG/CON the feed rate will change to 100%, 60%, ... and so forth. In Step mod
`whb.halui.feed-override.value` (float,in)::
connect to `halui.feed-override.value`. The current feed override value.
`whb.halui.feed-override.decrease` (bit,out)::
- connect to `halui.feed-override.decrease`. Pin for decreasing the feed
- override by amount of scale.
+ connect to `halui.feed-override.decrease`. Pin for decreasing the feed override by amount of scale.
`whb.halui.feed-override.increase` (bit,out)::
- connect to `halui.feed-override.increase`. Pin for increasing the feed
- override by amount of scale.
+ connect to `halui.feed-override.increase`. Pin for increasing the feed override by amount of scale.
`whb.halui.feed-override.scale` (float,out)::
- connect to `halui.feed-override.scale`. Pin for setting the scale on
- changing the feed override.
+ connect to `halui.feed-override.scale`. Pin for setting the scale on changing the feed override.
`whb.halui.max-velocity.value` (float,out)::
connect to `halui.max-velocity.value`.
@@ -280,7 +277,7 @@ By default the more frequent used orange buttons are executed,
whereas blue ones (``whb.button.macro-``_<M>_) by combining them with Fn
(press Fn first then button).
-Button macro needs to be added to your INI and needs to be edited for your own use :
+Button macro needs to be added to your INI and needs to be edited for your own use:
----
[HALUI]
@@ -306,44 +303,50 @@ MDI_COMMAND=(debug,macro16)
*_<M>_* ... denotes an arbitrary macro number which is of {1, 2, ..., 16}
`whb.button.reset` (bit,out)::
- see `whb.halui.estop.`{`activate`, `reset`} True one Reset button down, false otherwise.
+ see `whb.halui.estop.`{`activate`, `reset`}
+ True one Reset button down, false otherwise.
For toggling E-stop use whb.halui.estop .active and .reset.
`whb.button.stop` (bit,out)::
- see *whb.halui.program.stop` True on Stop button down, false otherwise.
+ see `whb.halui.program.stop`. True on Stop button down, false otherwise.
For stopping a program use whb.halui.program.stop.
`whb.button.start-pause` (bit,out)::
- see *whb.halui.program.{run, pause, resume}* True on Start-Pause button down, false otherwise.
+ see `whb.halui.program.`{`run`, `pause`, `resume`}`.
+ True on Start-Pause button down, false otherwise.
For toggling start-pause use `whb.halui.program.run`, `.pause`, and `.resume`.
`whb.button.feed-plus` (bit,out)::
True on Feed+ button down, false otherwise.
`whb.button.feed-minus` (bit,out)::
True on Feed- button down, false otherwise.
`whb.button.spindle-plus` (bit,out)::
- see *halui.spindle.0.override.increase* True on Spindle+ button down, false otherwise.
+ see `halui.spindle.0.override.increase`.
+ True on Spindle+ button down, false otherwise.
This button is meant to manipulate the spindle override.
For increasing the spindle override use `halui.spindle.0.override.increase`.
-`whb.button.spindle-minus* (bit,out)::
- see *halui.spindle.0.override.decrease* True on Spindle- button down, false otherwise.
+`whb.button.spindle-minus` (bit,out)::
+ see `halui.spindle.0.override.decrease`.
+ True on Spindle- button down, false otherwise.
This button is meant to manipulate the spindle override.
For decreasing the spindle override use `halui.spindle.0.override.decrease`.
-`whb.button.m-home* (bit,out)::
- connect to *halui.home-all* True on M-Home button down, false otherwise.
+`whb.button.m-home` (bit,out)::
+ connect to `halui.home-all`. True on M-Home button down, false otherwise.
Requests MDI mode before button pin is set. See also `whb.halui.mode.mdi`.
`whb.button.safe-z` (bit,out)::
- connect to *halui.mdi-command-`__<M>__ True on Safe-Z button down, false otherwise.
+ connect to `halui.mdi-command-`__<M>__
+ True on Safe-Z button down, false otherwise.
Requests MDI mode before button pin is set. See also `whb.halui.mode.mdi`.
`whb.button.w-home` (bit,out)::
- connect to *halui.mdi-command-`__<M>__ True on W-Home button down, false otherwise.
+ connect to `halui.mdi-command-`__<M>__
+ True on W-Home button down, false otherwise.
Requests MDI mode before button pin is set. See also `whb.halui.mode.mdi`.
`whb.button.s-on-off` (bit,out)::
- see `whb.halui.spindle.`{`start`, `stop`} True on S-ON/OFF button down, false otherwise.
+ see ``whb.halui.spindle.``{``start``, ``stop``} True on S-ON/OFF button down, false otherwise.
For toggling spindle on-off use `halui.spindle.0.start`.
For toggling spindle on-off use `halui.spindle.0.stop`.
`whb.button.fn` (bit,out)::
True on Fn button down, false otherwise.
`whb.button.probe-z` (bit,out)::
connect to `halui.mdi-command-`__<M>__ True on Probe-Z button down, false otherwise.
- Requests MDI mode before button pin is set. See also *whb.halui.mode.mdi*.
+ Requests MDI mode before button pin is set. See also `whb.halui.mode.mdi`.
`whb.button.macro-1` (bit,out)::
connect to `halui.mdi-command-`__<M>__ True on Macro-1 button (Fn + Feed+) down, false otherwise.
`whb.button.macro-2` (bit,out)::
@@ -355,7 +358,7 @@ MDI_COMMAND=(debug,macro16)
`whb.button.macro-4` (bit,out)::
see `whb.halui.spindle.decrease` True on Macro-4 button down (Fn + Spindle-), false otherwise.
This button is meant to manipulate the spindle speed.
- For decreasing the spindle speed use *whb.halui.spindle.decrease*.
+ For decreasing the spindle speed use `whb.halui.spindle.decrease`.
`whb.button.macro-5` (bit,out)::
connect to `halui.mdi-command-`__<M>__ True on Macro-5 button down (Fn + M-HOME), false otherwise.
`whb.button.macro-6` (bit,out)::
diff --git a/docs/src/plasma/plasma-cnc-primer.adoc b/docs/src/plasma/plasma-cnc-primer.adoc
index 36ef48c57f..1ba624809e 100644
--- a/docs/src/plasma/plasma-cnc-primer.adoc
+++ b/docs/src/plasma/plasma-cnc-primer.adoc
@@ -22,23 +22,40 @@ They consist of negative and positive sections separated by a center insulator.
Inside the torch, the pilot arc starts in the gap between the negatively charged electrode and the positively charged tip.
Once the pilot arc has ionised the plasma gas, the superheated column of gas flows through the small orifice in the torch tip, which is focused on the metal to be cut.
-In a Plasma Cutting Torch a cool gas enters Zone B, where a pilot arc between the electrode and the torch tip heats and ionises the gas. The main cutting arc then transfers to the workpiece through the column of plasma gas in Zone C. By forcing the plasma gas and electric arc through a small orifice, the torch delivers a high concentration of heat to a small area. The stiff, constricted plasma arc is shown in Zone C. Direct current (DC) straight polarity is used for plasma cutting, as shown in the illustration. Zone A channels a secondary gas that cools the torch. This gas also assists the high velocity plasma gas in blowing the molten metal out of the cut allowing for a fast, slag - free cut.
+In a Plasma Cutting Torch a cool gas enters Zone B, where a pilot arc between the electrode and the torch tip heats and ionises the gas.
+The main cutting arc then transfers to the workpiece through the column of plasma gas in Zone C.
+By forcing the plasma gas and electric arc through a small orifice, the torch delivers a high concentration of heat to a small area.
+The stiff, constricted plasma arc is shown in Zone C.
+Direct current (DC) straight polarity is used for plasma cutting, as shown in the illustration.
+Zone A channels a secondary gas that cools the torch.
+This gas also assists the high velocity plasma gas in blowing the molten metal out of the cut allowing for a fast, slag - free cut.
image::images/primer_torch-head.png[width=50%]
== Arc Initialisation
-There are two main methods for arc initialisation for plasma cutters that are designed for CNC operation. Whilst other methods are used on some machines (such as scratch start where physical contact with the material is required), they are unsuited for CNC applications..
+There are two main methods for arc initialisation for plasma cutters that are designed for CNC operation.
+Whilst other methods are used on some machines (such as scratch start where physical contact with the material is required), they are unsuited for CNC applications..
=== High Frequency Start
-This start type is widely employed, and has been around the longest. Although it is older technology, it works well, and starts quickly. But, because of the high frequency high voltage power that is required generated to ionise the air, it has some drawbacks. It often interferes with surrounding electronic circuitry, and can even damage components. Also a special circuit is needed to create a Pilot arc. Inexpensive models will not have a pilot arc, and require touching the consumable to the work to start. Employing a HF circuit also can increase maintenance issues, as there are usually adjustable points that must be cleaned and readjusted from time to time.
+This start type is widely employed, and has been around the longest.
+Although it is older technology, it works well, and starts quickly.
+But, because of the high frequency high voltage power that is required generated to ionise the air, it has some drawbacks.
+It often interferes with surrounding electronic circuitry, and can even damage components.
+Also a special circuit is needed to create a Pilot arc.
+Inexpensive models will not have a pilot arc, and require touching the consumable to the work to start.
+Employing a HF circuit also can increase maintenance issues, as there are usually adjustable points that must be cleaned and readjusted from time to time.
=== Blowback Start
-This start type uses air pressure supplied to the cutter to force a small piston or cartridge inside the torch head back to create a small spark between the inside surface of the consumable, ionising the air, and creating a small plasma flame. This also creates a "pilot arc" that provides a plasma flame that stays on, whether in contact with the metal or not. This is a very good start type that is now used by several manufacturers. It's advantage is that it requires somewhat less circuitry, is a fairly reliable and generates far less electrical noise.
+This start type uses air pressure supplied to the cutter to force a small piston or cartridge inside the torch head back to create a small spark between the inside surface of the consumable, ionising the air, and creating a small plasma flame.
+This also creates a "pilot arc" that provides a plasma flame that stays on, whether in contact with the metal or not.
+This is a very good start type that is now used by several manufacturers.
+It's advantage is that it requires somewhat less circuitry, is a fairly reliable and generates far less electrical noise.
-For entry level air plasma CNC systems, the blowback style is much preferred to minimise electrical interference with electronics and standard PCs but the High frequency start still rules supreme in larger machines from 200 amps and up. These require industrial level PC's and electronics and even commercial manufacturers have had issues with faults because they have failed to account for electrical noise in their designs.
+For entry level air plasma CNC systems, the blowback style is much preferred to minimise electrical interference with electronics and standard PCs but the High frequency start still rules supreme in larger machines from 200 amps and up.
+These require industrial level PC's and electronics and even commercial manufacturers have had issues with faults because they have failed to account for electrical noise in their designs.
== CNC Plasma
@@ -49,7 +66,9 @@ Thick sheets (30 mm plus) can be out of plane as much as 50 mm to 100 mm.
Most other CNC G-code operations will start from a known reference or a piece of stock that has a known size and shape and the G-code is written to rough the excess off and then finally cut the finished part.
With plasma the unknown state of the sheet makes it impossible to generate G-code that will cater for these variances in the material.
-A plasma Arc is oval in shape and the cutting height needs to be controlled to minimise bevelled edges. If the torch is too high or too low then the edges can become excessively bevelled. It is also critical that the torch is held perpendicular to the surface.
+A plasma Arc is oval in shape and the cutting height needs to be controlled to minimise bevelled edges.
+If the torch is too high or too low then the edges can become excessively bevelled.
+It is also critical that the torch is held perpendicular to the surface.
* *Torch to work distance can impact edge bevel*
@@ -61,7 +80,8 @@ image::images/primer_cut-angularity.png[width=50%]
[NOTE]
A slight variation in cut angles may be normal, as long as it is within tolerance.
-The ability to precisely control the cutting height in such a hostile and ever changing environment is a very difficult challenge. Fortunately there is a very linear relationship between Torch height (Arc length) and arc voltage as this graph shows.
+The ability to precisely control the cutting height in such a hostile and ever changing environment is a very difficult challenge.
+Fortunately there is a very linear relationship between Torch height (Arc length) and arc voltage as this graph shows.
image::images/primer_volts-height.png[width=50%]
@@ -77,7 +97,9 @@ A torch height control unit (THC) is traditionally used to manage this process.
== Choosing a Plasma Machine for CNC operations
-There are a plethora of plasma machines available on the market today and not all of them are suited for CNC use. CNC Plasma cutting is a complex operation and it is recommended that integrators choose a suitable plasma machine. Failure to do this is likely to cause hours and hours of fruitless trouble shooting trying to work around the lack of what many would consider to be mandatory features.
+There are a plethora of plasma machines available on the market today and not all of them are suited for CNC use.
+CNC Plasma cutting is a complex operation and it is recommended that integrators choose a suitable plasma machine.
+Failure to do this is likely to cause hours and hours of fruitless trouble shooting trying to work around the lack of what many would consider to be mandatory features.
Whilst rules are made to be broken if you fully understand the reasons the rule apply, we consider a new plasma table builder should select a machine with the following features:
@@ -98,37 +120,74 @@ In recent times, another class of machine which includes some of these features
== Types Of Torch Height Control
-Most THC units are external devices and many have a fairly crude “bit bang" adjustment method. They provide two signals back to the LinuxCNC controller. One turns on if the Z axis should move up and the other turns on if the Z axis should move down. Neither signal is true if the torch is at the correct height. The popular Proma 150 THC is one example of this type of THC. The LinuxCNC THCUD component is designed to work with this type of THC.
-
-With the release of the Mesa THCAD voltage to frequency interface, LinuxCNC was able to decode the actual torch voltage via an encoder input. This allowed LinuxCNC to control the Z axis and eliminate external hardware. Early implementations utilising the THCAD replicated the “bit bang" approach. The LinuxCNC THC component is an example of this approach.
-
-Jim Colt of Hypertherm is on record saying that the best THC controllers were fully integrated into the CNC controller itself. Of course he was referring to high end systems manufactured by Hypertherm, Esab, Thermal Dynamics and others such as Advanced Robotic Technology in Australia, little dreaming that open source could produce systems using this approach that rival high end systems.
-
-The inclusion of external offsets in LinuxCNC V2.8 allowed plasma control in LinuxCNC to rise to a whole new level. External Offsets refers to the ability to apply an offset to the axis commanded position external to the motion controller. This is perfect for plasma THC control as a method to adjust the torch height in real time based on our chosen process control methodology. Following a number of experimental builds, the Plasmac configuration was incorporated into LinuxCNC 2.8. link:./qtplasmac.html[QtPlasmaC] has superceded Plasmac in LinuxCNC 2.9.
-This has been an extremely ambitious project and many people around the globe have been involved in testing and improving the feature set. QtPlasmaC is unique in that its design goal was to support all THCs including the simple bit bang ones through to sophisticated torch voltage control if the voltage is made available to LinuxCNC via a THCAD or some other voltage sensor. What's more, QtPlasmaC is designed to be a stand alone system that does not need any additional G-code subroutines and allows the user to define their own cut charts that are stored in the system and accessible by a drop-down.
+Most THC units are external devices and many have a fairly crude “bit bang" adjustment method.
+They provide two signals back to the LinuxCNC controller.
+One turns on if the Z axis should move up and the other turns on if the Z axis should move down.
+Neither signal is true if the torch is at the correct height.
+The popular Proma 150 THC is one example of this type of THC.
+The LinuxCNC THCUD component is designed to work with this type of THC.
+
+With the release of the Mesa THCAD voltage to frequency interface, LinuxCNC was able to decode the actual torch voltage via an encoder input.
+This allowed LinuxCNC to control the Z axis and eliminate external hardware.
+Early implementations utilising the THCAD replicated the “bit bang" approach.
+The LinuxCNC THC component is an example of this approach.
+
+Jim Colt of Hypertherm is on record saying that the best THC controllers were fully integrated into the CNC controller itself.
+Of course he was referring to high end systems manufactured by Hypertherm, Esab, Thermal Dynamics and others such as Advanced Robotic Technology in Australia, little dreaming that open source could produce systems using this approach that rival high end systems.
+
+The inclusion of external offsets in LinuxCNC V2.8 allowed plasma control in LinuxCNC to rise to a whole new level.
+External Offsets refers to the ability to apply an offset to the axis commanded position external to the motion controller.
+This is perfect for plasma THC control as a method to adjust the torch height in real time based on our chosen process control methodology.
+Following a number of experimental builds, the Plasmac configuration was incorporated into LinuxCNC 2.8.
+link:./qtplasmac.html[QtPlasmaC] has superceded Plasmac in LinuxCNC 2.9.
+This has been an extremely ambitious project and many people around the globe have been involved in testing and improving the feature set.
+QtPlasmaC is unique in that its design goal was to support all THCs including the simple bit bang ones through to sophisticated torch voltage control if the voltage is made available to LinuxCNC via a THCAD or some other voltage sensor.
+What's more, QtPlasmaC is designed to be a stand alone system that does not need any additional G-code subroutines and allows the user to define their own cut charts that are stored in the system and accessible by a drop-down.
== Arc OK Signal
-Plasma machines that have a CNC interface contain a set of dry contacts (eg a relay) that close when a valid arc is established and each side of these contacts are bought out onto pins on the CNC interface. A plasma table builder should connect one side of these pins to field power and the other to an input pin. This then allows the CNC controller to know when a valid arc is established and also when an arc is lost unexpectedly. There is a potential trap here when the input is a high impedance circuit such as a Mesa card. If the dry contacts are a simple relay, there is a high probability that the current passing through the relay is less than the minimum current specification. Under these conditions, the relay contacts can suffer from a buildup of oxide which over time can result in intermittent contact operation. To prevent this from happening, a pull down resistor should be installed on the controller input pin. Care should be taken to ensure that this resistor is selected to ensure the minimum current passes through the relay and is of sufficient wattage to handle the power in the circuit. Finally, the resistor should be mounted in such a way that the generated heat does not damage anything whilst in operation.
-
-If you have an ArcOK signal, it is recommended it is used over and above any synthesised signal to eliminate potential build issues. A synthesised signal available from an external THC or QtPlasmaC's Mode 0 can't fully replace the ArcOK circuitry in a plasma inverter. Some build issues have been observed where misconfiguration or incompatibility with the plasma inverter has occurred from a synthesised ArcOK signal. By and large however, a correctly configured synthesised ArcOK signal is fine.
-
-A simple and effective ArcOK signal can be achieved with a simple reed relay. Wrap 3 turns of one of the plasma cutter's thick cables (eg the material clamp cable) around it. Place the relay in an old pen tube for protection and connect one side of the relay to field power and the other end to your ArcOK input pin.
+Plasma machines that have a CNC interface contain a set of dry contacts (eg a relay) that close when a valid arc is established and each side of these contacts are bought out onto pins on the CNC interface.
+A plasma table builder should connect one side of these pins to field power and the other to an input pin.
+This then allows the CNC controller to know when a valid arc is established and also when an arc is lost unexpectedly.
+There is a potential trap here when the input is a high impedance circuit such as a Mesa card.
+If the dry contacts are a simple relay, there is a high probability that the current passing through the relay is less than the minimum current specification.
+Under these conditions, the relay contacts can suffer from a buildup of oxide which over time can result in intermittent contact operation.
+To prevent this from happening, a pull down resistor should be installed on the controller input pin.
+Care should be taken to ensure that this resistor is selected to ensure the minimum current passes through the relay and is of sufficient wattage to handle the power in the circuit.
+Finally, the resistor should be mounted in such a way that the generated heat does not damage anything whilst in operation.
+
+If you have an ArcOK signal, it is recommended it is used over and above any synthesised signal to eliminate potential build issues.
+A synthesised signal available from an external THC or QtPlasmaC's Mode 0 can't fully replace the ArcOK circuitry in a plasma inverter.
+Some build issues have been observed where misconfiguration or incompatibility with the plasma inverter has occurred from a synthesised ArcOK signal.
+By and large however, a correctly configured synthesised ArcOK signal is fine.
+
+A simple and effective ArcOK signal can be achieved with a simple reed relay.
+Wrap 3 turns of one of the plasma cutter's thick cables, e.g. the material clamp cable, around it.
+Place the relay in an old pen tube for protection and connect one side of the relay to field power and the other end to your ArcOK input pin.
== Initial Height Sensing
-Because the cutting height is such a critical system parameter and the material surface is inherently uneven, a Z axis mechanism needs a method to sense the material surface. There are three methods this can be achieved; Current sensing to detect increased motor torque, a “float" switch and an electrical or “ohmic" sensing circuit that is closed when the torch shield contacts the material. Current sensing is not a viable technique for DIY tables but float switches and ohmic sensing are discussed below:
+Because the cutting height is such a critical system parameter and the material surface is inherently uneven, a Z axis mechanism needs a method to sense the material surface.
+There are three methods this can be achieved; Current sensing to detect increased motor torque, a “float" switch and an electrical or “ohmic" sensing circuit that is closed when the torch shield contacts the material.
+Current sensing is not a viable technique for DIY tables but float switches and ohmic sensing are discussed below:
=== Float Switches
-The torch is mounted on a sliding stage that can move up when the torch tip contacts the material surface and trigger a switch or sensor. Often this is achieved under G-code control using the G38 Commands. If this is the case, then after initial probing, it is recommended to probe away from the surface until the probe signal is lost at a slower speed. Also, ensure the switch hysteresis is accounted for.
+The torch is mounted on a sliding stage that can move up when the torch tip contacts the material surface and trigger a switch or sensor.
+Often this is achieved under G-code control using the G38 Commands.
+If this is the case, then after initial probing, it is recommended to probe away from the surface until the probe signal is lost at a slower speed.
+Also, ensure the switch hysteresis is accounted for.
Regardless of the probing method used, it is strongly recommended that float switch is implemented so that there is a fallback or secondary signal to avoid damage to the torch from a crash.
[[ohmic-sensing]]
=== Ohmic Sensing
-Ohmic sensing relies on contact between the torch and the material acting as a switch to activate an electrical signal that is sensed by the CNC controller. Provided the material is clean, this can be a much more accurate method of sensing the material than a float switch which can cause deflection of the material surface. This ohmic sensing circuit is operating in an extremely hostile environment so a number of failsafes need to be implemented to ensure safety of both the CNC electronics and the operator. In plasma cutting, the earth clamp attached to the material is positive and the torch is negative. It is recommended that:
+Ohmic sensing relies on contact between the torch and the material acting as a switch to activate an electrical signal that is sensed by the CNC controller.
+Provided the material is clean, this can be a much more accurate method of sensing the material than a float switch which can cause deflection of the material surface.
+This ohmic sensing circuit is operating in an extremely hostile environment so a number of failsafes need to be implemented to ensure safety of both the CNC electronics and the operator.
+In plasma cutting, the earth clamp attached to the material is positive and the torch is negative.
+It is recommended that:
. Ohmic sensing only be implemented where the torch has a shield that is isolated from the torch tip that conveys the cutting arc.
. The ohmic circuit uses a totally separate isolated power supply that activates an opto-isolated relay to enable the probing signal to be transmitted to the CNC controller.
@@ -142,13 +201,21 @@ image::images/primer_ohmic-sensing.png[width=100%]
=== Hypersensing with a MESA THCAD-5
-A more sophisticated method of material sensing that eliminates the relays and diodes is to use another THCAD-5 to monitor the material sensing circuit voltage from an isolated power supply. The advantage this has is the THCAD is designed for the hostile plasma electrical environment and totally and safely isolates the logic side from the high voltage side.
+A more sophisticated method of material sensing that eliminates the relays and diodes is to use another THCAD-5 to monitor the material sensing circuit voltage from an isolated power supply.
+The advantage this has is the THCAD is designed for the hostile plasma electrical environment and totally and safely isolates the logic side from the high voltage side.
To implement this method, a second encoder input is required.
-If using a mesa card, different firmware is available to provide 2 additional Encoder A inputs on the Encoder B and Encoder Index pins. This firmware is available for download for the 7i76e and 7i96 boards from the Mesa web site on the product pages.
+If using a mesa card, different firmware is available to provide 2 additional Encoder A inputs on the Encoder B and Encoder Index pins.
+This firmware is available for download for the 7I76e and 7I96 boards from the Mesa web site on the product pages.
-The THCAD is sensitive enough to see the ramp up in circuit voltage as contact pressure increases. The ohmic.comp component included in LinuxCNC can monitor the sensing voltage and set a voltage threshold above which it is deemed contact is made and an output is enabled. By monitoring the voltage, a lower “break circuit" threshold can be set to build in strong switch hysteresis. This minimises false triggering. In our testing, we found the material sensing using this method was more sensitive and robust as well as being simpler to implement the wiring. One further advantage is using software outputs instead of physical I/O pins is that it frees up pins to use for other purposes. This advantage is helpful to get the most out of the Mesa 7i96 which has limited I/O pins.
+The THCAD is sensitive enough to see the ramp up in circuit voltage as contact pressure increases.
+The ohmic.comp component included in LinuxCNC can monitor the sensing voltage and set a voltage threshold above which it is deemed contact is made and an output is enabled.
+By monitoring the voltage, a lower “break circuit" threshold can be set to build in strong switch hysteresis.
+This minimises false triggering.
+In our testing, we found the material sensing using this method was more sensitive and robust as well as being simpler to implement the wiring.
+One further advantage is using software outputs instead of physical I/O pins is that it frees up pins to use for other purposes.
+This advantage is helpful to get the most out of the Mesa 7I96 which has limited I/O pins.
The following circuit diagram shows how to implement a hypersensing circuit.
@@ -159,7 +226,9 @@ This is a double insulated Isolation Class II device that will withstand any arc
=== Example HAL Code for Hypersensing
-The following HAL code can be pasted into your QtPlasmaC's custom.hal to enable Ohmic sensing on Encoder 2 of a 7i76e. Install the correct bit file and connect the THCAD to IDX+ and IDX-. Be sure to change the calibration settings to agree with your THCAD-5.
+The following HAL code can be pasted into your QtPlasmaC's custom.hal to enable Ohmic sensing on Encoder 2 of a 7I76e.
+Install the correct bit file and connect the THCAD to IDX+ and IDX-.
+Be sure to change the calibration settings to agree with your THCAD-5.
[source,{hal}]
----
@@ -167,7 +236,7 @@ The following HAL code can be pasted into your QtPlasmaC's custom.hal to enable
loadrt ohmic names=ohmicsense
addf ohmicsense servo-thread
-# --- 7i76e ENCODER 2 SETUP FOR OHMIC SENSING---
+# --- 7I76e ENCODER 2 SETUP FOR OHMIC SENSING---
setp hm2_7i76e.0.encoder.02.scale -1
setp hm2_7i76e.0.encoder.02.counter-mode 1
@@ -193,9 +262,12 @@ When an arc is established, arc voltage peaks significantly and then settles bac
image::images/primer_thc-delay.png[width=100%]
-It is important for the plasma controller to “wait it out" before auto sampling the torch voltage and commencing THC control. If enabled too early, the voltage will be above the desired cut Volts and the torch will be driven down in an attempt to address a perceived over-height condition.
+It is important for the plasma controller to “wait it out" before auto sampling the torch voltage and commencing THC control.
+If enabled too early, the voltage will be above the desired cut Volts and the torch will be driven down in an attempt to address a perceived over-height condition.
-In our testing this varies between machines and material from 0.5 to 1.5 seconds. Therefore a delay of 1.5 s after a valid ArcOK signal is received before enabling THC control is a safe initial setting. If you want to shorten this for a given material, LinuxCNC's Halscope will allow you to plot the torch voltage and make informed decisions about the shortest safe delay is used.
+In our testing this varies between machines and material from 0.5 to 1.5 seconds.
+Therefore a delay of 1.5 s after a valid ArcOK signal is received before enabling THC control is a safe initial setting.
+If you want to shorten this for a given material, LinuxCNC's Halscope will allow you to plot the torch voltage and make informed decisions about the shortest safe delay is used.
[NOTE]
If the cut velocity is not near the desired cut speed at the end of this delay, the controller should wait until this is achieved before enabling the THC.
@@ -206,7 +278,9 @@ Rather than relying on the manufacturer's cut charts to set the desired torch vo
== Torch Breakaway
-It is recommended that a mechanism is provided to allow the torch to “break away" or fall off in the case of impact with the material or a cut part that has tipped up. A sensor should be installed to allow the CNC controller to detect if this has occurred and pause the running program. Usually a break away is implemented using magnets to secure the torch to the Z axis stage.
+It is recommended that a mechanism is provided to allow the torch to “break away" or fall off in the case of impact with the material or a cut part that has tipped up.
+A sensor should be installed to allow the CNC controller to detect if this has occurred and pause the running program.
+Usually a break away is implemented using magnets to secure the torch to the Z axis stage.
== Corner Lock / Velocity Anti-Dive
@@ -219,13 +293,18 @@ So it becomes a trivial matter to monitor the current velocity (`motion.current-
== Void / Kerf Crossing
-If the plasma torch passes over a void while cutting, arc voltage rapidly rises and the THC responds by violent downward motion which can smash the torch into the material possibly damaging it. This is a situation that is difficult to detect and handle. To a certain extent it can be mitigated by good nesting techniques but can still occur on thicker material when a slug falls away. This is the one problem that has yet to be solved within the LinuxCNC open source movement.
+If the plasma torch passes over a void while cutting, arc voltage rapidly rises and the THC responds by violent downward motion which can smash the torch into the material possibly damaging it.
+This is a situation that is difficult to detect and handle.
+To a certain extent it can be mitigated by good nesting techniques but can still occur on thicker material when a slug falls away.
+This is the one problem that has yet to be solved within the LinuxCNC Open Source movement.
-One suggested technique is to monitor the rate of change in torch Volts over time (dv/dt) because this parameter is orders of magnitude higher when crossing a void than what occurs due to normal warpage of the material. The following graph shows a low resolution plot of dv/dt (in blue) while crossing a void. The red curve is a moving average of torch Volts.
+One suggested technique is to monitor the rate of change in torch Volts over time (dv/dt) because this parameter is orders of magnitude higher when crossing a void than what occurs due to normal warpage of the material.
+The following graph shows a low resolution plot of dv/dt (in blue) while crossing a void. The red curve is a moving average of torch Volts.
image::images/primer_kerf-cross.png[width=50%]
-So it should be possible to compare the moving average with the dv/dt and halt THC operation once the dv/dt exceeds the normal range expected due to warpage. More work needs to be done in this area to come up with a working solution in LinuxCNC.
+So it should be possible to compare the moving average with the dv/dt and halt THC operation once the dv/dt exceeds the normal range expected due to warpage.
+More work needs to be done in this area to come up with a working solution in LinuxCNC.
== Hole And Small Shape Cutting
@@ -244,22 +323,34 @@ The generally accepted method to get good holes from 37mm dia. and down to mater
You will need to experiment to get exact hole size because the kerf with this method will be wider than your usual straight cut."
-This slow down can be achieved by manipulating the feed rate directly in your post processor or by using adaptive feed and an analog pin as input. This lets you use M67/M68 to set the percentage of desired feed to cut at.
+This slow down can be achieved by manipulating the feed rate directly in your post processor or by using adaptive feed and an analog pin as input.
+This lets you use M67/M68 to set the percentage of desired feed to cut at.
- Knowing The Feedrate
-From the preceding discussion it is evident that the plasma controller needs to know the feed rate set by the user. This poses a problem with LinuxCNC because the Feedrate is not saved by LinuxCNC after the G-code is buffered and parsed. There are two approaches to work around this:
+From the preceding discussion it is evident that the plasma controller needs to know the feed rate set by the user.
+This poses a problem with LinuxCNC because the Feedrate is not saved by LinuxCNC after the G-code is buffered and parsed.
+There are two approaches to work around this:
-. Remap the F command and save the commanded feedrate set in G-code via an M67/M68 command
-. Storing the cut charts in the plasma controller and allow the current feedrate be queried by the G-code program (as QtPlasmaC does)
+. Remap the F command and save the commanded feedrate set in G-code via an M67/M68 command.
+. Storing the cut charts in the plasma controller and allow the current feedrate be queried by the G-code program (as QtPlasmaC does).
-One experimental LinuxCNC branch that would be useful for plasma cutting was the state tags branch. This adds a “tag" that is available to motion containing the current feed and speed rates for all active motion commands. It has been merged and will be in LinuxCNC v2.9
+A feature newly added to LinuxCNC 2.9 that is useful for plasma cutting are the state tags.
+This adds a “tag" that is available to motion containing the current feed and speed rates for all active motion commands.
== I/O Pins For Plasma Controllers
-Plasma cutters require several additional pins. In LinuxCNC, there are no hard and fast rules about which pin does what. In this discussion we will assume the plasma inverter has a CNC interface and the controller card has active high inputs are in use (e.g., Mesa 7i76e).
+Plasma cutters require several additional pins.
+In LinuxCNC, there are no hard and fast rules about which pin does what.
+In this discussion we will assume the plasma inverter has a CNC interface and the controller card has active high inputs are in use (e.g., Mesa 7I76e).
-Plasma tables can be large machines and we recommend that you take the time to install separate max/min limit switches and homing switches for each joint. The exception might be the Z axis lower limit. When a homing switch is triggered the joint decelerates fairly slowly for maximum accuracy. This means that if you wish to use homing velocities that are commensurate with table size, you can overshoot the initial trigger point by 50-100 mm. If you use a shared home/limit switch, you have to move the sensor off the trigger point with the final HOME_OFFSET or you will trigger a limit switch fault as the machine comes out of homing. This means you could lose 50 mm or more of axis travel with shared home/limit switches. This does not happen if separate home and limit switches are used.
+Plasma tables can be large machines and we recommend that you take the time to install separate max/min limit switches and homing switches for each joint.
+The exception might be the Z axis lower limit.
+When a homing switch is triggered the joint decelerates fairly slowly for maximum accuracy.
+This means that if you wish to use homing velocities that are commensurate with table size, you can overshoot the initial trigger point by 50-100 mm.
+If you use a shared home/limit switch, you have to move the sensor off the trigger point with the final HOME_OFFSET or you will trigger a limit switch fault as the machine comes out of homing.
+This means you could lose 50 mm or more of axis travel with shared home/limit switches.
+This does not happen if separate home and limit switches are used.
The following pins are usually required (note that suggested connections may not be appropriate for a QtPlasmaC configuration):
@@ -272,16 +363,16 @@ The following pins are usually required (note that suggested connections may not
=== Torch On (output)
-* Triggers a relay to close the torch on switch in the inverter
-* Connect the torch on terminals on the inverter to the relay output terminals
-* Connect one side of the coil to the output pin
+* Triggers a relay to close the torch on switch in the inverter.
+* Connect the torch on terminals on the inverter to the relay output terminals.
+* Connect one side of the coil to the output pin.
* Connect the other side of the coil to Field Power ground.
-* If a mechanical relay is used, connect a flyback diode (e.g., IN400x series) across the coil terminals with the band on the diode pointing towards the output pin
-* If a Solid State Relay is used, polarity may need to be observed on the outputs
+* If a mechanical relay is used, connect a flyback diode (e.g., IN400x series) across the coil terminals with the band on the diode pointing towards the output pin.
+* If a Solid State Relay is used, polarity may need to be observed on the outputs.
* In some circumstances, the onboard spindle relay on a Mesa card can be used instead of an external relay.
-* Usually connected to `spindle.0.on`
+* Usually connected to `spindle.0.on`.
-WARNING: It is strongly recommended that the torch cannot be enabled while this pin is false otherwise the torch will not be extinguished when estop is pressed;
+WARNING: It is strongly recommended that the torch cannot be enabled while this pin is false otherwise the torch will not be extinguished when estop is pressed.
=== Float switch (input)
@@ -293,7 +384,7 @@ WARNING: It is strongly recommended that the torch cannot be enabled while this
* See the <<ohmic-sensing,ohmic sensing>> schematic.
* Connect output pin to one side of the isolation relays and the other side to field power ground.
-* In a non-QtPlasmaC configuration, usually triggered by a `motion.digital-out-_<nn>_` so it can be controlled in G-code by M62/M63/M64/M65
+* In a non-QtPlasmaC configuration, usually triggered by a `motion.digital-out-_<nn>_` so it can be controlled in G-code by M62/M63/M64/M65.
=== Ohmic Sensing (input)
@@ -303,7 +394,10 @@ WARNING: It is strongly recommended that the torch cannot be enabled while this
* Take care to observe relay polarity if opto-coupled solid State relays are used.
* Usually connected to `motion.probe-input` and may be or'd with the float switch.
-As can be seen, plasma tables are pin intensive and we have already consumed about 15 inputs before the normal estops are added. Others have other views but it is the writer's opinion that the Mesa 7i76e is preferred over the cheaper 7i96 to allow for MPG's, scale and axis selection switch and other features you may wish to add over time. If your table uses servos, there are a number of alternatives. Whilst there are other suppliers, designing your machine around the Mesa ecosystem will simplify use of their THCAD board to read arc voltage.
+As can be seen, plasma tables are pin intensive and we have already consumed about 15 inputs before the normal E-stops are added.
+Others have other views but it is the writer's opinion that the Mesa 7I76e is preferred over the cheaper 7I96 to allow for MPG's, scale and axis selection switch and other features you may wish to add over time.
+If your table uses servos, there are a number of alternatives.
+Whilst there are other suppliers, designing your machine around the Mesa ecosystem will simplify use of their THCAD board to read arc voltage.
=== Torch Breakaway Sensor
@@ -312,7 +406,10 @@ As can be seen, plasma tables are pin intensive and we have already consumed abo
== G-code For Plasma Controllers
-Most plasma controllers offer a method to change settings from G-code. LinuxCNC support this via M67/M68 for analog commands and M62-M65 for digital (on/off commands). How this is implemented is totally arbitrary. Lets look at how the LinuxCNC QtPlasmaC configuration does this:
+Most plasma controllers offer a method to change settings from G-code.
+LinuxCNC support this via M67/M68 for analog commands and M62-M65 for digital (on/off commands).
+How this is implemented is totally arbitrary.
+Lets look at how the LinuxCNC QtPlasmaC configuration does this:
=== Select Material Settings In QtPlasmaC And Use The Feedrate For That Material:
@@ -359,9 +456,24 @@ NOTE: Integrators should familiarise themselves with the LinuxCNC documentation
== External Offsets and Plasma Cutting
-External Offsets were introduced to LinuxCNC with version 2.8. By external, it means that we can apply an offset external to the G-code that the trajectory planner knows nothing about. It easiest to explain with an example. Picture a lathe with an external offset being applied by a mathematical formula to machine a lobe on a cam. So the lathe is blindly spinning around with the cut diameter set to a fixed diameter and the external offset moves the tool in and out to machine the cam lobe via an applied external offset. To configure our lathe to machine this cam, we need to allocate some portion of the axis velocity and acceleration to external offsets or the tool can't move. This is where the ini variable OFFSET_AV_RATIO comes in. Say we decide we need to allocate 20% of the velocity and acceleration to the external offset to the Z axis. We set this equal to 0.2. The consequence of this is that your maximum velocity and acceleration for the Lathe's Z axis is only 80% of what it could be.
-
-External offsets are a very powerful method to make torch height adjustments to the Z axis via a THC. But plasma is all about high velocities and rapid acceleration so it makes no sense to limit these parameters. Fortunately in a plasma machine, the Z axis is either 100% controlled by the THC or it isn't. During the development of LinuxCNC's external offsets it was recognised that Z axis motion by G-code and by THC were mutually exclusive. This allows us to trick external offsets into giving 100 % of velocity and acceleration all of the time. We can do this by doubling the machine's Z axis velocity and acceleration settings in the ini file and set OFFSET_AV_RATIO = 0.5. That way 100% of the maximum velocity and acceleration will be available for both probing and THC.
+External Offsets were introduced to LinuxCNC with version 2.8.
+By external, it means that we can apply an offset external to the G-code that the trajectory planner knows nothing about.
+It easiest to explain with an example.
+Picture a lathe with an external offset being applied by a mathematical formula to machine a lobe on a cam.
+So the lathe is blindly spinning around with the cut diameter set to a fixed diameter and the external offset moves the tool in and out to machine the cam lobe via an applied external offset.
+To configure our lathe to machine this cam, we need to allocate some portion of the axis velocity and acceleration to external offsets or the tool can't move.
+This is where the ini variable OFFSET_AV_RATIO comes in.
+Say we decide we need to allocate 20% of the velocity and acceleration to the external offset to the Z axis.
+We set this equal to 0.2.
+The consequence of this is that your maximum velocity and acceleration for the Lathe's Z axis is only 80% of what it could be.
+
+External offsets are a very powerful method to make torch height adjustments to the Z axis via a THC.
+But plasma is all about high velocities and rapid acceleration so it makes no sense to limit these parameters.
+Fortunately in a plasma machine, the Z axis is either 100% controlled by the THC or it isn't.
+During the development of LinuxCNC's external offsets it was recognised that Z axis motion by G-code and by THC were mutually exclusive.
+This allows us to trick external offsets into giving 100 % of velocity and acceleration all of the time.
+We can do this by doubling the machine's Z axis velocity and acceleration settings in the ini file and set OFFSET_AV_RATIO = 0.5.
+That way 100% of the maximum velocity and acceleration will be available for both probing and THC.
Example:
On a metric machine with a NEMA23 motor with a direct drive to a 5 mm ball screw, 60 mm/s maximum velocity and 700 mm/s^2^ acceleration were determined to be safe values without loss of steps. For this machine, set the Z axis in the ini file as follows:
@@ -387,24 +499,31 @@ For further information about external offsets (for version 2.8 or later) please
== Reading Arc Voltage With The Mesa THCAD
-The Mesa THCAD board is a remarkably well priced and accurate voltage to frequency converter that is designed for the hostile noisy electrical environment associated with plasma cutting. Internally it has a 0-10 V range. This range can be simply extended by the addition of some resistors as described in the documentation. This board is available in three versions, the newer THCAD-5 with a 0-5 V range, the THCAD-10 with a 0-10 Volt range and the THCAD-300 which is pre-calibrated for a 300 Volt extended range. Each board is individually calibrated and a sticker is applied to the board that states the frequency at 0 Volts and full scale. For use with LinuxCNC, it is recommended that the 1/32 divisor be selected by the appropriate link on the board. In this case, be sure to also divide the stated frequencies by 32. This is more appropriate for the 1 kHz servo thread and also allows more time for the THCAD to average and smooth the output.
+The Mesa THCAD board is a remarkably well priced and accurate voltage to frequency converter that is designed for the hostile noisy electrical environment associated with plasma cutting.
+Internally it has a 0-10 V range.
+This range can be simply extended by the addition of some resistors as described in the documentation.
+This board is available in three versions, the newer THCAD-5 with a 0-5 V range, the THCAD-10 with a 0-10 Volt range and the THCAD-300 which is pre-calibrated for a 300 Volt extended range.
+Each board is individually calibrated and a sticker is applied to the board that states the frequency at 0 Volts and full scale.
+For use with LinuxCNC, it is recommended that the 1/32 divisor be selected by the appropriate link on the board.
+In this case, be sure to also divide the stated frequencies by 32.
+This is more appropriate for the 1 kHz servo thread and also allows more time for the THCAD to average and smooth the output.
-There is a lot of confusion around how to decode the THCAD output so lets consider the Mesa 7i76e and the THCAD-10 for a moment with the following hypothetical calibration data:
+There is a lot of confusion around how to decode the THCAD output so lets consider the Mesa 7I76e and the THCAD-10 for a moment with the following hypothetical calibration data:
-* Full scale 928,000 Hz (1/32 29,000 Hz)
-* 0 volt 121,600 Hz (1/32 3,800 Hz)
+* Full scale 928 kHz (1/32 29000 Hz)
+* 0 volt 121.6 kHz (1/32 3800 Hz)
Because the full scale is 10 Volts, then the frequency per Volt is:
-(29,000 Hz - 3,800 Hz) / 10 V = 2,520 Hz per Volt
+(29000 Hz - 3800 Hz) / 10 V = 2520 Hz per Volt
So assuming we have a 5 Volt input, the calculated frequency would be:
-(2520 Hz/V * 5 V) + 3,800 Hz = 16,400 Hz
+(2520 Hz/V * 5 V) + 3800 Hz = 16400 Hz
So now it should be fairly clear how to convert the frequency to its voltage equivalent:
-Volts = (frequency (Hz) - 3,800 Hz) / 2,520 Hz/V
+Volts = (frequency [Hz] - 3800 Hz) / 2520 Hz/V
=== THCAD Connections
@@ -423,7 +542,7 @@ Assuming it is connected to a Mesa 7I76E, connect the output to the spindle enco
=== THCAD Initial Testing
-Make sure you have the following lines in your ini file (assuming a Mesa 7I76E):
+Make sure you have the following lines in your INI file (assuming a Mesa 7I76E):
[source,{hal}]
----
@@ -437,9 +556,15 @@ Grab a 9 Volt battery and connect it to I~N~+ and I~N~-.
For a THCAD-10 you can now calculate the expected velocity (26,480 in our hypothetical example).
If you pass this test, then you are ready to configure your LinuxCNC plasma controller.
-=== Which Model THCAD To Use
+=== Which Model THCAD To Use?
-The THCAD-5 is useful if you intend to use it for ohmic sensing. There is no doubt the THCAD-10 is the more flexible device and it is easy to alter the scaling. However, there is one caveat that can come into play with some cheaper plasma cutters with an inbuilt voltage divider. That is, the internal resistors may be sensed by the THCAD as being part of its own external resistance and return erroneous results. For example, the 16:1 divider on the Everlast plasma cutters needs to be treated as 24:1 (and 50:1 becomes 75:1). This is not a problem with more reputable brands (e.g., Thermal Dynamics, Hypertherm, ESAB etc). So if you are seeing lower than expected cutting voltages, it might be preferable to reconfigure the THCAD to read raw arc voltage.
+The THCAD-5 is useful if you intend to use it for ohmic sensing.
+There is no doubt the THCAD-10 is the more flexible device and it is easy to alter the scaling.
+However, there is one caveat that can come into play with some cheaper plasma cutters with an inbuilt voltage divider.
+That is, the internal resistors may be sensed by the THCAD as being part of its own external resistance and return erroneous results.
+For example, the 16:1 divider on the Everlast plasma cutters needs to be treated as 24:1 (and 50:1 becomes 75:1).
+This is not a problem with more reputable brands (e.g., Thermal Dynamics, Hypertherm, ESAB etc).
+So if you are seeing lower than expected cutting voltages, it might be preferable to reconfigure the THCAD to read raw arc voltage.
Remembering that plasma arc voltages are potentially lethal, here are some suggested criteria.
@@ -474,7 +599,10 @@ Some people achieve good results with Inkscape and G-code tools but SheetCam is
== Designing For Noisy Electrical Environments
-Plasma cutting is inherently an extremely hostile and noisy electrical environment. If you have EMI problems things won't work correctly. You might fire the torch and the computer will reboot in a more obvious example, but you can have any number of other odd symptoms. They will pretty much all happen only when the torch is cutting - often when it is first fired.
+Plasma cutting is inherently an extremely hostile and noisy electrical environment.
+If you have EMI problems things won't work correctly.
+You might fire the torch and the computer will reboot in a more obvious example, but you can have any number of other odd symptoms.
+They will pretty much all happen only when the torch is cutting - often when it is first fired.
Therefore, system builders should select components carefully and design from the ground up to cope with this hostile environment to avoid the impact of Electro-Magnetic Interference (EMI).
Failure to do this could result in countless hours of fruitless troubleshooting.
@@ -499,15 +627,23 @@ Tommy Berisha, the master of building plasma machines on a budget says: “If on
== Water Tables
-The minimum water level under the cut level of the torch should be around 40 mm, having space under slats is nice so the water can level and escape during cutting, having a bit of water above the metal plate being cut is really nice as it gets rid of the little bit of dust, running it submerged is the best way but not preferable for systems with part time use as it will corrode the torch. Adding baking soda to the water will keep the table in a nice condition for many years as it does not allow corrosion while the slats are under water and it also reduces the smell of water vapour. Some people use a water reservoir with a compressed air inlet so they can push the water from the reservoir up to the water table on demand and thus allow changes in water levels.
+The minimum water level under the cut level of the torch should be around 40 mm, having space under slats is nice so the water can level and escape during cutting, having a bit of water above the metal plate being cut is really nice as it gets rid of the little bit of dust, running it submerged is the best way but not preferable for systems with part time use as it will corrode the torch.
+Adding baking soda to the water will keep the table in a nice condition for many years as it does not allow corrosion while the slats are under water and it also reduces the smell of water vapour.
+Some people use a water reservoir with a compressed air inlet so they can push the water from the reservoir up to the water table on demand and thus allow changes in water levels.
== Downdraft Tables
-Many commercial tables utilise a down draft design so fans are used to suck air down through the slats to capture fumes and sparks. Often tables are zoned so only a section below the torch is opened to the outgoing vent, often using air rams and air solenoids to open shutters. Triggering these zones is relatively straightforward if you use the axis or joint position from one of the motion pins and the lincurve component to map downdraft zones to the correct output pin.
+Many commercial tables utilise a down draft design so fans are used to suck air down through the slats to capture fumes and sparks.
+Often tables are zoned so only a section below the torch is opened to the outgoing vent, often using air rams and air solenoids to open shutters.
+Triggering these zones is relatively straightforward if you use the axis or joint position from one of the motion pins and the lincurve component to map downdraft zones to the correct output pin.
== Designing For Speed And Acceleration
-In plasma cutting, speed and acceleration are king. The higher the acceleration, the less the machine needs to slow down when negotiating corners. This implies that the gantry should be as light as possible without sacrificing torsional stiffness. A 100 mm x 100 mm x 2 mm aluminium box section has equivalent torsional stiffness to an 80 mm x 80 mm T slot extrusion yet is 62% lighter. So does the convenience of T slots outweigh the additional construction?
+In plasma cutting, speed and acceleration are king.
+The higher the acceleration, the less the machine needs to slow down when negotiating corners.
+This implies that the gantry should be as light as possible without sacrificing torsional stiffness.
+A 100 mm x 100 mm x 2 mm aluminium box section has equivalent torsional stiffness to an 80 mm x 80 mm T slot extrusion yet is 62% lighter.
+So does the convenience of T slots outweigh the additional construction?
== Distance Travelled Per Motor Revolution
@@ -517,15 +653,20 @@ A 5 mm pitch ball screw with a 3:1 or 5:1 reduction drive is ideal for the Z a
== QtPlasmaC LinuxCNC Plasma Configuration
-The link:./qtplasmac.html[QtPlasmaC] which is comprised of a HAL component (plasmac.hal) plus a complete configurations for the QtPlasmaC GUI has received considerable input from many in the LinuxCNC Open Source movement that have advanced the understanding of plasma controllers since about 2015. There has been much testing and development work in getting QtPlasmaC to its current working state. Everything from circuit design to G-code control and configuration has been included. Additionally, QtPlasmaC supports external THC's such as the Proma 150 but really comes into its own when paired with a Mesa controller as this allows the integrator to include the Mesa THCAD voltage to frequency converter which is purpose built to deal with the hostile plasma environment.
+The link:./qtplasmac.html[QtPlasmaC] which is comprised of a HAL component (plasmac.hal) plus a complete configurations for the QtPlasmaC GUI has received considerable input from many in the LinuxCNC Open Source movement that have advanced the understanding of plasma controllers since about 2015.
+There has been much testing and development work in getting QtPlasmaC to its current working state.
+Everything from circuit design to G-code control and configuration has been included.
+Additionally, QtPlasmaC supports external THC's such as the Proma 150 but really comes into its own when paired with a Mesa controller as this allows the integrator to include the Mesa THCAD voltage to frequency converter which is purpose built to deal with the hostile plasma environment.
QtPlasmaC is designed to stand alone and includes the ability to include your cutting charts yet also includes features to be used with a post processor like SheetCam.
-The QtPlasmaC system is now included in Version 2.9 and above of LinuxCNC. Its now quite mature and has been significantly enhanced since the first version of this guide was written. QtPlasmaC will define LinuxCNC's plasma support for many years to come as it includes all of the features a proprietary high end plasma control system at an open source price.
+The QtPlasmaC system is now included in Version 2.9 and above of LinuxCNC.
+Its now quite mature and has been significantly enhanced since the first version of this guide was written.
+QtPlasmaC will define LinuxCNC's plasma support for many years to come as it includes all of the features a proprietary high end plasma control system at an open source price.
== Hypertherm RS485 Control
-Some Hypertherm plasma cutters have a RS485 interface to allow the controller (e.g., LinuxCNC) to set amps.pressure and mode.
+Some Hypertherm plasma cutters have a RS485 interface to allow the controller (e.g., LinuxCNC) to set amps.pressure and mode.
A number of people have used a userspace component written in Python to achieve this.
More recently, QtPlasmaC now supports this interface natively.
Refer to the QtPlasmaC documentation for how to use it.
@@ -538,7 +679,13 @@ When selecting a RS485 interface to use at the PC end, users have reported that
CAM programs (Computer Aided Manufacture) are the bridge between CAD (Computer Aided Design) and the final CNC (Computer Numerical Control) operation. They often include a user configurable post processor to define the code that is generated for a specific machine or dialect of G-code.
-Many LinuxCNC users are perfectly happy with using Inkscape to convert .SVG vector based files to G-code. If you are using a plasma for hobby or home use, consider this option. However, if your needs are more complex, probably the best and most reasonably priced solution is SheetCam. SheetCam supports both Windows and Linux and post processors are available for it including the QtPlasmaC configuration. SheetCam allows you to nest parts over a full sheet of material and allows you to configure toolsets and code snippets to suit your needs. SheetCam post processors are text files written in the Lua programming language and are generally easy to modify to suit your exact requirements. For further information, consult the https://sheetcam.com[SheetCam web site] and their support forum.
+Many LinuxCNC users are perfectly happy with using Inkscape to convert .SVG vector based files to G-code.
+If you are using a plasma for hobby or home use, consider this option.
+However, if your needs are more complex, probably the best and most reasonably priced solution is SheetCam.
+SheetCam supports both Windows and Linux and post processors are available for it including the QtPlasmaC configuration.
+SheetCam allows you to nest parts over a full sheet of material and allows you to configure toolsets and code snippets to suit your needs.
+SheetCam post processors are text files written in the Lua programming language and are generally easy to modify to suit your exact requirements.
+For further information, consult the https://sheetcam.com[SheetCam web site] and their support forum.
Another popular post-processor is included with the popular Fusion360 package but the included post-processors will need some customisation.
diff --git a/docs/src/plasma/qtplasmac.adoc b/docs/src/plasma/qtplasmac.adoc
index 81e27d59f4..f0cc9e4ed2 100644
--- a/docs/src/plasma/qtplasmac.adoc
+++ b/docs/src/plasma/qtplasmac.adoc
@@ -11,8 +11,10 @@
:ngc: {basebackend@docbook:'':ngc}
== Preamble
-
-*Except where noted, this guide assumes the user is using the latest version of QtPlasmaC. Version history can be seen by visiting this https://htmlpreview.github.io/?https://github.com/LinuxCNC/linuxcnc/blob/master/share/qtvcp/screens/qtplasmac/versions.html[link] which will show the latest available version. The installed QtPlasmaC version is displayed in the title bar. See <<qt_update, Update QtPlasmaC>> for information on updating QtPlasmaC.*
+*Except where noted, this guide assumes the user is using the latest version of QtPlasmaC.*
+*Version history can be seen by visiting this https://htmlpreview.github.io/?https://github.com/LinuxCNC/linuxcnc/blob/master/share/qtvcp/screens/qtplasmac/versions.html[link] which will show the latest available version.*
+*The installed QtPlasmaC version is displayed in the title bar.*
+*See <<qt_update,Update QtPlasmaC>> for information on updating QtPlasmaC.*
== License
@@ -138,31 +140,31 @@ Base machine requirements such as limit switches, home switches, etc. are in add
HAL pin name `plasmac.ohmic-enable` +
Connected from a breakout board output to an input to control the ohmic probe's power.
|Breakaway Switch |0, 1, 2 |Digital input; *optional, see info below table:* +
- HAL pin name plasmac.breakaway +
+ HAL pin name `plasmac.breakaway` +
Connected from a breakout board input to a torch breakaway detection switch. +
This signal senses if the torch has broken away from its cradle.
|Torch On |0, 1, 2 |Digital output; *required.* +
- HAL pin name plasmac.torch-on +
+ HAL pin name `plasmac.torch-on` +
Connected from a breakout board output to the torch-on input of the plasma power supply.
This signal is used to control the plasma power supply and start the arc.
|Move Up |2 |Digital input; *optional.* +
- HAL pin name plasmac.move-up +
+ HAL pin name `plasmac.move-up` +
Connected from the up output of the external THC control to a break out board input.
This signal is used to control the Z axis in an upward motion and make necessary corrections to maintain the torch distance from the work piece during cutting.
|Move Down |2 |Digital input; *optional.* +
- HAL pin name plasmac.move-down +
+ HAL pin name `plasmac.move-down` +
Connected from the down output of the external THC control to a break out board input.
This signal is used to control the Z axis in a downward motion and make necessary corrections to maintain the torch distance from the work piece during cutting.
|Scribe Arming |0, 1, 2 |Digital output; *optional.* +
- HAL pin name plasmac.scribe-arm +
+ HAL pin name `plasmac.scribe-arm` +
Connected from a breakout board output to the scribe arming circuit.
This signal is used to place the scribe into position on the work piece .
|Scribe On |0, 1, 2 |Digital output; *optional.* +
- HAL pin name plasmac.scribe-on +
+ HAL pin name `plasmac.scribe-on` +
Connected from a breakout board output to the scribe-on circuit.
This signal is used to turn the scribing device on.
|Laser On |0, 1, 2 |Digital output; *optional.* +
- HAL pin name qtplasmac.laser_on +
+ HAL pin name `qtplasmac.laser_on` +
This signal is used to turn the alignment laser on.
|===
@@ -170,10 +172,13 @@ Only one of either *Float Switch* or *Ohmic Probe* is required. If both are used
If *Ohmic Probe* is used then *Ohmic Probe Enable* is required to be checked on the QtPlasmaC GUI.
-*Breakaway Switch* is not mandatory because the *Float Switch* is treated the same as a breakaway when not probing. If they are two separate switches, and there are not enough inputs on the breakout board, they could be combined and connected as a *Float Switch*.
+*Breakaway Switch* is not mandatory because the *Float Switch* is treated the same as a breakaway when not probing.
+If they are two separate switches, and there are not enough inputs on the breakout board, they could be combined and connected as a *Float Switch*.
[NOTE]
-The minimum I/O requirement for a QtPlasmaC configuration to function are: *Arc Voltage* input OR *Arc OK* input, *Float Switch* input, and *Torch On* output. To reiterate, in this case QtPlasmaC will treat the float switch as a breakaway switch when it is not probing.
+The minimum I/O requirement for a QtPlasmaC configuration to function are:
+*Arc Voltage* input OR *Arc OK* input, *Float Switch* input, and *Torch On* output.
+To reiterate, in this case QtPlasmaC will treat the float switch as a breakaway switch when it is not probing.
[[qt_z-settings]]
=== Recommended Settings:
@@ -295,7 +300,8 @@ It is possible to create a sim configuration using StepConf but it is not possib
[[qt-dependency]]
=== Qt Dependency Errors
-If any Qt dependency errors are encountered while attempting to run the QtPlasmaC configuration, the user may need to run the QtVCP installation script to resolve these issues.
+If any Qt dependency errors are encountered while attempting to run the QtPlasmaC configuration,
+the user may need to run the QtVCP installation script to resolve these issues.
For a package installation (Buildbot) enter the following command in a terminal window:
@@ -316,15 +322,14 @@ The following heights diagram will help the user visualize the different heights
image::images/qtplasmac_heights_diagram.png[width=800,align="center"]
-Click on the <<qt_parameters-tab,Parameters Tab>> to view the *CONFIGURATION* section which shows the user settable parameters. It is necessary to ensure every one of these settings is tailored to the machine.
+Click on the <<qt_parameters-tab,Parameters Tab>> to view the *CONFIGURATION* section which shows the user settable parameters.
+It is necessary to ensure every one of these settings is tailored to the machine.
To set the Z axis DRO relative to the Z axis MINIMUM_LIMIT, the user should perform the following steps.
-It is important to understand that in QtPlasmaC,
-touching off the Z axis DRO has no effect on the Z axis position while running a G-code program.
-These steps simply allow the user to more easily set the probe height as after performing the steps,
-the displayed Z axis DRO value will be relative to Z axis MINIMUM_LIMIT.
+It is important to understand that in QtPlasmaC, touching off the Z axis DRO has no effect on the Z axis position while running a G-code program.
+These steps simply allow the user to more easily set the probe height as after performing the steps, the displayed Z axis DRO value will be relative to Z axis MINIMUM_LIMIT.
-. The user should be familiar with the recommended <<qt_z-settings, Z Axis Settings>>.
+. The user should be familiar with the recommended <<qt_z-settings,Z Axis Settings>>.
. Home the Z axis.
. Ensure there is nothing below the torch then jog the Z axis down until it stops at the Z axis MINIMUM_LIMIT then click the 0 next to the Z axis DRO to *Touch Off* with the Z axis selected to set the Z axis at zero offset. This step only serves to allow the user to more easily visualize and adjust *Probe Height* this value is measured from the Z axis MINIMUM_LIMIT up.
. Home the Z axis again.
@@ -347,21 +352,26 @@ If the machine is equipped with a float switch then the user will need to set th
If the amount of time between the torch contacting the material and when the torch moves up and comes to rest at the Pierce Height seems excessive, see <<qt_probing,the probing section>> for a possible solution.
[IMPORTANT]
-IF USING A *Mesa Electronics THCAD* THEN THE *Voltage Scale* VALUE WAS OBTAINED MATHEMATICALLY. IF THE USER INTENDS TO USE CUT VOLTAGES FROM A MANUFACTURE'S CUT CHART THEN IT WOULD BE ADVISABLE TO DO MEASUREMENTS OF ACTUAL VOLTAGES AND FINE TUNE THE *Voltage Scale* AND *Voltage Offset*.
+IF USING A *Mesa Electronics THCAD* THEN THE *Voltage Scale* VALUE WAS OBTAINED MATHEMATICALLY.
+IF THE USER INTENDS TO USE CUT VOLTAGES FROM A MANUFACTURE'S CUT CHART THEN IT WOULD BE ADVISABLE TO DO MEASUREMENTS OF ACTUAL VOLTAGES AND FINE TUNE THE *Voltage Scale* AND *Voltage Offset*.
[CAUTION]
PLASMA CUTTING VOLTAGES CAN BE LETHAL, IF THE USER IS NOT EXPERIENCED IN DOING THESE MEASUREMENTS GET SOME QUALIFIED HELP.
[[qt_modify-config]]
-== Migrating to QtPlasmac From PlasmaC (Axis or Gmoccapy)
+== Migrating to QtPlasmac From PlasmaC (AXIS or GMOCCAPY)
-There are two methods available to get from a working PlasmaC configuration to a new QtPlasmaC configuration. These methods assume the user is on LinuxCNC v2.9 or later, QtVCP is installed, and all dependency requirements are satisfied.
+There are two methods available to get from a working PlasmaC configuration to a new QtPlasmaC configuration.
+These methods assume the user is on LinuxCNC v2.9 or later, QtVCP is installed, and all dependency requirements are satisfied.
If there are Qt dependency errors, the user should run the <<qt-dependency,QtVCP install script>>.
=== Quick Method
-A quick method to move to QtPlasmaC from PlasmaC (loaded on top of either Axis or Gmoccapy) is to use the plasmac2qt conversion program which will attempt to create a new QtPlasmaC configuration from an existing PlasmaC INI file. This program will convert the user's parameters, settings, and materials from the previous PlasmaC configuration and create a new QtPlasmaC configuration directory in the ~/linuxcnc/configs directory.
+A quick method to move to QtPlasmaC from PlasmaC (loaded on top of either AXIS or GMOCCAPY) is to use the plasmac2qt conversion program,
+which will attempt to create a new QtPlasmaC configuration from an existing PlasmaC INI file.
+This program will convert the user's parameters, settings, and materials from the previous PlasmaC configuration
+and create a new QtPlasmaC configuration directory in the ~/linuxcnc/configs directory.
This methods will keep the original PlasmaC config as a backup with _plasmac and a time stamp appended to the directory name.
@@ -389,12 +399,12 @@ image::images/qtplasmac_plasmac2qt.png[width=500,align="center"]
[width="100%",cols="4,10,6",options="header"]
|===
|Field |Description |Examples
-|INI FILE IN EXISTING PLASMAC CONFIG |This is the INI file of the PlasmaC config that requires migrating.|_<machine_name>_.ini
-|MONITOR ASPECT RATIO |This is the <<qt_formats, aspect ratio format>> for the GUI.|16:9
+|INI FILE IN EXISTING PLASMAC CONFIG |This is the INI file of the PlasmaC config that requires migrating. |_<machine_name>_.ini
+|MONITOR ASPECT RATIO |This is the <<qt_formats,aspect ratio format>> for the GUI. |16:9
|ESTOP |Selects the required Estop type based on the following criteria: +
0 - Estop is an indicator only. +
1 - Estop indicator is hidden. +
- 2 - Estop is a button.|ESTOP:1
+ 2 - Estop is a button. |ESTOP:1
|===
*Optional Setting*
@@ -419,8 +429,7 @@ If the user wishes to change to the new dbounce component then the New Base Conf
=== New Base Config Method
This method to move to QtPlasmaC from PlasmaC (loaded on top of either AXIS or GMOCCAPY) is to use a <<configuring,configuration wizard>> to create a new configuration.
-This method then allows changing the base machine configuration at a later date via the configuration wizard,
-provided that the base INI and base HAL files have not been edited.
+This method then allows changing of the base machine configuration at a later date via the configuration wizard provided that the base INI and base HAL files have not been edited.
This method requires that the user take note of all HAL pins used in the existing config so they can be entered into the configuration wizard.
Any custom HAL commands will also need to be noted and added manually to either the custom.hal file or the custom_postgui.hal file,
@@ -430,8 +439,8 @@ After using the wizard, the user can then run a conversion program (cfg2prefs) t
settings, and materials from the previous PlasmaC configuration to the new QtPlasmaC configuration.
This tool should be used immediately after the user has created a new QtPlasmaC configuration.
-Prior to running this conversion program, it is mandatory that the user have
-both an existing PlasmaC configuration and a new QtPlasmaC configuration.
+Prior to running this conversion program,
+it is mandatory that the user have both an existing PlasmaC configuration and a new QtPlasmaC configuration.
This program WILL overwrite the existing QtPlasmaC preferences and materials files,
and should be used with caution if it is not being run on a new QtPlasmaC configuration.
@@ -599,7 +608,7 @@ After a successful QtPlasmaC installation, the following files are created in th
[width="100%",cols="1,2"]
|===
-|*Filename*|*Function*
+|*Filename* |*Function*
|_<machine_name>_.ini |A configuration file for the machine.
|_<machine_name>_.hal |A HAL for the machine.
|_<machine_name>_.prefs |A configuration file for QtPlasmaC specific parameters and preferences.
@@ -612,7 +621,7 @@ After a successful QtPlasmaC installation, the following files are created in th
|===
[NOTE]
-_<machine_name>_ is whatever name the user entered into the "Machine Name" field of the configuration wizard program
+_<machine_name>_ is whatever name the user entered into the "Machine Name" field of the configuration wizard program.
[NOTE]
Custom commands are allowed in custom.hal and the custom_postgui.hal files as they are not overwritten during updates.
@@ -765,7 +774,7 @@ Exiting or shutting down QtPlasmaC is done by either:
. Click the window shutdown button on the window title bar
. Long press the *POWER* button on the MAIN Tab.
-A shutdown warning can be displayed on every shutdown by checking the *Exit Warning* checkbox on the <<qt_settings-tab, SETTINGS Tab>>.
+A shutdown warning can be displayed on every shutdown by checking the *Exit Warning* checkbox on the <<qt_settings-tab,SETTINGS Tab>>.
[[qt_main-tab]]
=== MAIN Tab
@@ -780,24 +789,24 @@ Some functions/features are only used for particular modes and are not displayed
[width="100%",cols="4,16",options="header"]
|===
-|Name |Description
+|Name |Description
|Material |The top header is clickable in this area to reveal a drop down menu. It is used to manually select the current material cut parameters. If there are no materials in the material file then only the default material will be displayed.
-|VEL:|This displays the actual cut feed rate the table is moving at.
-|FR:|If "View Material" is selected on the <<qt_settings-tab, SETTINGS Tab>>, this displays the currently selected material's Feed Rate.
-|PH:|If "View Material" is selected on the <<qt_settings-tab, SETTINGS Tab>>, this displays the currently selected material's Pierce Height.
-|PD:|If "View Material" is selected on the <<qt_settings-tab, SETTINGS Tab>>, this displays the currently selected material's Pierce Delay.
-|CH:|If "View Material" is selected on the <<qt_settings-tab, SETTINGS Tab>>, this displays the currently selected material's Cut Height.
-|CA:|If "View Material" is selected on the <<qt_settings-tab, SETTINGS Tab>>, and RS485 communications are enabled, this displays the currently selected material's Cut Amperage.
-|T |This button changes the <<sub:qt-preview-views,preview>> to a top down full table view.
-|P |This button changes the <<sub:qt-preview-views,preview>> to an isometric view.
-|Z |This button changes the <<sub:qt-preview-views,preview>> to a top down view.
-|→|This button pans the <<sub:qt-preview-views,preview>> right.
-|←|This button pans the <<sub:qt-preview-views,preview>> left.
-|↑|This button pans the <<sub:qt-preview-views,preview>> up.
-|↓|This button pans the <<sub:qt-preview-views,preview>> down.
-|+|This button zooms the <<sub:qt-preview-views,preview>>.
-|-|This button zooms the <<sub:qt-preview-views,preview>>.
-|C |This button clears the live plot.
+|VEL: |This displays the actual cut feed rate the table is moving at.
+|FR: |If "View Material" is selected on the <<qt_settings-tab,SETTINGS Tab>>, this displays the currently selected material's Feed Rate.
+|PH: |If "View Material" is selected on the <<qt_settings-tab,SETTINGS Tab>>, this displays the currently selected material's Pierce Height.
+|PD: |If "View Material" is selected on the <<qt_settings-tab,SETTINGS Tab>>, this displays the currently selected material's Pierce Delay.
+|CH: |If "View Material" is selected on the <<qt_settings-tab,SETTINGS Tab>>, this displays the currently selected material's Cut Height.
+|CA: |If "View Material" is selected on the <<qt_settings-tab,SETTINGS Tab>>, and RS485 communications are enabled, this displays the currently selected material's Cut Amperage.
+|T |This button changes the <<sub:qt-preview-views,preview>> to a top down full table view.
+|P |This button changes the <<sub:qt-preview-views,preview>> to an isometric view.
+|Z |This button changes the <<sub:qt-preview-views,preview>> to a top down view.
+|→ |This button pans the <<sub:qt-preview-views,preview>> right.
+|← |This button pans the <<sub:qt-preview-views,preview>> left.
+|↑ |This button pans the <<sub:qt-preview-views,preview>> up.
+|↓ |This button pans the <<sub:qt-preview-views,preview>> down.
+|+ |This button zooms the <<sub:qt-preview-views,preview>>.
+|- |This button zooms the <<sub:qt-preview-views,preview>>.
+|C |This button clears the live plot.
|===
[underline]*MACHINE*
@@ -805,10 +814,10 @@ Some functions/features are only used for particular modes and are not displayed
[width="100%",cols="4,16",options="header"]
|===
|Name |Description
-|ESTOP |If ESTOP_TYPE = 0 in the _<machine_name>_.prefs file, this button becomes an indicator of the hardware ESTOP's status only. +
+|ESTOP |If ESTOP_TYPE = 0 in the _<machine_name>_.prefs file, this button becomes an indicator of the hardware E-stop's status only. +
If ESTOP_TYPE = 1 in the _<machine_name>_.prefs file, this button will not be visible. +
-If ESTOP_TYPE = 2 in the _<machine_name>_.prefs file, this button will act as a GUI ESTOP. +
-If ESTOP_TYPE is omitted from the _<machine_name>_.prefs file, this button will default to being an indicator of the hardware ESTOP's status only.
+If ESTOP_TYPE = 2 in the _<machine_name>_.prefs file, this button will act as a GUI E-stop. +
+If ESTOP_TYPE is omitted from the _<machine_name>_.prefs file, this button will default to being an indicator of the hardware E-stop's status only.
|POWER |This button turns the GUI on and allows QtPlasmaC/LinuxCNC to control the hardware. +
Pressing and holding the *POWER* button for longer than two seconds will bring up a dialog to exit the QtPlasmaC application.
|CYCLE START |This button starts the cycle for any loaded G-code file.
@@ -847,7 +856,7 @@ See <<qt_custom-user-buttons,custom user buttons>> for detailed information on c
|MDI |This button places QtPlasmaC into Manual Data Input (MDI) mode which will display the MDI HISTORY and an entry box over top of the G-code window. +
Once pressed, this button will display "MDI CLOSE". +
Pressing *MDI CLOSE* will close the MDI. +
-Please see the <<qt_mdi, MDI>> section for additional MDI information.
+Please see the <<qt_mdi,MDI>> section for additional MDI information.
|OHMIC TEST |This button will enable the Ohmic Probe Enable output signal and if the Ohmic Probe input is sensed, the LED indicator in the SENSOR Panel will light. +
The main purpose of this is to allow a quick test for a shorted torch tip.
|PROBE TEST |This button will initiate a <<qt_probe-test,Probe Test>>.
@@ -912,7 +921,7 @@ For more information, see the <<qt_pm_comms,PowerMax Communications>> section.
[width="100%",cols="4,16",options="header"]
|===
-|Name |Description
+|Name |Description
|FLOAT |Indicates that the float switch is activated.
|OHMIC |Indicates that the probe has sensed the material.
|BREAK |Indicates that the torch breakaway sensor is activated.
@@ -1180,9 +1189,9 @@ This is a visual indicator to the operator only, unless PowerMax communications
|Cut Volts |This sets the cut voltage for the currently selected material.
|Puddle Height |Expressed as a percentage of Pierce Height, this sets the Puddle Jump height for the currently selected material. +
Typically used for thicker materials, Puddle Jump allows the torch to have an intermediate step between Pierce Height and Cut Height. +
-If set, the torch will proceed from Pierce Height to P-Jump Height for a period of time (P-Jump Delay) before proceeding to Cut Height to effectively "jump" over the molten puddle. Refer to the <<qt_initial-setup, Heights Diagram>> diagram for a visual representation.
+If set, the torch will proceed from Pierce Height to P-Jump Height for a period of time (P-Jump Delay) before proceeding to Cut Height to effectively "jump" over the molten puddle. Refer to the <<qt_initial-setup,Heights Diagram>> diagram for a visual representation.
|Puddle Delay |This sets the amount of time (in seconds) the torch will stay at the P-Jump Height before proceeding to Cut Height.
-|Pause At End |This sets the amount of time (in seconds) the torch will stay on at the end of the cut before proceeding with the M5 command to turn off and raise the torch. For more information see <<qt_pause-at-end, Pause At End Of Cut>>.
+|Pause At End |This sets the amount of time (in seconds) the torch will stay on at the end of the cut before proceeding with the M5 command to turn off and raise the torch. For more information see <<qt_pause-at-end,Pause At End Of Cut>>.
|Gas Pressure |This sets the gas pressure for the currently selected material. +
This setting is only valid if PowerMax communications are being used. +
0 = Use the PowerMax's automatic pressure mode.
@@ -1262,7 +1271,7 @@ The custom message can be made multi-line by adding a "\" between lines.
[[qt_button_entries]]
[underline]*USER BUTTON ENTRIES* USERBUTTON
-This section shows the text that appears on the <<qt_custom-user-buttons, Custom User Buttons>> as well as the code associated with the user button.
+This section shows the text that appears on the <<qt_custom-user-buttons,Custom User Buttons>> as well as the code associated with the user button.
User buttons may be changed and the new settings used without restarting LinuxCNC.
The text and/or code may be edited at any time and will be loaded ready for use if the *SAVE* button is clicked.
@@ -1316,7 +1325,7 @@ These files are not required by QtPlasmaC and are safe to delete at any time.
[[qt_statistics-tab]]
=== STATISTICS Tab
-The <<qt_statistics-tab, STATISTICS Tab>> provides statistics to allow for the tracking of consumable wear and job run times.
+The <<qt_statistics-tab,STATISTICS Tab>> provides statistics to allow for the tracking of consumable wear and job run times.
These statistics are shown for the current job as well as the running total.
@@ -1328,7 +1337,7 @@ The *RS485 PMX STATISTICS* panel will be only be displayed if the user has Hyper
This panel will show the *ARC ON TIME* for the PowerMax in hh:mm:ss format.
The *MACHINE LOG* is also displayed on the <<qt_statistics-tab,STATISTICS Tab>>, this log will display any errors and/or important information that occurs during the current LinuxCNC session.
-If the user makes a backup of the configuration from the <<qt_settings-tab, SETTINGS Tab>> then the machine log is also included in the backup.
+If the user makes a backup of the configuration from the <<qt_settings-tab,SETTINGS Tab>> then the machine log is also included in the backup.
image::images/qtplasmac_stats.png[width=800,align="center"]
@@ -1416,7 +1425,7 @@ If the *F* word is used and the *F* word value does not match the cut feed rate
[[qt_material-handling]]
=== Material File
-Material handling uses a material file that was created for the machine configuration when the configuration wizard was ran and allows the user to conveniently store known material settings for easy recall either manually or automatically via G-code. The resulting <<qt_material-file, material file>> is named *<machine_name>_material.cfg*.
+Material handling uses a material file that was created for the machine configuration when the configuration wizard was ran and allows the user to conveniently store known material settings for easy recall either manually or automatically via G-code. The resulting <<qt_material-file,material file>> is named *<machine_name>_material.cfg*.
QtPlasmaC does not require the use of a material file. Instead, the user could change the cut parameters manually from the MATERIAL section of the <<qt_parameters-tab,PARAMETERS Tab>>.
It is also not required to use the automatic material changes.
@@ -1475,12 +1484,12 @@ CUT_MODE = value (only used for PowerMax communications)
It is possible to add new material, delete material, or edit existing material from the <<qt_parameters-tab,PARAMETERS tab.>> It is also possible to achieve this by using <<qt_magic-comments,magic comments>> in a g-Code file.
-The material file may be edited with a text editor while LinuxCNC is running. After any changes have been saved, press *Reload* in the MATERIAL section of the <<qt_parameters-tab, PARAMETERS Tab>> to reload the material file.
+The material file may be edited with a text editor while LinuxCNC is running. After any changes have been saved, press *Reload* in the MATERIAL section of the <<qt_parameters-tab,PARAMETERS Tab>> to reload the material file.
=== Manual Material Handling
For manual material handling, the user would manually select the material from the materials list in the MATERIAL section of the <<qt_parameters-tab,PARAMETERS Tab>> before starting the G-code program.
-In addition to selecting materials with materials list in the MATERIAL section of the <<qt_parameters-tab, PARAMETERS Tab>>, the user could use the MDI to change materials with the following command:
+In addition to selecting materials with materials list in the MATERIAL section of the <<qt_parameters-tab,PARAMETERS Tab>>, the user could use the MDI to change materials with the following command:
[source,{ngc}]
----
@@ -2010,7 +2019,7 @@ When a probe sequence has begun, the `plasmac.ohmic-enable` pin will be set True
The probe will begin moving to the offset position simultaneously with the Z axis moving down to the Probe Height, probing will not commence unless the deployment timer has completed.
It is required that the *Probe Height* in the PROBING frame of the CONFIGURATION section of the <<qt_parameters-tab,PARAMETERS Tab>> is above the top of the material to ensure that the probe is fully offset to the correct X/Y position before the final vertical probe down movement.
-IMPORTANT: PROBE HEIGHT NEEDS TO BE SET ABOVE THE TOP OF THE MATERIAL FOR OFFSET PROBING
+IMPORTANT: PROBE HEIGHT NEEDS TO BE SET ABOVE THE TOP OF THE MATERIAL FOR OFFSET PROBING.
[[qt_cut-types]]
=== Cut Types
@@ -2018,7 +2027,7 @@ IMPORTANT: PROBE HEIGHT NEEDS TO BE SET ABOVE THE TOP OF THE MATERIAL FOR OFFSET
QtPlasmaC allows two different cut modes:
. *NORMAL CUT* - runs the loaded G-code program to pierce then cut.
-. *PIERCE ONLY* - only pierces the material at each cut start position, useful prior to a *NORMAL CUT* on <<qt_thick-materials,thick materials>>
+. *PIERCE ONLY* - only pierces the material at each cut start position, useful prior to a *NORMAL CUT* on <<qt_thick-materials,thick materials>>.
There are two ways of enabling this feature:
@@ -2043,7 +2052,7 @@ QtPlasmaC can utilize G-code commands usually set by a CAM Post Processor (PP) t
There are three methods available for improving the quality of small holes:
. *Velocity Reduction* - <<qt_hole-cutting-velocity-reduction,Reducing the velocity>> to approximately 60% of the *CutFeedRate*.
-. *Arc Dwell (<<qt_pause-at-end, Pause At End>>)* - Keeping the torch on for a short time at the end of the hole while motion is stopped to allow the arc to catch up.
+. *Arc Dwell (<<qt_pause-at-end,Pause At End>>)* - Keeping the torch on for a short time at the end of the hole while motion is stopped to allow the arc to catch up.
. *Over cut* - Turning the torch off at the end of the hole then continue along the path.
[NOTE]
@@ -2223,7 +2232,7 @@ If the machine is equipped with a pendant that can start and stop the spindle pl
[[qt_manual-single-cut]]
[underline]*Manual Single Cut*
-Manual single cut requires that either <<qt_keyboard-shortcuts,keyboard shortcuts>> are enabled in the GUI SETTINGS section of the <<qt_settings-tab, SETTINGS Tab>>,
+Manual single cut requires that either <<qt_keyboard-shortcuts,keyboard shortcuts>> are enabled in the GUI SETTINGS section of the <<qt_settings-tab,SETTINGS Tab>>,
or a custom user button is specified as a <<qt_button-mancut,manual cut>> button.
If the user is using a custom user button then substitute *F9* with *User Button* in the following description.
@@ -2347,7 +2356,7 @@ IMPORTANT: PUDDLE JUMP IS DISABLED DURING CUT RECOVERY
[[qt_run-from-line]]
=== Run From Line
-If the user has the Run From Line option enabled in the GUI SETTINGS section of the <<qt_settings-tab, SETTINGS Tab>> they will have the ability to start from any line in a G-code program via the following methods:
+If the user has the Run From Line option enabled in the GUI SETTINGS section of the <<qt_settings-tab,SETTINGS Tab>> they will have the ability to start from any line in a G-code program via the following methods:
. Clicking any line in the Preview Window
. Clicking any line in the G-code Window
@@ -2520,7 +2529,7 @@ Below is a list of all available keyboard shortcuts in QtPlasmaC.
[NOTE]
All keyboard shortcuts are disabled by default.
-In order to utilize them, *KB Shortcuts* must be enabled in the *GUI SETTINGS* section of the <<qt_settings-tab, SETTINGS Tab>>.
+In order to utilize them, *KB Shortcuts* must be enabled in the *GUI SETTINGS* section of the <<qt_settings-tab,SETTINGS Tab>>.
[width="100%",cols="4,16",options="header"]
|===
@@ -2613,7 +2622,7 @@ The general functions are as follows:
|===
|Name |Description
|Material Drop Down |Allows the user to select the desired material for cutting. +
-If "VIEW MATERIAL" is selected on the <<qt_settings-tab, SETTINGS Tab>>, a visual reference showing key material cut settings will be displayed on the Conversational Preview Window. +
+If "VIEW MATERIAL" is selected on the <<qt_settings-tab,SETTINGS Tab>>, a visual reference showing key material cut settings will be displayed on the Conversational Preview Window. +
Examples are: Feed Rate, Pierce Height, Pierce Delay, Cut Height, and Kerf Width (for Conversational only). Cut Amps will be shown if PowerMax communications are enabled.
|NEW |Removes the current G-code file and load a blank G-code file.
|SAVE |Opens a dialog box allowing the current shape to be saved as a G-code file.
@@ -2844,9 +2853,9 @@ When the error is cleared the program may be resumed.
These errors indicate the corresponding sensor was activated during cutting:
-* *breakaway switch activated program is paused*
-* *float switch activated program is paused*
-* *ohmic probe activated program is paused*
+* *breakaway switch activated, program is paused*
+* *float switch activated, program is paused*
+* *ohmic probe activated, program is paused*
These errors indicate the corresponding sensor was activated before probing commenced:
@@ -2864,11 +2873,11 @@ The Z axis reached the bottom limit before the work piece was detected:
The work piece is too high for any safe rapid removes:
-* *material too high for safe traverse program is paused*
+* *material too high for safe traverse, program is paused*
One of these values in MATERIAL section of the <<qt_parameters-tab,PARAMETERS Tab>> is invalid (For example: if they are set to zero):
-* *invalid pierce height or invalid cut height or invalid cut volts program is paused*
+* *invalid pierce height or invalid cut height or invalid cut volts, program is paused*
No arc has been detected after attempting to start the number of times indicated by *Max Starts* in the ARC frame of the CONFIGURATION section of the <<qt_parameters-tab,PARAMETERS Tab>>:
@@ -2893,11 +2902,11 @@ These errors indicate the move to pierce height would exceed the Z axis maximum
* *pierce height would exceed Z axis maximum safe height condition found while float switch probing*
* *pierce height would exceed Z axis maximum safe height condition found while ohmic probing*
-=== Warning Errors
+=== Warning Messages
-Warning errors will not pause a running program and are informational only.
+Warning messages will not pause a running program and are informational only.
-These errors indicate the corresponding sensor was activated before a probe test commenced:
+These messages indicate the corresponding sensor was activated before a probe test commenced:
* *ohmic probe detected before probing probe test aborted*
* *float switch detected before probing probe test aborted*
@@ -2963,7 +2972,7 @@ If the user wishes to update whenever a new QtPlasmaC version has been pushed, t
There are two ways to modify an existing QtPlasmaC configuration:
-. Running the appropriate <<configuring,configuration wizard>> and loading the conf file saved by the wizard.
+. Running the appropriate <<configuring,configuration wizard>> and loading the .conf file saved by the wizard.
. Manually edit the INI and/or the HAL file of the configuration.
IMPORTANT: Any manual modification to the _<machine_name>_.ini and _<machine_name>_.hal files will not be registered in PnCconf or StepConf.
@@ -2986,7 +2995,7 @@ There are two methods available to apply custom styles:
=== Add A Custom Style
-Adding style changes to the default stylesheet is achieved by creating a file in the <machine_name> configuration directory.
+Adding style changes to the default stylesheet is achieved by creating a file in the _<machine_name>_ configuration directory.
This file MUST be named qtplasmac_custom.qss. Any required style changes are then added to this file.
For example the user may want the arc voltage display in red, a green Torch On LED of a larger size and a larger Torch Enable button.
@@ -3045,7 +3054,7 @@ color5 = #808080
The colors may be expressed in any valid stylesheet format.
The above colors are used for the following widgets. So any custom styling will need to take these into account.
-The colors shown below are the defaults used in QtPlasmaC along with the color name from the <<qt_settings-tab, SETTINGS Tab>>.
+The colors shown below are the defaults used in QtPlasmaC along with the color name from the <<qt_settings-tab,SETTINGS Tab>>.
[width="100%",cols="1,1,2",options="header"]
|===
@@ -3098,17 +3107,18 @@ Preview = #000000
=== Custom Python Code
-It is possible to add custom python code to change some existing functions or to add new ones.
+It is possible to add custom Python code to change some existing functions or to add new ones.
Custom code can be added in two different way, a user command file or a user periodic file.
-A user command file is specified in the DISPLAY section of the _<machine_name>_.ini file and contains python code that is processed during startup.
+A user command file is specified in the DISPLAY section of the _<machine_name>_.ini file and contains Python code that is processed during startup.
[source,{ini}]
----
n USER_COMMAND_FILE = my_custom_code.py
----
-A user periodic file must be named user_periodic.py and must be loated in the machines config directory. This file is processed every cycle (usually 100 ms) and is used for functions that require regular updating.
+A user periodic file must be named user_periodic.py and must be loated in the machines config directory.
+This file is processed every cycle (usually 100 ms) and is used for functions that require regular updating.
== QtPlasmaC Advanced Topics
@@ -3156,7 +3166,7 @@ n Name = PIERCE\&&CUT
Buttons can run the following:
. <<qt_button-cmds,External commands>>
-. <<qt_button-py,External python scripts>>
+. <<qt_button-py,External Python scripts>>
. <<qt_button-code,G-code commands>>
. <<qt_button-toggle,Toggle a HAL pin>>
. <<qt_button-laser,Toggle the alignment laser HAL pin>>
@@ -3186,7 +3196,7 @@ n Code = %halshow
[[qt_button-py]]
[underline]*External Python Scripts*
-To run an external python script, the script name is preceded by a % character and it also requires a .py extension.
+To run an external Python script, the script name is preceded by a % character and it also requires a .py extension.
It is valid to use the ~ character as a shortcut for the users home directory.
[source,{ini}]
@@ -3255,7 +3265,8 @@ The button colors will follow the state of the HAL pin.
After setting the code, upon clicking, the button will invert colors and the HAL pin will invert pin state.
The button will stay "latched" until the button is clicked again, which will return the button to the original colors and the HAL pin to the original pin state.
-There are three <<qt_ext-hal-pin,External HAL Pins>> that are available to toggle as an output, the pin names are `qtplasmac.ext_out_0`, `qtplasmac.ext_out_1`, and `qtplasmac.ext_out_2`. HAL connections to these HAL pins need to be specified in a postgui HAL file as the HAL pins are not available until the QtPlasmac GUI has loaded.
+There are three <<qt_ext-hal-pin,External HAL Pins>> that are available to toggle as an output, the pin names are `qtplasmac.ext_out_0`, `qtplasmac.ext_out_1`, and `qtplasmac.ext_out_2`.
+HAL connections to these HAL pins need to be specified in a postgui HAL file as the HAL pins are not available until the QtPlasmac GUI has loaded.
For toggle-halpin buttons, it is possible for the user to mark the associated HAL pin as being required to be turned "ON" before starting a cut cycle by adding "runcritical" after the HAL pin in the button code. If *TORCH ENABLE* is checked and *CYCLE START* is pressed while the "runcritical" button is not "ON" then the user will receive a dialog warning them as such and asking to CONTINUE or CANCEL.
@@ -3278,7 +3289,9 @@ This code is also able to be used as a multiple command with G-code or external
The button colors will follow the state of the alignment laser HAL pin.
-After setting the code, upon clicking, the button will invert colors and the alignment laser HAL pin will invert pin state. The button will stay "latched" until the button is clicked again, which will return the button to the original colors and the alignment laser HAL pin to the original pin state.
+After setting the code, upon clicking, the button will invert colors and the alignment laser HAL pin will invert pin state.
+The button will stay "latched" until the button is clicked again,
+which will return the button to the original colors and the alignment laser HAL pin to the original pin state.
The following code would allow the user to use a button to invert the current state of the alignment laser HAL bit pin and then move the X and Y axes to the offset for the alignment laser as specified in the _<machine_name>_.prefs file:
@@ -3305,7 +3318,8 @@ The pulse duration is specified in seconds, if the pulse duration is not specifi
The button colors will follow the state of the HAL pin.
-After setting the code, upon clicking the button, the button will invert colors, the HAL pin will invert pin state, and the time remaining will be displayed on the button. The button color and the pin state will stay inverted until the pulse duration timer has completed, which will return the button to the original colors, the HAL pin to the original pin state, and the original button name.
+After setting the code, upon clicking the button, the button will invert colors, the HAL pin will invert pin state, and the time remaining will be displayed on the button.
+The button color and the pin state will stay inverted until the pulse duration timer has completed, which will return the button to the original colors, the HAL pin to the original pin state, and the original button name.
An active pulse can be canceled by clicking the button again.
@@ -3316,7 +3330,8 @@ HAL connections to these HAL pins need to be specified in a postgui HAL file as
.Probe Test
QtPlasmaC will begin a probe and when the material is detected, the Z axis will rise to the Pierce Height currently displayed in the MATERIAL section of the <<qt_parameters-tab,PARAMETERS Tab>>.
-If the user has "View Material" selected in the GUI SETTINGS section of the <<qt_settings-tab, SETTINGS Tab>>, this value will be displayed in the top left corner of the PREVIEW Window next to *PH:*.
+If the user has "View Material" selected in the GUI SETTINGS section of the <<qt_settings-tab,SETTINGS Tab>>,
+this value will be displayed in the top left corner of the PREVIEW Window next to *PH:*.
QtPlasmaC will then wait in this state for the time specified (rounded to no decimal places) before returning the Z axis to the starting position.
An example of a 6 second delay is below. If there is no time specified then the probe time will default to 10 seconds.
@@ -3333,7 +3348,8 @@ HAL connections to this HAL pin needs to be specified in a postgui HAL file as t
[[qt_button-ohmic]]
.Ohmic Test
-QtPlasmaC will enable the Ohmic Probe Enable output signal and if the Ohmic Probe input is sensed, the LED indicator in the SENSOR Panel will light. The main purpose of this is to allow a quick test for a shorted torch tip.
+QtPlasmaC will enable the Ohmic Probe Enable output signal and if the Ohmic Probe input is sensed, the LED indicator in the SENSOR Panel will light.
+The main purpose of this is to allow a quick test for a shorted torch tip.
[source,{ini}]
----
@@ -3408,7 +3424,7 @@ It there is no time specified then it will default to 1 second.
Pulse times with more than one decimal place will be rounded to one decimal place.
Pressing the button again during the countdown will cause the torch to be turned off,
-as will pressing 'Esc' if keyboard shortcuts are enabled in the <<qt_settings-tab, SETTINGS Tab>>.
+as will pressing 'Esc' if keyboard shortcuts are enabled in the <<qt_settings-tab,SETTINGS Tab>>.
If the button is released before the countdown is complete then the torch will turn off at countdown completion,
holding the button on until after the countdown has completed will cause the torch to remain on until the button has been released.
@@ -3449,7 +3465,7 @@ The velocity for the XY movements of the Framing motion can be specified so that
This can be achieved by adding the feed rate (F) as the as the last portion of the button code.
If the feed rate is omitted from the button code, framing motion velocity will default to the feed rate for the currently selected material.
-The following GUI buttons and Keyboard Shortcuts (if enabled in the <<qt_settings-tab, SETTINGS Tab>>) are valid during Framing motion:
+The following GUI buttons and Keyboard Shortcuts (if enabled in the <<qt_settings-tab,SETTINGS Tab>>) are valid during Framing motion:
. Pressing *CYCLE STOP* or the ESC <<qt_keyboard-shortcuts,keyboard shortcut>> - Stops Framing motion.
. Pressing *CYCLE PAUSE* or the SPACE BAR <<qt_keyboard-shortcuts,keyboard shortcut>>- Pauses Framing motion.
@@ -3527,13 +3543,13 @@ Use the following sequence to set the offsets for a laser, camera, scribe, or of
. Place a piece of scrap material under the torch.
. The machine must be homed and idle before proceeding.
-. Open the <<qt_settings-tab, SETTINGS Tab>>.
+. Open the <<qt_settings-tab,SETTINGS Tab>>.
. Click the SET OFFSETS button which opens the Set Peripheral Offsets dialog.
. Click the X0Y0 button to set the torch position to zero.
. Make a mark on the material by one of:
.. Jog the torch down to pierce height then pulse the torch on to make a dimple in the material.
.. Place marking dye on the torch shield then jog the torch down to mark the material.
-. Raise the Z axis so the torch and peripheral are clear of the material
+. Raise the Z axis so the torch and peripheral are clear of the material.
. Jog the X/Y axes so that the peripheral is close to the mark from the torch.
. Click the appropriate button to activate the peripheral.
. Jog the X/Y axes so that the peripheral is centered in the mark from the torch.
@@ -3609,7 +3625,7 @@ The following HAL pins which allow the use of an MPG to control height override
[width="100%",cols="2,3",options="header"]
|===
-|Function |HAL Pin
+|Function |HAL Pin
|Enable MPG height control m|qtplasmac.ext_height_ovr_count_enable
|MPG height change m|qtplasmac.ext_height_ovr_counts
|===
@@ -3619,7 +3635,7 @@ The HAL pin has the identical behaviour of the related custom user button.
[width="50%",cols="1,1",options="header"]
|===
-|User Button Function |HAL Pin
+|User Button Function |HAL Pin
|Probe Test m|qtplasmac.ext_probe
|Torch Pulse m|qtplasmac.ext_pulse
|Ohmic Test m|qtplasmac.ext_ohmic
@@ -3720,10 +3736,10 @@ setp plasmac.zero-window 5
=== Tuning Void Sensing
-In addition to the *Void Slope* setting in the <<qt_parameters-tab,PARAMETERS Tab>> there are two HAL pins to aid in the fine tuning of void anti-dive. These HAL pins are:
+In addition to the *Void Slope* setting in the <<qt_parameters-tab,PARAMETERS Tab>> there are two HAL pins to aid in the fine tuning of void anti-dive.
+These HAL pins are:
- *plasmac.void-on-cycles* which is the number of times the slope rate needs to be exceeded to activate void anti-dive. The default is 2.
-
- *plasmac.void-off-cycles* which is the number of cycles without the slope rate being exceeded to deactivate void anti-dive. The default is 10.
The following example would set the number of on cycles required to 3:
@@ -3765,13 +3781,13 @@ setp qtplasmac.tabs_always_enabled 1
[WARNING]
====
-It is the responsibility of the operator to ensure that the machine is equipped with a suitable, working hardware ESTOP.
+It is the responsibility of the operator to ensure that the machine is equipped with a suitable, working hardware E-stop.
If using only a touchscreen to navigate the QtPlasmaC GUI, there is no way to stop automated machine motion on any tab but the MAIN tab.
====
=== Override Jog Inhibit Via Z+ Jog
-It is possible to override the jog inhibit by using the GUI or keyboard to jog in the Z+ direction rather than checking the Override Jog box on the <<qt_settings-tab, SETTINGS Tab>>.
+It is possible to override the jog inhibit by using the GUI or keyboard to jog in the Z+ direction rather than checking the Override Jog box on the <<qt_settings-tab,SETTINGS Tab>>.
This is done by changing the following preference to *True* in the *[GUI_OPTIONS]* of the _<machine_name>_.prefs file in the <machine_name> folder:
@@ -3788,34 +3804,34 @@ The different states QtPlasmaC could encounter are as follows:
[width="100%",cols="1,4,12",options="header"]
|===
|State |Name |Description
-|0 |IDLE |idle and waiting for a start command
-|1 |PROBE_HEIGHT |move down to probe height
-|2 |PROBE_DOWN |probe down until material sensed
-|3 |PROBE_UP |probe up until material not sensed, this sets the zero height
-|4 |ZERO_HEIGHT |not used at present
-|5 |PIERCE_HEIGHT |move up to pierce height
-|6 |TORCH_ON |turn the torch on
-|7 |ARC_OK |wait until arc ok detected
-|8 |PIERCE_DELAY |wait for pierce delay time
-|9 |PUDDLE_JUMP |xy motion begins, move to puddle jump height
-|10 |CUT_HEIGHT |move to cut height
-|11 |CUT_MODE_01 |cutting in either mode 0 or mode 1
-|12 |CUT_MODE_2 |cutting in mode 2
-|13 |PAUSE_AT_END |pause motion at end of cut
-|14 |SAFE_HEIGHT |move to safe height
-|15 |MAX_HEIGHT |move to maximum height
-|16 |END_CUT |end the current cut
-|17 |END_JOB |end the current job
-|18 |TORCHPULSE |a torch pulse is active
-|19 |PAUSED_MOTION |cut recovery motion is active while paused
-|20 |OHMIC_TEST |an ohmic test is active
-|21 |PROBE_TEST |a probe test is active
-|22 |SCRIBING |a scribing job is active
-|23 |CONSUMABLE_CHANGE_ON |move to consumable change coordinates
-|24 |CONSUMABLE_CHANGE_OFF |return from consumable change coordinates
-|25 |CUT_RECOVERY_ON |cut recovery is active
-|26 |CUT_RECOVERY_OFF |cut recovery is deactivated
-|27 |DEBUG
+|0 m|IDLE |idle and waiting for a start command
+|1 m|PROBE_HEIGHT |move down to probe height
+|2 m|PROBE_DOWN |probe down until material sensed
+|3 m|PROBE_UP |probe up until material not sensed, this sets the zero height
+|4 m|ZERO_HEIGHT |not used at present
+|5 m|PIERCE_HEIGHT |move up to pierce height
+|6 m|TORCH_ON |turn the torch on
+|7 m|ARC_OK |wait until arc ok detected
+|8 m|PIERCE_DELAY |wait for pierce delay time
+|9 m|PUDDLE_JUMP |xy motion begins, move to puddle jump height
+|10 m|CUT_HEIGHT |move to cut height
+|11 m|CUT_MODE_01 |cutting in either mode 0 or mode 1
+|12 m|CUT_MODE_2 |cutting in mode 2
+|13 m|PAUSE_AT_END |pause motion at end of cut
+|14 m|SAFE_HEIGHT |move to safe height
+|15 m|MAX_HEIGHT |move to maximum height
+|16 m|END_CUT |end the current cut
+|17 m|END_JOB |end the current job
+|18 m|TORCHPULSE |a torch pulse is active
+|19 m|PAUSED_MOTION |cut recovery motion is active while paused
+|20 m|OHMIC_TEST |an ohmic test is active
+|21 m|PROBE_TEST |a probe test is active
+|22 m|SCRIBING |a scribing job is active
+|23 m|CONSUMABLE_CHANGE_ON |move to consumable change coordinates
+|24 m|CONSUMABLE_CHANGE_OFF |return from consumable change coordinates
+|25 m|CUT_RECOVERY_ON |cut recovery is active
+|26 m|CUT_RECOVERY_OFF |cut recovery is deactivated
+|27 m|DEBUG
|===
The DEBUG state is for testing purposes only and will not normally be encountered.
@@ -3849,7 +3865,7 @@ Example showing enabling the Hypertherm PowerMax Communications on USB0:
Port = /dev/ttyusb0
----
-If the user is unsure of the name of the port, there is a python script in the configuration directory
+If the user is unsure of the name of the port, there is a Python script in the configuration directory
that will show all available ports and can also be used to test communications with the plasma unit prior to enabling this feature in the QtPlasmaC GUI.
To use the test script follow these instructions:
@@ -3875,14 +3891,14 @@ The connection can be validated by observing the PowerMax display.
To switch the PowerMax back to local mode the user can either:
-. Disable PowerMax Comms from the <<qt_main-tab, MAIN Tab>>
+. Disable PowerMax Comms from the <<qt_main-tab,MAIN Tab>>
. Close LinuxCNC which will put the PowerMax into local mode during shutdown.
. Turn the PowerMax off for 30 seconds and then power it back on.
TIP: If PowerMax communications is active then selecting <<qt_mesh-mode,Mesh Mode>> will automatically select CPA mode on the PowerMax unit.
[NOTE]
-To use the PowerMax communications feature it is necessary to have the python pyserial module installed. +
+To use the PowerMax communications feature it is necessary to have the Python pyserial module installed. +
If pyserial is not installed an error message will be displayed.
To install pyserial, enter the following command into a terminal window:
@@ -3905,7 +3921,7 @@ The *$* indicates a terminal prompt.
All language files are kept in ~/linuxcnc-dev/share/screens/qtplasmac/languages.
-The qtplasmac.py file is a python version of the GUI file used for translation purposes.
+The qtplasmac.py file is a Python version of the GUI file used for translation purposes.
The .ts files are the translation source files for the translations.
These are the files that require creating/editing for each language.
@@ -3929,7 +3945,7 @@ Change to the languages directory:
$ cd ~/linuxcnc-dev/share/qtvcp/screens/qtplasmac/languages
----
-If any text changes have been made to the GUI then run the following to update the GUI python file:
+If any text changes have been made to the GUI then run the following to update the GUI Python file:
----
$ pyuic5 ../qtplasmac.ui > qtplasmac.py
----
@@ -4005,68 +4021,68 @@ There are some sample G-code files in the ~/linuxcnc/nc_files/examples/plasmac d
[width="100%",cols="1,2",options="header"]
|===
|Description |Code
-|Begin <<qt_multi-tool,cut>> |M3 $0 S1
-|End <<qt_multi-tool,cut>> |M5 $0
-|Begin <<qt_scribe,scribe>> |M3 $1 S1
-|End <<qt_scribe,scribe>> |M5 $1
-|Begin <<qt_spotting,center spot>> |M3 $2 S1
-|End <<qt_spotting,center spot>> |M5 $2
-|End all the above |M5 $-1
-|Select a <<qt_material-handling,material>> |M190 P__n__ +
+|Begin <<qt_multi-tool,cut>> m|M3 $0 S1
+|End <<qt_multi-tool,cut>> m|M5 $0
+|Begin <<qt_scribe,scribe>> m|M3 $1 S1
+|End <<qt_scribe,scribe>> m|M5 $1
+|Begin <<qt_spotting,center spot>> m|M3 $2 S1
+|End <<qt_spotting,center spot>> m|M5 $2
+|End all the above. m|M5 $-1
+|Select a <<qt_material-handling,material>>. m|`M190 P`__n__ +
_n_ denotes the material number.
-|Wait for <<qt_material-handling,material>> change confirmation |M66 P3 L3 Qn +
-_n_ is delay time (in seconds). +
+|Wait for <<qt_material-handling,material>> change confirmation. |`M66 P3 L3 Q`__n __+
+_n_ is delay time (in seconds).
This value may need to be increased for very large material files.
-|Set feed rate from <<qt_material-handling,material>> |F#<_hal[plasmac.cut-feed-rate]>
-|Enable <<qt_ignore-ok,Ignore Arc OK>> |M62 P1 (synchronized with motion) +
- M64 P1 (immediate)
-|Disable <<qt_ignore-ok,Ignore Arc OK>> |M63 P1 (synchronized with motion) +
- M65 P1 (immediate)
-|Disable <<qt_thc,THC>> |M62 P2 (synchronized with motion) +
- M64 P2 (immediate)
-|Enable <<qt_thc,THC>> |M63 P2 (synchronized with motion) +
- M65 P2 (immediate)
-|Disable <<qt_overcut,Torch>> |M62 P3 (synchronized with motion) +
- M64 P3 (immediate)
-|Enable <<qt_overcut,Torch>> |M63 P3 (synchronized with motion) +
- M65 P3 (immediate)
-|Set <<qt_velocity_thc,velocity>> to a percentage of feed rate |M67 E3 Qn (synchronized with motion) +
-M68 E3 Qn (immediate) +
+|Set feed rate from <<qt_material-handling,material>>. m|F#<_hal[plasmac.cut-feed-rate]>
+|Enable <<qt_ignore-ok,Ignore Arc OK>> |`M62 P1` (synchronized with motion) +
+`M64 P1` (immediate)
+|Disable <<qt_ignore-ok,Ignore Arc OK>> |`M63 P1` (synchronized with motion) +
+`M65 P1` (immediate)
+|Disable <<qt_thc,THC>> |`M62 P2` (synchronized with motion) +
+`M64 P2` (immediate)
+|Enable <<qt_thc,THC>> |`M63 P2` (synchronized with motion) +
+`M65 P2` (immediate)
+|Disable <<qt_overcut,Torch>> |`M62 P3` (synchronized with motion) +
+`M64 P3` (immediate)
+|Enable <<qt_overcut,Torch>> |`M63 P3` (synchronized with motion) +
+`M65 P3` (immediate)
+|Set <<qt_velocity_thc,velocity>> to a percentage of feed rate. |`M67 E3 Q`__n__ (synchronized with motion) +
+`M68 E3 Q`__n__ (immediate) +
_n_ is the percentage to set +
10 is the minimum, below this will be set to 100% +
100 is the maximum, above this will be set to 100% +
*It is recommended to have M68 E3 Q0 in both the preamble and postamble.*
-|Cutter <<qt_cutter-compensation,compensation>> - left of path |G41.1 D#<_hal[plasmac.kerf-width]>
-|Cutter <<qt_cutter-compensation,compensation>> - right of path |G42.1 D#<_hal[plasmac.kerf-width]>
-|Cutter <<qt_cutter-compensation,compensation>> off |G40 +
-*Note that M62 through M68 are invalid while cutter compensation is on*
-|Cut <<qt_hole-cutting,holes>> at 60% feed rate |#<holes> = 1 +
+|Cutter <<qt_cutter-compensation,compensation>> - left of path m|G41.1 D#<_hal[plasmac.kerf-width]>
+|Cutter <<qt_cutter-compensation,compensation>> - right of path m|G42.1 D#<_hal[plasmac.kerf-width]>
+|Cutter <<qt_cutter-compensation,compensation>> off |`G40` +
+*Note that M62 through M68 are invalid while cutter compensation is on.*
+|Cut <<qt_hole-cutting,holes>> at 60% feed rate |`#<holes> = 1` +
for holes less than 32 mm (1.26") diameter
-|Cut <<qt_hole-cutting,holes>> at 60% feed rate, turn torch off at hole end, continue hole path for over cut |#<holes> = 2 +
+|Cut <<qt_hole-cutting,holes>> at 60% feed rate, turn torch off at hole end, continue hole path for over cut. |`#<holes> = 2` +
for holes less than 32 mm (1.26") diameter +
over cut length = 4 mm (0.157")
-|Cut <<qt_hole-cutting,holes>> and arcs at 60% feed rate |#<holes> = 3 +
+|Cut <<qt_hole-cutting,holes>> and arcs at 60% feed rate. |`#<holes> = 3` +
for holes less than 32 mm (1.26") diameter +
for arcs less than 16 mm (0.63") radius
-|Cut <<qt_hole-cutting,holes>> and arcs at 60% feed rate, turn torch off at hole end, continue hole path for over cut |#<holes> = 4 +
+|Cut <<qt_hole-cutting,holes>> and arcs at 60% feed rate, turn torch off at hole end, continue hole path for over cut. |`#<holes> = 4` +
for holes less than 32 mm (1.26") diameter +
for arcs less than 16 mm (0.63") radius +
over cut length = 4 mm (0.157")
|Specify <<qt_hole-cutting,hole>> diameter for +
- #<holes> = 1-4 |#<h_diameter> = _n_ +
+ #<holes> = 1-4. |`#<h_diameter> =` _n_ +
(_n_ is the diameter, use the same units system as the rest of the G-code file)
|Specify <<qt_hole-cutting,hole>> velocity for +
- #<holes>=1-4 |#<h_velocity> = _n_ +
+ #<holes>=1-4. |`#<h_velocity> =` _n_ +
(_n_ is the percentage, set the percentage of the current feed rate)
-|Specify <<qt_overcut,over cut>> length |#<oclength> = _n_ +
- (_n_ is the length, use the same units system as the rest of the G-code file)
-|Specify <<qt_cut-types,pierce-only>> mode |#<pierce-only> = _n_ +
+|Specify <<qt_overcut,over cut>> length. |`#<oclength> =` _n_ +
+(_n_ is the length, use the same units system as the rest of the G-code file)
+|Specify <<qt_cut-types,pierce-only>> mode. |`#<pierce-only> =` _n_ +
(_n_ is the mode, 0=normal cut mode, 1=pierce only mode)
|Create or edit materials. +
- options: +
- 0 - Create temporary default +
- 1 - Add if not existing +
- 2 - Overwrite if existing else add new |mandatory parameters: +
+Options: +
+0 - Create temporary default +
+1 - Add if not existing +
+2 - Overwrite if existing else add new |mandatory parameters: +
(o=<option>, nu=<__nn__>, na=<__ll__>, ph=<__nn__>, pd=<__nn__>, ch=<__nn__>, fr=<__nn__>) +
optional parameters: +
(kw=<__nn__>, th=<__nn__>, ca=<__nn__>, cv=<__nn__>, pe=<__nn__>, gp=<__nn__>, cm=<__nn__>, jh=<__nn__>, jd=<__nn__>)
@@ -4078,17 +4094,17 @@ optional parameters: +
[width="100%",cols="1,2",options="header"]
|===
|Description |Example
-|Select material and do a normal cut |M190 P3 +
+|Select material and do a normal cut m|M190 P3 +
M66 P3 L3 Q1 +
F#<_hal[plasmac.cut-feed-rate]> +
M3 $0 S1 +
. +
. +
M5 $0
-|Set velocity to 100% of CutFeedRate |M67 E3 Q0 or M67 E3 Q100
-|Set velocity to 60% of CutFeedRate |M67 E3 Q60
-|Set velocity to 40% of CutFeedRate |M67 E3 Q40
-|Cut a hole with 60% reduced speed using velocity setting |G21 (metric) +
+|Set velocity to 100% of CutFeedRate m|M67 E3 Q0 or M67 E3 Q100
+|Set velocity to 60% of CutFeedRate m|M67 E3 Q60
+|Set velocity to 40% of CutFeedRate m|M67 E3 Q40
+|Cut a hole with 60% reduced speed using velocity setting m|G21 (metric) +
G64 P0.05 +
M52 P1 (allow paused motion) +
F#<_hal[plasmac.cut-feed-rate]> +
@@ -4154,7 +4170,7 @@ G3 I10 (the hole) +
M5 $0 (end cut) +
G0 X0 Y0 +
M2 (end job)
-|Select scribe and select torch at end of scribing |. +
+|Select scribe and select torch at end of scribing m|. +
. +
M52 P1 (paused motion on) +
F#<_hal[plasmac.cut-feed-rate]> +
@@ -4180,7 +4196,7 @@ M5 $2 (spotting off) +
G0 X0 Y0 +
G90 +
M2
-|Create temporary default material |(o=0, nu=2, na=5mm Mild Steel 40A, ph=3.1, pd=0.1, ch=0.75, fr=3000)
+|Create temporary default material m|(o=0, nu=2, na=5mm Mild Steel 40A, ph=3.1, pd=0.1, ch=0.75, fr=3000)
|Edit material, if not existing create a new one |(o=2, nu=2, na=5mm Mild Steel 40A, ph=3.1, pd=0.1, ch=0.75, fr=3000, kw=1.0)
|===
@@ -4214,7 +4230,6 @@ Symptoms may include random torch raises or dives during otherwise stable cuttin
Located on the rear of the THCAD is a calibration sticker showing:
----
-
THCAD-nnn
0V 121.1 kHz
@@ -4254,7 +4269,8 @@ _THCAD-5 or THCAD-10_
If connecting to a plasma CNC port then the divider ratio is selected from the plasma machine. A common ratio used is 20:1.
-If connecting to the plasma machines full arc voltage then a common setup for a THCAD-10 is to use a 1 MΩ; resistor from arc negative to THCAD negative and a 1 MΩ; resistor from arc positive to THCAD positive.
+If connecting to the plasma machines full arc voltage then a common setup for a THCAD-10 is to use a 1 MΩ resistor from arc negative to THCAD negative
+and a 1 MΩ resistor from arc positive to THCAD positive.
The divider ratio is obtained by:
----
@@ -4318,7 +4334,8 @@ is to mount a reed relay inside a non-conductive tube and wrap and secure three
This assembly will now act as a relay that will switch on when current is flowing through the work lead which only occurs when a cutting arc has been established.
-This will require that QtPlasmaC be operated in Mode 1 rather than Mode 0. See the <<qt_mode,QtPlasmaC Modes>> sections for more information.
+This will require that QtPlasmaC be operated in Mode 1 rather than Mode 0.
+See the <<qt_mode,QtPlasmaC Modes>> sections for more information.
image::images/qtplasmac_reed_arc_ok.png[width=600,align="center"]
@@ -4327,7 +4344,7 @@ image::images/qtplasmac_reed_arc_ok.png[width=600,align="center"]
image::images/qtplasmac_relay_contact.png[width=600,align="center"]
-A full description is at <<qt-contact-load,Contact Load>>
+A full description is at <<qt-contact-load,Contact Load>>.
== Known Issues
@@ -4340,7 +4357,8 @@ QtPlasmaC uses this disabling feature by default for all keys only when the <<qt
with the following exceptions when autorepeat is allowed with the <<qt_main-tab,MAIN Tab>> visible:
G-code editor is active, MDI is active. When QtPlasmaC is shut down, the Operating System's autorepeat feature will be enabled for all keys.
-If the user wishes to prevent QtPlasmaC from changing the Operating System's autorepeat settings, enter the following in the *[GUI_OPTIONS]* section of the _<machine_name>_.prefs file:
+If the user wishes to prevent QtPlasmaC from changing the Operating System's autorepeat settings,
+enter the following in the *[GUI_OPTIONS]* section of the _<machine_name>_.prefs file:
[source,{ini}]
----
diff --git a/docs/src/remap/remap.adoc b/docs/src/remap/remap.adoc
index 5c3fc42e33..4b3b03bd19 100644
--- a/docs/src/remap/remap.adoc
+++ b/docs/src/remap/remap.adoc
@@ -22,40 +22,31 @@ By 'remapping codes' we mean one of the following:
The set of codes (M,G,T,S,F) currently understood by the RS274NGC
interpreter is fixed and cannot be extended by configuration options.
-In particular, some of these codes implement a fixed sequence of steps
-to be executed. While some of these, like M6, can be moderately
-configured by activating or skipping some of these steps through INI
-file options, overall the behavior is fairly rigid. So - if your
-are happy with this situation, then this manual section is not for you.
-
-In many cases, this means that supporting a non 'out of the box'
-configuration or machine is either cumbersome or impossible, or
-requires resorting to changes at the 'C/C\+\+' language level. The latter
-is unpopular for good reasons - changing internals requires in-depth
-understanding of interpreter internals, and moreover brings its own
-set of support issues. While it is conceivable that certain patches
-might make their way into the main LinuxCNC distribution, the result of
-this approach is a hodge-podge of special-case solutions.
+In particular, some of these codes implement a fixed sequence of steps to be executed.
+While some of these, like M6, can be moderately configured by activating or skipping some of these steps through INI file options,
+overall the behavior is fairly rigid.
+So - if your are happy with this situation, then this manual section is not for you.
+
+In many cases, this means that supporting a non 'out of the box' configuration or machine is either cumbersome or impossible,
+or requires resorting to changes at the 'C/C\+\+' language level.
+The latter is unpopular for good reasons - changing internals requires in-depth understanding of interpreter internals,
+and moreover brings its own set of support issues.
+While it is conceivable that certain patches might make their way into the main LinuxCNC distribution,
+the result of this approach is a hodge-podge of special-case solutions.
A good example for this deficiency is tool change support in LinuxCNC:
While random tool changers are well supported, it is next to impossible
to reasonably define a configuration for a manual-tool change machine
-with, for example, an automatic tool length offset switch being
-visited after a tool change, and offsets set accordingly. Also, while a
-patch for a very specific rack tool changer exists, it has not found
-its way back into the main code base.
-
-However, many of these things may be fixed by using an O-word
-procedure instead of a built in code - whenever the - insufficient -
-built in code is to be executed, call the O-word procedure
-instead. While possible, it is cumbersome - it requires source-editing
-of NGC programs, replacing all calls to the deficient code by a an
-O-word procedure call.
-
-In its simplest form, a remapped code isn't much more than a
-spontaneous call to an O-word procedure. This happens behind the scenes -
-the procedure is visible at the configuration level, but not at the
-NGC program level.
+with, for example, an automatic tool length offset switch being visited after a tool change, and offsets set accordingly.
+Also, while a patch for a very specific rack tool changer exists, it has not found its way back into the main code base.
+
+However, many of these things may be fixed by using an O-word procedure instead of a built in code -
+whenever the - insufficient - built in code is to be executed, call the O-word procedure instead.
+While possible, it is cumbersome - it requires source-editing of NGC programs,
+replacing all calls to the deficient code by a an O-word procedure call.
+
+In its simplest form, a remapped code isn't much more than a spontaneous call to an O-word procedure.
+This happens behind the scenes - the procedure is visible at the configuration level, but not at the NGC program level.
Generally, the behavior of a remapped code may be defined in the following ways:
@@ -65,17 +56,15 @@ Generally, the behavior of a remapped code may be defined in the following ways:
.How to glue things together
M- and G-codes, and O-words subroutine calls have some fairly different syntax.
-O-word procedures, for example, take positional parameters
-with a specific syntax like so:
+O-word procedures, for example, take positional parameters with a specific syntax like so:
[source,{ngc}]
---------------------------------------------------------------------
o<test> call [1.234] [4.65]
---------------------------------------------------------------------
-whereas M- or G-codes typically take required or optional 'word'
-parameters. For instance, G76 (threading) requires the P,Z,I,J and K
-words, and optionally takes the R,Q,H, E and L words.
+whereas M- or G-codes typically take required or optional 'word' parameters.
+For instance, G76 (threading) requires the P,Z,I,J and K words, and optionally takes the R,Q,H, E and L words.
So it isn't simply enough to say 'whenever you encounter code X, please
call procedure Y' - at least some checking and conversion of parameters
@@ -409,7 +398,7 @@ code does not receive any parameters from the block.
It will ignore any extra parameters present.
Note that RS274NGC rules still apply - for instance you may use axis
-words (eg X,Y,Z) only in the context of a G-code.
+words (e.g. X,Y,Z) only in the context of a G-code.
Axis words may also only be used if the axis is enabled.
If only XYZ are enabled, ABCUVW will not be available to be used in argspec.
@@ -421,23 +410,18 @@ Words FST should not be used if this behavior is not desired.
Words DEIJKPQR have no predefined function and are recommended for use as argspec parameters.
`ABCDEFHIJKPQRSTUVWXYZ`::
- Defines a required word parameter: an uppercase letter specifies that
- the corresponding word *must* be present in the current block.
+ Defines a required word parameter: an uppercase letter specifies that the corresponding word *must* be present in the current block.
The word`s value will be passed as a local named parameter with a corresponding name.
If the `@` character is present in the argspec, it will be passed as positional parameter, see below.
`abcdefhijkpqrstuvwxyz`::
- Defines an optional word parameter: a lowercase letter specifies that
- the corresponding word *may* be present in the current block.
+ Defines an optional word parameter: a lowercase letter specifies that the corresponding word *may* be present in the current block.
If the word is present, the word's value will be passed as a local named parameter.
- If the `@` character is present in the argspec, it will be passed as positional parameter,
- see below.
+ If the `@` character is present in the argspec, it will be passed as positional parameter, see below.
`@`::
- The `@` (at-sign) tells argspec to pass words as positional parameters,
- in the order defined following the `@` option.
- Note that when using positional parameter passing,
- a procedure cannot tell whether a word was present or not, see example below.
+ The `@` (at-sign) tells argspec to pass words as positional parameters, in the order defined following the `@` option.
+ Note that when using positional parameter passing, a procedure cannot tell whether a word was present or not, see example below.
TIP: this helps with packaging existing NGC procedures as remapped codes.
Existing procedures do expect positional parameters.
@@ -485,9 +469,9 @@ o<m400> endsub
M2
----------------------------------------------------------------------------------
-- executing `M400` will fail with the message `user-defined M400: missing: P`
-- executing `M400 P123` will display `P word=123.000000`
-- executing `M400 P123 Q456` will display `P word=123.000000` and `Q word set: 456.000000`
+- Executing `M400` will fail with the message `user-defined M400: missing: P`.
+- Executing `M400 P123` will display `P word=123.000000`.
+- Executing `M400 P123 Q456` will display `P word=123.000000` and `Q word set: 456.000000`
.Example for positional parameter passing to NGC procedures
@@ -505,12 +489,11 @@ o<m410> endsub
M2
----------------------------------------------------------------------------------
-- executing `M410 P10` will display `m410.ngc: [1]=10.000000 [2]=0.000000`
-- executing `M410 P10 Q20` will display `m410.ngc: [1]=10.000000 [2]=20.000000`
+- Executing `M410 P10` will display `m410.ngc: [1]=10.000000 [2]=0.000000`.
+- Executing `M410 P10 Q20` will display `m410.ngc: [1]=10.000000 [2]=20.000000`.
-NOTE: you lose the capability to distinguish more than one optional
-parameter word, and you cannot tell whether an optional parameter was
-present but had the value 0, or was not present at all.
+NOTE: you lose the capability to distinguish more than one optional parameter word,
+and you cannot tell whether an optional parameter was present but had the value 0, or was not present at all.
.Simple example for named parameter passing to a Python function
@@ -545,14 +528,12 @@ Try this with out with:
You'll notice the gradual introduction of the embedded Python
environment - see <<remap:programming-embedded-python,here>> for details.
Note that with Python remapping functions, it make no sense to have Python
-prolog or epilog functions since it's executing a Python function in
-the first place.
+prolog or epilog functions since it's executing a Python function in the first place.
.Advanced example: Remapped codes in pure Python
-The `interpreter` and `emccanon` modules expose most of the Interpreter
-and some Canon internals, so many things which so far required coding in
-'C/C\+\+' can be now be done in Python.
+The `interpreter` and `emccanon` modules expose most of the Interpreter and some Canon internals,
+so many things which so far required coding in 'C/C\+\+' can be now be done in Python.
The following example is based on the `nc_files/involute.py` script -
but canned as a G-code with some parameter extraction and checking.
@@ -635,18 +616,13 @@ The examples described so far can be found in 'configs/sim/axis/remap/getting-st
The minimal prerequisites for using `REMAP` statements are as follows:
-- the Python plug in must be activated by specifying a
- `[PYTHON]TOPLEVEL=<path-to-toplevel-script>` in the INI file.
-- the toplevel script needs to import the `remap` module, which can be
- initially empty, but the import needs to be in place.
-- The Python interpreter needs to find the remap.py module above, so
- the path to the directory where your Python modules live needs to be
- added with `[PYTHON]PATH_APPEND=<path-to-your-local-Python-directory>`
-- Recommended: import the `stdglue` handlers in the `remap` module. In
- this case Python also needs to find `stdglue.py` - we just copy it
- from the distribution so you can make local changes as
- needed. Depending on your installation the path to `stdglue.py` might
- vary.
+- The Python plug in must be activated by specifying a `[PYTHON]TOPLEVEL=<path-to-toplevel-script>` in the INI file.
+- The toplevel script needs to import the `remap` module, which can be initially empty, but the import needs to be in place.
+- The Python interpreter needs to find the remap.py module above, so the path to the directory
+ where your Python modules live needs to be added with `[PYTHON]PATH_APPEND=<path-to-your-local-Python-directory>`
+- Recommended: import the `stdglue` handlers in the `remap` module.
+ In this case Python also needs to find `stdglue.py` - we just copy it from the distribution so you can make local changes as needed.
+ Depending on your installation the path to `stdglue.py` might vary.
Assuming your configuration lives under `/home/user/xxx` and the INI file is `/home/user/xxx/xxx.ini`,
execute the following commands.
@@ -683,22 +659,17 @@ $ linuxcnc xxx.ini
=== Overview
If you are unfamiliar with LinuxCNC internals, first read the
-<<remap:how-tool-change-currently-works,How tool change currently works>>
-section (dire but necessary).
+<<remap:how-tool-change-currently-works,How tool change currently works>> section (dire but necessary).
Note than when remapping an existing code, we completely disable
-<<remap:interpreter-action-on-m6,this codes' built in functionality>>
-of the interpreter.
+<<remap:interpreter-action-on-m6,this codes' built in functionality>> of the interpreter.
-So our remapped code will need to do a bit more
-than just generating some commands to move the machine as we like - it
-will also need to replicate those steps from this sequence which are
-needed to keep the interpreter and `task` happy.
+So our remapped code will need to do a bit more than just generating some commands to move the machine as we like -
+it will also need to replicate those steps from this sequence which are needed to keep the interpreter and `task` happy.
-However, this does *not* affect the processing of
-tool change-related commands in `task` and `iocontrol`. This means when we
-execute <<remap:send-tool-load-msg,step 6b>> this will still cause
-<<remap:iocontrol-action-on-load,iocontrol to do its thing>>.
+However, this does *not* affect the processing of tool change-related commands in `task` and `iocontrol`.
+This means when we execute <<remap:send-tool-load-msg,step 6b>>
+this will still cause <<remap:iocontrol-action-on-load,iocontrol to do its thing>>.
Decisions, decisions:
@@ -713,13 +684,10 @@ Depending on the answer, we have four different scenarios:
- When using an O-word procedure, we need prolog and epilog functions.
- If using all Python code and no O-word procedure, a Python function is enough.
- When using the `iocontrol` pins, our O-word procedure or Python code will contain mostly moves.
-- When we need a more complex interaction than offered by `iocontrol`,
- we need to completely define our own interaction,
- using `motion.digital*` and `motion.analog*` pins,
- and essentially ignore the `iocontrol` pins by looping them.
+- When we need a more complex interaction than offered by `iocontrol`, we need to completely define our own interaction,
+ using `motion.digital*` and `motion.analog*` pins, and essentially ignore the `iocontrol` pins by looping them.
-NOTE: If you hate O-word procedures and love Python,
-you're free to do it all in Python,
+NOTE: If you hate O-word procedures and love Python, you're free to do it all in Python,
in which case you would just have a `python=_<function>_` spec in the REMAP statement.
But assuming most folks would be interested in using O-word procedures
because they are more familiar with that, we'll do that as the first example.
@@ -766,14 +734,14 @@ We'll use the following correspondence in our example:
[frame="topbot",grid="none"]
[options="header"]
|===
-|iocontrol.0 pin |motion pin
-|tool-prepare |digital-out-00
-|tool-prepared |digital-in-00
-|tool-change |digital-out-01
-|tool-changed |digital-in-01
-|tool-prep-number |analog-out-00
-|tool-prep-pocket |analog-out-01
-|tool-number |analog-out-02
+|`iocontrol.0` pin |`motion` pin
+m|tool-prepare m|digital-out-00
+m|tool-prepared m|digital-in-00
+m|tool-change m|digital-out-01
+m|tool-changed m|digital-in-01
+m|tool-prep-number m|analog-out-00
+m|tool-prep-pocket m|analog-out-01
+m|tool-number m|analog-out-02
|===
Let us assume you want to redefine the M6 command,
@@ -800,25 +768,22 @@ Going through the <<remap:interpreter-action-on-m6,steps>>, we find:
.. generate rapid move to the G30 position - *can be done in NGC*
. send a CHANGE_TOOL Canon command to `task` - *execute in Python epilog*
. set the numberer parameters 5400-5413 according to the new tool - *execute in Python epilog*
-. signal to `task` to stop calling the interpreter for readahead until
- tool change complete - *execute in Python epilog*
+. signal to `task` to stop calling the interpreter for readahead until tool change complete - *execute in Python epilog*
-So we need a prolog, and an epilog. Lets assume our INI file incantation of the M6 remap looks as follows:
+So we need a prolog, and an epilog.
+Lets assume our INI file incantation of the M6 remap looks as follows:
----
REMAP=M6 modalgroup=6 prolog=change_prolog ngc=change epilog=change_epilog
----
-So the prolog covering steps 1 and 2 would look like so - we decide to
-pass a few variables to the remap procedure which can be inspected and
-changed there, or used in a message.
-Those are: `tool_in_spindle`, `selected_tool` (tool numbers) and
-their respective tooldata indices `current_pocket` and `selected_pocket`:
+So the prolog covering steps 1 and 2 would look like so - we decide to pass a few variables to the remap procedure
+which can be inspected and changed there, or used in a message.
+Those are: `tool_in_spindle`, `selected_tool` (tool numbers) and their respective tooldata indices `current_pocket` and `selected_pocket`:
[NOTE]
-The legacy names *selected_pocket* and *current_pocket* actually reference
-a sequential tooldata index for tool items loaded from a tool
-table ([EMCIO]TOOL_TABLE) or via a tooldata database ([EMCIO]DB_PROGRAM)
+The legacy names *selected_pocket* and *current_pocket* actually reference a sequential tooldata index for tool items loaded from a tool table
+([EMCIO]TOOL_TABLE) or via a tooldata database ([EMCIO]DB_PROGRAM).
[source,python]
---------------------------------------------------------------------
@@ -893,21 +858,17 @@ Again, most epilogs have a common scheme:
=== Configuring `iocontrol` with a remapped M6
-Note that the sequence of operations has changed: we do everything
-required in the O-word procedure - including any HAL pin
-setting/reading to get a changer going, and to acknowledge a tool
-change - likely with `motion.digital-*` and `motion-analog-*` IO
-pins. When we finally execute the `CHANGE_TOOL()` command, all
-movements and HAL interactions are already completed.
+Note that the sequence of operations has changed:
+we do everything required in the O-word procedure - including any HAL pin setting/reading to get a changer going,
+and to acknowledge a tool change - likely with `motion.digital-*` and `motion-analog-*` IO pins.
+When we finally execute the `CHANGE_TOOL()` command,
+all movements and HAL interactions are already completed.
-Normally only now `iocontrol` would do its thing as outlined
-<<remap:iocontrol-action-on-load,here>>. However, we don't need the
-HAL pin wiggling anymore - all `iocontrol` is left to do is to accept
-we're done with prepare and change.
+Normally only now `iocontrol` would do its thing as outlined <<remap:iocontrol-action-on-load,here>>.
+However, we don't need the HAL pin wiggling anymore - all `iocontrol` is left to do is to accept we're done with prepare and change.
-This means that the corresponding `iocontrol` pins have no function any
-more. Therefore, we configure `iocontrol` to immediately acknowledge a
-change by configuring like so:
+This means that the corresponding `iocontrol` pins have no function any more.
+Therefore, we configure `iocontrol` to immediately acknowledge a change by configuring like so:
[source,{hal}]
---------------------------------------------------------------------
@@ -980,10 +941,8 @@ But remapping is also a way to work around deficiencies in the current implement
for instance to not block until the "tool-prepared" pin is set.
What you could do, for instance, is:
-- in a remapped T, just set the equivalent of the "tool-prepare" pin,
- but *not* wait for "tool-prepared" here
-- in the corresponding remapped M6,
- wait for the "tool-prepared" at the very beginning of the O-word procedure.
+- In a remapped T, just set the equivalent of the "tool-prepare" pin, but *not* wait for "tool-prepared" here.
+- In the corresponding remapped M6, wait for the "tool-prepared" at the very beginning of the O-word procedure.
Again, the `iocontrol` tool-prepare/tool-prepared pins would be unused and replaced by `motion.*` pins,
so those would pins must be looped:
@@ -1064,8 +1023,7 @@ This module is intended to cover most standard remapping situations in a common
=== Error handling: dealing with abort
-The built in tool change procedure has some precautions for dealing with a program abort,
-e.g., by hitting escape in AXIS during a change.
+The built in tool change procedure has some precautions for dealing with a program abort, e.g., by hitting escape in AXIS during a change.
Your remapped function has none of this, therefore some explicit cleanup might be needed if a remapped code is aborted.
In particular, a remap procedure might establish modal settings which are undesirable to have active after an abort.
For instance, if your remap procedure has motion codes (G0,G1,G38..) and the remap is aborted,
@@ -1073,8 +1031,7 @@ then the last modal code will remain active.
However, you very likely want to have any modal motion canceled when the remap is aborted.
The way to do this is by using the `[RS274NGC]ON_ABORT_COMMAND` feature.
-This INI option specifies a O-word procedure call which is executed
-if `task` for some reason aborts program execution.
+This INI option specifies a O-word procedure call which is executed if `task` for some reason aborts program execution.
`on_abort` receives a single parameter indicating the cause for calling the abort procedure,
which might be used for conditional cleanup.
@@ -1133,33 +1090,25 @@ o<on_abort> endsub
m2
----
-CAUTION: Never use an `M2` in a O-word subroutine, including this
-one. It will cause hard-to-find errors. For instance, using an `M2` in
-a subroutine will not end the subroutine properly and will leave the
-subroutine NGC file open, not your main program.
+CAUTION: Never use an `M2` in a O-word subroutine, including this one.
+It will cause hard-to-find errors. For instance, using an `M2` in a subroutine will not end the subroutine properly and will leave the subroutine NGC file open,
+not your main program.
Make sure `on_abort.ngc` is along the interpreter search path
-(recommended location: `SUBROUTINE_PATH` so as not to clutter your
-`NC_FILES` directory with internal procedures).
+(recommended location: `SUBROUTINE_PATH` so as not to clutter your `NC_FILES` directory with internal procedures).
-Statements in that procedure typically would assure that post-abort
-any state has been cleaned up, like HAL pins properly reset. For an
-example, see `configs/sim/axis/remap/rack-toolchange`.
+Statements in that procedure typically would assure that post-abort any state has been cleaned up,
+like HAL pins properly reset. For an example, see `configs/sim/axis/remap/rack-toolchange`.
-Note that terminating a remapped code by returning INTERP_ERROR from
-the epilog (see previous section) will also cause the `on_abort` procedure
-to be called.
+Note that terminating a remapped code by returning INTERP_ERROR from the epilog (see previous section) will also cause the `on_abort` procedure to be called.
=== Error handling: failing a remapped code NGC procedure
-If you determine in your handler procedure that some error condition
-occurred, do not use `M2` to end your handler - see above:
+If you determine in your handler procedure that some error condition occurred, do not use `M2` to end your handler - see above:
-If displaying an operator error message and stopping the current program is
-good enough, use the `(abort, `__<message>__`)` feature to terminate the handler with an
-error message. Note that you can substitute numbered, named, INI and
-HAL parameters in the text like
-in this example (see also `tests/interp/abort-hot-comment/test.ngc`):
+If displaying an operator error message and stopping the current program is good enough,
+use the `(abort, `__<message>__`)` feature to terminate the handler with an error message.
+Note that you can substitute numbered, named, INI and HAL parameters in the text like in this example (see also `tests/interp/abort-hot-comment/test.ngc`):
[source,{ngc}]
----
@@ -1168,11 +1117,9 @@ o100 if [..] (some error condition)
o100 endif
----
-NOTE: INI and HAL variable expansion is optional and can be disabled in
-the <<sub:ini:sec:rs274ngc,INI file>>
+NOTE: INI and HAL variable expansion is optional and can be disabled in the <<sub:ini:sec:rs274ngc,INI file>>
-If more fine grained recovery action is needed, use the idiom
-laid out in the previous example:
+If more fine grained recovery action is needed, use the idiom laid out in the previous example:
- Define an epilog function, even if it's just to signal an error condition,
- pass a negative value from the handler to signal the error,
@@ -1182,11 +1129,9 @@ laid out in the previous example:
which will set the interpreter error message and abort the program
(pretty much like `abort, message=`).
-This error message will be displayed in the UI, and returning
-INTERP_ERROR will cause this error handled like any other runtime error.
+This error message will be displayed in the UI, and returning INTERP_ERROR will cause this error handled like any other runtime error.
-Note that both `(abort,` __<msg>__ `)` and returning INTERP_ERROR from an
-epilog will cause any ON_ABORT handler to be called as well if defined
+Note that both `(abort,` __<msg>__ `)` and returning INTERP_ERROR from an epilog will cause any ON_ABORT handler to be called as well if defined
(see previous section).
== Remapping other existing codes: S, M0, M1, M60
@@ -1194,18 +1139,15 @@ epilog will cause any ON_ABORT handler to be called as well if defined
=== Automatic gear selection be remapping S (set spindle speed)
A potential use for a remapped S code would be 'automatic gear selection' depending on speed.
-In the remap procedure one would test for the desired speed attainable given the current gear setting,
-and change gears appropriately if not.
+In the remap procedure one would test for the desired speed attainable given the current gear setting, and change gears appropriately if not.
=== Adjusting the behavior of M0, M1, M60
-A use case for remapping M0/M1 would be to customize the behavior of
-the existing code. For instance, it could be desirable to turn off the
-spindle, mist and flood during an M0 or M1 program pause, and turn
-these settings back on when the program is resumed.
+A use case for remapping M0/M1 would be to customize the behavior of the existing code.
+For instance, it could be desirable to turn off the spindle, mist and flood during an M0 or M1 program pause,
+and turn these settings back on when the program is resumed.
-For a complete example doing just that, see
-`configs/sim/axis/remap/extend-builtins/`, which adapts M1 as laid out above.
+For a complete example doing just that, see `configs/sim/axis/remap/extend-builtins/`, which adapts M1 as laid out above.
== Creating new G-code cycles
@@ -1215,9 +1157,8 @@ A G-code cycle as used here is meant to behave as follows:
* If subsequent lines just continue parameter words applicable to this code,
but no new G-code, the previous G-code is re-executed with the parameters changed accordingly.
-An example: Assume you have `G84.3` defined as remapped G-code cycle
-with the following INI segment (see <<remap:cycle-stdglue,here>> for
-a detailed description of +cycle_prolog+ and +cycle_epilog+):
+An example: Assume you have `G84.3` defined as remapped G-code cycle with the following INI segment
+(see <<remap:cycle-stdglue,here>> for a detailed description of +cycle_prolog+ and +cycle_epilog+):
[source,{ini}]
---------------------------------------------------------------------
@@ -1244,8 +1185,7 @@ causes the following (note 'R' is sticky, and 'Z' is sticky since the plane is '
. `g843.ngc` is called with words x=6, y=7, z=3, r=1
. The `G84.3` cycle is canceled.
-Besides creating new cycles, this provides an easy method for
-repackaging existing G-codes which do not behave as cycles.
+Besides creating new cycles, this provides an easy method for repackaging existing G-codes which do not behave as cycles.
For instance, the `G33.1` Rigid Tapping code does not behave as a cycle.
With such a wrapper, a new code can be easily created which uses `G33.1` but behaves as a cycle.
@@ -1256,8 +1196,7 @@ and a cycle example using just Python.
[[remap:embedded-python]]
== Configuring Embedded Python
-The Python plugin serves both the interpreter, and `task` if so
-configured, and hence has its own section `PYTHON` in the INI file.
+The Python plugin serves both the interpreter, and `task` if so configured, and hence has its own section `PYTHON` in the INI file.
=== Python plugin : INI file configuration
@@ -1366,18 +1305,14 @@ def __delete__(self):
---------------------------------------------------------------------
This function may be used to initialize any Python-side attributes which might be needed later,
-for instance in remap or oword functions,
-and save or restore state beyond what `PARAMETER_FILE` provides.
+for instance in remap or oword functions, and save or restore state beyond what `PARAMETER_FILE` provides.
-If there are setup or cleanup actions
-which are to happen only in the milltask Interpreter instance
+If there are setup or cleanup actions which are to happen only in the milltask Interpreter instance
(as opposed to the interpreter instance which sits in the `gcode` Python module and serves preview/progress display purposes but nothing else),
this can be tested for by <<remap:axis-preview-and-remapped-code-execution,evaluating 'self.task'>>.
-An example use of `__init__` and `__delete__` can be found in
-`configs/sim/axis/remap/cycle/python/toplevel.py` initialising attributes
-needed to handle cycles in `ncfiles/remap_lib/python-stdglue/stdglue.py`
-(and imported into `configs/sim/axis/remap/cycle/python/remap.py`).
+An example use of `__init__` and `__delete__` can be found in `configs/sim/axis/remap/cycle/python/toplevel.py` initialising attributes
+needed to handle cycles in `ncfiles/remap_lib/python-stdglue/stdglue.py` (and imported into `configs/sim/axis/remap/cycle/python/remap.py`).
=== Calling conventions: NGC to Python
@@ -1406,7 +1341,7 @@ Arguments:
def mysub(self, *args):
print("number of parameters passed:", len(args))
for a in args:
- print(a)
+ print(a)
---------------------------------------------------------------------
.Return values of O-word Python subroutines
@@ -1439,7 +1374,7 @@ Arguments are:
The interpreter instance
`words`::
- Keyword parameter dictionary
+ Keyword parameter dictionary.
If an argspec was present, words are collected from the current block accordingly and passed in the dictionary for convenience
(the words could as well be retrieved directly from the calling block, but this requires more knowledge of interpreter internals).
If no argspec was passed, or only optional values were specified and none of these was present in the calling block, this dict is empty.
@@ -1505,11 +1440,9 @@ to suspend execution with the following statement:
.Dealing with queue-buster: Probe, Tool change and waiting for a HAL pin
-Queue busters interrupt a procedure at the point where such an
-operation is called, hence the procedure needs to be restarted
-after the interpreter synch(). When this happens the procedure needs to
-know if it is restarted, and where to continue. The Python generator
-method is used to deal with procedure restart.
+Queue busters interrupt a procedure at the point where such an operation is called, hence the procedure needs to be restarted after the interpreter synch().
+When this happens the procedure needs to know if it is restarted, and where to continue.
+The Python generator method is used to deal with procedure restart.
This demonstrates call continuation with a single point-of-restart:
@@ -1528,30 +1461,24 @@ def read_pin(self,*args):
WARNING: The 'yield' feature is fragile. The following restrictions
apply to the usage of 'yield INTERP_EXECUTE_FINISH':
-- Python code executing a 'yield INTERP_EXECUTE_FINISH' must be part
- of a remap procedure. Yield does not work in a Python oword procedure.
-- A Python remap subroutine containing 'yield INTERP_EXECUTE_FINISH' statement may
- not return a value, as with normal Python yield statements.
-- Code following a yield may not recursively call the interpreter, like with
- self.execute("<mdi command>"). This is an architectural restriction
- of the interpreter and is not fixable without a major redesign.
+- Python code executing a 'yield INTERP_EXECUTE_FINISH' must be part of a remap procedure. Yield does not work in a Python oword procedure.
+- A Python remap subroutine containing 'yield INTERP_EXECUTE_FINISH' statement may not return a value, as with normal Python yield statements.
+- Code following a yield may not recursively call the interpreter, like with `self.execute("<mdi command>")`.
+ This is an architectural restriction of the interpreter and is not fixable without a major redesign.
=== Calling conventions: Python to NGC
NGC code is executed from Python when
- the method `self.execute(<NGC code>[,<line number>])` is executed, or
-- during execution of a remapped code, if a `prolog=` function is defined,
- the NGC procedure given in `ngc=` is executed immediately thereafter.
+- during execution of a remapped code, if a `prolog=` function is defined, the NGC procedure given in `ngc=` is executed immediately thereafter.
-The prolog handler does not call the handler, but it prepares its call
-environment, for instance by setting up predefined local parameters.
+The prolog handler does not call the handler, but it prepares its call environment, for instance by setting up predefined local parameters.
.Inserting parameters in a prolog, and retrieving them in an epilog
-Conceptually a prolog and an epilog execute at the same call level
-like the O-word procedure, that is: after the subroutine call is set
-up, and before the subroutine endsub or return.
+Conceptually a prolog and an epilog execute at the same call level like the O-word procedure,
+that is: after the subroutine call is set up, and before the subroutine endsub or return.
This means that any local variable created in a prolog will be a local variable in the O-word procedure,
and any local variables created in the O-word procedure are still accessible when the epilog executes.
@@ -1619,9 +1546,8 @@ Examples:
self.execute("O <myprocedure> call", currentline)
---------------------------------------------------------------------
-You might want to test for the return value being `<
-INTERP_MIN_ERROR`. If you're using lots of execute() statements, it's
-probably easier to trap InterpreterException as per below.
+You might want to test for the return value being `< INTERP_MIN_ERROR`.
+If you're using lots of execute() statements, it's probably easier to trap InterpreterException as shown below.
CAUTION:
====
@@ -1637,8 +1563,7 @@ The recursive call feature is fragile.
.Interpreter Exception during execute()
-if `interpreter.throw_exceptions` is nonzero (default 1), and self.execute() returns an error,
-the exception `InterpreterException` is raised.
+if `interpreter.throw_exceptions` is nonzero (default 1), and self.execute() returns an error, the exception `InterpreterException` is raised.
InterpreterException has the following attributes:
`line_number`::
@@ -1702,8 +1627,7 @@ The following modules are built in:
[[remap:adding-predefined-named-parameters]]
== Adding Predefined Named Parameters
-The interpreter comes with a set of predefined named parameters for
-accessing internal state from the NGC language level.
+The interpreter comes with a set of predefined named parameters for accessing internal state from the NGC language level.
These parameters are read-only and global, and hence cannot be assigned to.
Additional parameters may be added by defining a function in the `namedparams` module.
@@ -1734,11 +1658,9 @@ def _pi(self):
Functions in `namedparams.py` are expected to return a float or int value.
If a string is returned, this sets the interpreter error message and aborts execution.
-Ònly functions with a leading underscore are added as parameters,
-since this is the RS274NGC convention for globals.
+Ònly functions with a leading underscore are added as parameters, since this is the RS274NGC convention for globals.
-It is possible to redefine an existing predefined parameter by adding
-a Python function of the same name to the `namedparams` module.
+It is possible to redefine an existing predefined parameter by adding a Python function of the same name to the `namedparams` module.
In this case, a warning is generated during startup.
While the above example isn't terribly useful,
@@ -1771,21 +1693,18 @@ It is an error if:
- no tool number is given as T parameter
- the tool cannot be found in the tool table.
-Note that unless you set the `[EMCIO] RANDOM_TOOLCHANGER=1` parameter,
-tool and pocket number are identical,
+Note that unless you set the `[EMCIO] RANDOM_TOOLCHANGER=1` parameter, tool and pocket number are identical,
and the pocket number from the tool table is ignored.
This is currently a restriction.
.Actions of +prepare_epilog+
-- The NGC procedure is expected to return a positive value, otherwise
- an error message containing the return value is given and the interpreter aborts.
+- The NGC procedure is expected to return a positive value, otherwise an error message containing the return value is given and the interpreter aborts.
- In case the NGC procedure executed the T command (which then refers to the built in T behavior), no further action is taken.
This can be used for instance to minimally adjust the built in behavior be preceding or following it with some other statements.
- Otherwise, the `#<tool>` and `#<pocket>` parameters are extracted from the subroutine's parameter space.
- This means that the NGC procedure could change these values,
- and the epilog takes the changed values in account.
-- then, the Canon command `SELECT_TOOL(#<tool>)` is executed.
+ This means that the NGC procedure could change these values, and the epilog takes the changed values in account.
+- Then, the Canon command `SELECT_TOOL(#<tool>)` is executed.
=== M6: +change_prolog+ and +change_epilog+
@@ -1794,14 +1713,11 @@ These wrap a NGC procedure for M6 Tool Change.
.Actions of +change_prolog+
* The following three steps are applicable only if the `iocontrol-v2` component is used:
-** If parameter 5600 (fault indicator) is greater than zero,
- this indicates a Toolchanger fault, which is handled as follows:
-** if parameter 5601 (error code) is negative, this indicates a hard
- fault and the prolog aborts with an error message.
+** If parameter 5600 (fault indicator) is greater than zero, this indicates a Toolchanger fault, which is handled as follows:
+** if parameter 5601 (error code) is negative, this indicates a hard fault and the prolog aborts with an error message.
** if parameter 5601 (error code) is greater equal zero, this indicates a soft fault.
An informational message is displayed and the prolog continues.
-* If there was no preceding T command which caused a pocket to be selected,
- the prolog aborts with an error message.
+* If there was no preceding T command which caused a pocket to be selected, the prolog aborts with an error message.
* If cutter radius compensation is on, the prolog aborts with an error message.
Then, the following parameters are exported to the NGC procedure:
@@ -1816,19 +1732,13 @@ Then, the following parameters are exported to the NGC procedure:
otherwise an error message containing the return value is given and the interpreter aborts.
* If parameter 5600 (fault indicator) is greater than zero, this indicates a Toolchanger fault,
which is handled as follows (`iocontrol-v2`-only):
-** If parameter 5601 (error code) is negative,
- this indicates a hard fault and the epilog aborts with an error message.
+** If parameter 5601 (error code) is negative, this indicates a hard fault and the epilog aborts with an error message.
** If parameter 5601 (error code) is greater equal zero, this indicates a soft fault.
An informational message is displayed and the epilog continues.
-* In case the NGC procedure executed the M6 command (which then refers
- to the built in M6 behavior), no further action is taken.
- This can be used for instance to minimally adjust the built in behavior be preceding
- or following it with some other statements.
-* Otherwise, the `#<selected_pocket>` parameter is extracted
- from the subroutine's parameter space, and used to set the
- interpreter's `current_pocket` variable.
- Again, the procedure could change this value,
- and the epilog takes the changed value in account.
+* In case the NGC procedure executed the M6 command (which then refers to the built in M6 behavior), no further action is taken.
+ This can be used for instance to minimally adjust the built in behavior be preceding or following it with some other statements.
+* Otherwise, the `#<selected_pocket>` parameter is extracted from the subroutine's parameter space, and used to set the interpreter's `current_pocket` variable.
+ Again, the procedure could change this value, and the epilog takes the changed value in account.
* Then, the Canon command `CHANGE_TOOL(#<selected_pocket>)` is executed.
* The new tool parameters (offsets, diameter etc) are set.
@@ -1842,8 +1752,7 @@ the code is executed again with the new parameter words merged into the set of t
These routines are designed to work in conjunction with an <<sub:argspec-parameter,`argspec=<words>` parameter>>.
While this is easy to use, in a realistic scenario you would avoid argspec and
-do a more thorough investigation of the block manually
-in order to give better error messages.
+do a more thorough investigation of the block manually in order to give better error messages.
The suggested argspec is as follows:
@@ -1864,8 +1773,7 @@ This will permit +cycle_prolog+ to determine the compatibility of any axis words
** Export 'R-' as +#<r>+; fail if r not given, or less equal 0 if given.
** Fail if feed rate is zero, or inverse time feed or cutter compensation is on.
* Determine whether this is the first invocation of a cycle G-code, if so:
-** Add the words passed in (as per argspec) into a set of sticky parameters,
- which is retained across several invocations.
+** Add the words passed in (as per argspec) into a set of sticky parameters, which is retained across several invocations.
* If not (a continuation line with new parameters) then
** merge the words passed in into the existing set of sticky parameters.
* Export the set of sticky parameters to the NGC procedure.
@@ -1943,16 +1851,13 @@ To use this approach:
which comes with that plug in - it's buried somewhere deep under the Eclipse install directory.
Set the the `pydevd` variable in `util.py` to reflect this directory location.
- Add `import pydevd` to your Python module - see example `util.py` and `remap.py`.
-- Call `pydevd.settrace()` in your module at some point to connect to
- the Eclipse Python debug server - here you can set breakpoints in your code,
+- Call `pydevd.settrace()` in your module at some point to connect to the Eclipse Python debug server - here you can set breakpoints in your code,
inspect variables, step etc. as usual.
-CAUTION: `pydevd.settrace()` will block execution if Eclipse and the
-Pydev debug server have not been started.
+CAUTION: `pydevd.settrace()` will block execution if Eclipse and the Pydev debug server have not been started.
-To cover the last two steps: the `o<pydevd>` procedure helps to get
-into the debugger from MDI mode. See also the `call_pydevd` function
-in `util.py` and its usage in `remap.involute` to set a breakpoint.
+To cover the last two steps: the `o<pydevd>` procedure helps to get into the debugger from MDI mode.
+See also the `call_pydevd` function in `util.py` and its usage in `remap.involute` to set a breakpoint.
Here's a screen-shot of Eclipse/PyDevd debugging the `involute` procedure from above:
@@ -1967,8 +1872,7 @@ For complete preview of a remapped code's tool path some precautions need to be
To understand what is going on,
let's review the preview and execution process (this covers the AXIS case, but others are similar):
-First, note that there are *two* independent interpreter instances
-involved:
+First, note that there are *two* independent interpreter instancesinvolved:
- One instance in the milltask program, which executes a program when you hit the 'Start' button,
and actually makes the machine move.
@@ -2183,9 +2087,8 @@ All the listed G-codes are already defined in the current implementation of Linu
[[remap:unallocated-m-codes]]
=== Currently unallocated M-codes:
-These M-codes are currently undefined in the current implementation of LinuxCNC
-and may be used to define new M-codes. (Developers who define new M-codes in
-LinuxCNC are encouraged to remove them from this table.)
+These M-codes are currently undefined in the current implementation of LinuxCNC and may be used to define new M-codes.
+(Developers who define new M-codes in LinuxCNC are encouraged to remove them from this table.)
.Table of Unallocated M-codes 00-99
[width="90%",align="center",options="header,strong,unbreakable",cols="1*2^em,10*1<m"]
@@ -2203,8 +2106,7 @@ LinuxCNC are encouraged to remove them from this table.)
|90-99 |M90 |M91 |M92 |M93 |M94 |M95 |M96 |M97 |M98 |M99
|===
-All M-codes from `M100` to `M199` are user-defined M-codes already,
-and should not be remapped.
+All M-codes from `M100` to `M199` are user-defined M-codes already, and should not be remapped.
All M-codes from `M200` to `M999` are available for remapping.
@@ -2257,8 +2159,7 @@ execution of `task` and interpreter as far as it relates to remapping.
=== Interpreter state
-Conceptually, the interpreter's state consist of variables which fall into
-the following categories:
+Conceptually, the interpreter's state consist of variables which fall into the following categories:
1. _Configuration information_ (typically from INI file)
2. _The 'World model'_ - a representation of actual machine state
@@ -2283,9 +2184,7 @@ These are, however, not immediately executed but put on a queue.
The actual execution of these codes happens in the `task` part of LinuxCNC: canon commands are pulled off that interpreter queue,
and executed resulting in actual machine movements.
-This means that typically the interpreter is far ahead of the actual
-execution of commands - the parsing of the program might well be
-finished before any noticeable movement starts.
+This means that typically the interpreter is far ahead of the actual execution of commands - the parsing of the program might well be finished before any noticeable movement starts.
This behavior is called 'read-ahead'.
=== Predicting the machine position
@@ -2294,8 +2193,7 @@ To compute canonical machine operations in advance during read ahead,
the interpreter must be able to predict the machine position after each line of G-code,
and that is not always possible.
-Let's look at a simple example program which does relative moves (G91),
-and assume the machine starts at x=0,y=0,z=0.
+Let's look at a simple example program which does relative moves (G91), and assume the machine starts at x=0,y=0,z=0.
Relative moves imply that the outcome of the next move relies on the position of the previous one:
[source,{ngc}]
@@ -2315,8 +2213,7 @@ and so can parse the whole program and generate canonical operations well in adv
=== Queue-busters break position prediction
-However, complete read ahead is only possible
-when the interpreter can predict the position impact for *every* line in the program in advance.
+However, complete read ahead is only possible when the interpreter can predict the position impact for *every* line in the program in advance.
Let's look at a modified example:
[source,{ngc}]
@@ -2334,9 +2231,8 @@ N95 M2
----
To pre-compute the move in N90, the interpreter would need to know
-where the machine is after line N80 - and that depends on whether the
-probe command succeeded or not, which is not known until it's actually
-executed.
+where the machine is after line N80 - and that depends on whether the probe command succeeded or not,
+which is not known until it's actually executed.
So, some operations are incompatible with further read-ahead.
These are called _queue busters_, and they are:
@@ -2347,23 +2243,16 @@ These are called _queue busters_, and they are:
=== How queue-busters are dealt with
-Whenever the interpreter encounters a queue-buster,
-it needs to stop read ahead and wait until the relevant result is available.
+Whenever the interpreter encounters a queue-buster, it needs to stop read ahead and wait until the relevant result is available.
The way this works is:
-- When such a code is encountered,
- the interpreter returns a special return code to `task` ('INTERP_EXECUTE_FINISH').
+- When such a code is encountered, the interpreter returns a special return code to `task` ('INTERP_EXECUTE_FINISH').
- This return code signals to `task` to stop read ahead for now,
- execute all queued canonical commands built up so far (including the last one,
- which is the queue buster),
+ execute all queued canonical commands built up so far (including the last one, which is the queue buster),
and then 'synchronize the interpreter state with the world model'.
- Technically, this means updating internal variables to reflect HAL pin values,
- reload tool geometries after an M6, and convey results of a probe.
-- The interpreter's 'synch()' method is called by `task` and does just
- that - read all the world model 'actual' values which are relevant for
- further execution.
-- At this point, `task` goes ahead and calls the interpreter for more read ahead -
- until either the program ends or another queue-buster is encountered.
+ Technically, this means updating internal variables to reflect HAL pin values, reload tool geometries after an M6, and convey results of a probe.
+- The interpreter's 'synch()' method is called by `task` and does just that - read all the world model 'actual' values which are relevant for further execution.
+- At this point, `task` goes ahead and calls the interpreter for more read ahead - until either the program ends or another queue-buster is encountered.
=== Word order and execution order
@@ -2387,29 +2276,21 @@ Right after parsing, all codes on a block are checked for compatibility.
After successful parsing the block is executed by execute_block(),
and here the different items are handled according to execution order.
-If a "queue buster" is found, a corresponding flag is set in the
-interpreter state (toolchange_flag, input_flag, probe_flag) and the
-interpreter returns an INTERP_EXECUTE_FINISH return value, signaling
-'stop readahead for now, and resynch' to the caller ('`task`').
-If no queue busters are found
-after all items are executed, INTERP_OK is returned, signalling that
-read-ahead may continue.
-
-When read ahead continues after the synch, `task` starts executing
-interpreter read() operations again. During the next read operation,
-the above mentioned flags are checked and corresponding variables are
-set (because the a synch() was just executed, the values are now
-current). This means that the next command already executes in the
-properly set variable context.
+If a "queue buster" is found, a corresponding flag is set in the interpreter state (toolchange_flag, input_flag, probe_flag)
+and the interpreter returns an INTERP_EXECUTE_FINISH return value,
+signaling 'stop readahead for now, and resynch' to the caller ('`task`').
+If no queue busters are found after all items are executed, INTERP_OK is returned, signalling that read-ahead may continue.
+
+When read ahead continues after the synch, `task` starts executing interpreter read() operations again.
+During the next read operation, the above mentioned flags are checked and corresponding variables are set
+(because the a synch() was just executed, the values are now current).
+This means that the next command already executes in the properly set variable context.
=== Procedure execution
-O-word procedures complicate handling of queue busters a bit. A queue
-buster might be found somewhere in a nested procedure, resulting in a
-semi-finished procedure call when INTERP_EXECUTE_FINISH is
-returned. Task makes sure to synchronize the world model, and continue
-parsing and execution as long as there is still a procedure executing
-(call_level > 0).
+O-word procedures complicate handling of queue busters a bit.
+A queue buster might be found somewhere in a nested procedure, resulting in a semi-finished procedure call when INTERP_EXECUTE_FINISH is returned.
+Task makes sure to synchronize the world model, and continue parsing and execution as long as there is still a procedure executing (call_level > 0).
[[remap:how-tool-change-currently-works]]
=== How tool change currently works
@@ -2464,47 +2345,35 @@ You need to have LinuxCNC started from a terminal window to see the results.
[[remap:interpreter-action-on-t]]
.Interpreter action on a Tx command
-All the interpreter does is evaluate the toolnumber parameter, looks up
-its corresponding tooldata index, remembers it in the `selected_pocket`
-variable for later, and queues a canon command (SELECT_TOOL).
+All the interpreter does is evaluate the toolnumber parameter, looks up its corresponding tooldata index,
+remembers it in the `selected_pocket` variable for later, and queues a canon command (SELECT_TOOL).
See 'Interp::convert_tool_select' in 'src/emc/rs274/interp_execute.cc'.
.Task action on SELECT_TOOL
-When `task` gets around to handle a SELECT_TOOL, it sends a
-EMC_TOOL_PREPARE message to the `iocontrol` process, which handles most
-tool-related actions in LinuxCNC.
+When `task` gets around to handle a SELECT_TOOL, it sends a EMC_TOOL_PREPARE message to the `iocontrol` process,
+which handles most tool-related actions in LinuxCNC.
-In the current implementation, `task` actually waits for `iocontrol` to
-complete the changer positioning operation, which is not necessary IMO
-since it defeats the idea that changer preparation and code execution can
-proceed in parallel.
+In the current implementation, `task` actually waits for `iocontrol` to complete the changer positioning operation,
+which is not necessary IMO since it defeats the idea that changer preparation and code execution can proceed in parallel.
.Iocontrol action on EMC_TOOL_PREPARE
-When `iocontrol` sees the select pocket command, it does the related HAL
-pin wiggling - it sets the "tool-prep-number" pin to indicate which
-tool is next, raises the "tool-prepare" pin, and waits for the
-"tool-prepared" pin to go high.
+When `iocontrol` sees the select pocket command, it does the related HAL pin wiggling - it sets the "tool-prep-number" pin to indicate which tool is next,
+raises the "tool-prepare" pin, and waits for the "tool-prepared" pin to go high.
-When the changer responds by asserting "tool-prepared", it considers
-the prepare phase to be completed and signals `task` to
-continue. Again, this 'wait' is not strictly necessary IMO.
+When the changer responds by asserting "tool-prepared", it considers the prepare phase to be completed and signals `task` to continue.
+Again, this 'wait' is not strictly necessary IMO.
.Building the prolog and epilog for Tx
-See the Python functions `prepare_prolog` and `prepare_epilog` in
-`configs/sim/axis/remap/toolchange/python/toolchange.py`.
+See the Python functions `prepare_prolog` and `prepare_epilog` in `configs/sim/axis/remap/toolchange/python/toolchange.py`.
=== How M6 (Change tool) works
You need to understand this fully before you can adapt it.
It is very relevant to writing a prolog and epilog handler for a remapped M6.
-Remapping an existing codes means you disable the internal steps
-taken normally, and replicate them as far as needed for your own
-purposes.
+Remapping an existing codes means you disable the internal steps taken normally, and replicate them as far as needed for your own purposes.
-Even if you are not familiar with C, I suggest you look at the
-'Interp::convert_tool_change' code in
-'src/emc/rs274/interp_convert.cc'.
+Even if you are not familiar with C, I suggest you look at the 'Interp::convert_tool_change' code in 'src/emc/rs274/interp_convert.cc'.
[[remap:interpreter-action-on-m6]]
.Interpreter action on a M6 command
@@ -2512,30 +2381,23 @@ Even if you are not familiar with C, I suggest you look at the
When the interpreter sees an M6, it:
[[remap:send-tool-load-msg]]
-. checks whether a T command has already been executed (test
- 'settings->selected_pocket' to be >= 0) and fail with 'Need tool
- prepared -Txx- for toolchange' message if not.
-. check for cutter compensation being active, and fail with 'Cannot
- change tools with cutter radius compensation on' if so.
-. stop the spindle except if the "TOOL_CHANGE_WITH_SPINDLE_ON" INI
- option is set.
-. generate a rapid 'Z up' move if if the "TOOL_CHANGE_QUILL_UP" INI
- option is set.
+. checks whether a T command has already been executed (test 'settings->selected_pocket' to be >= 0)
+ and fail with 'Need tool prepared -Txx- for toolchange' message if not.
+. check for cutter compensation being active, and fail with 'Cannot change tools with cutter radius compensation on' if so.
+. stop the spindle except if the "TOOL_CHANGE_WITH_SPINDLE_ON" INI option is set.
+. generate a rapid 'Z up' move if if the "TOOL_CHANGE_QUILL_UP" INI option is set.
. if TOOL_CHANGE_AT_G30 was set:
.. move the A, B and C indexers if applicable
.. generate rapid move to the G30 position
-. execute a CHANGE_TOOL canon command,with the selected pocket as
- parameter. CHANGE_TOOL will:
+. execute a CHANGE_TOOL canon command,with the selected pocket as a parameter. CHANGE_TOOL will:
.. generate a rapid move to TOOL_CHANGE_POSITION if so set in INI
.. enqueue an EMC_TOOL_LOAD NML message to `task`.
. set the numberer parameters 5400-5413 according to the new tool
-. signal to `task` to stop calling the interpreter for readahead by
- returning INTERP_EXECUTE_FINISH since M6 is a queue buster.
+. signal to `task` to stop calling the interpreter for readahead by returning INTERP_EXECUTE_FINISH since M6 is a queue buster.
.What `task` does when it sees a CHANGE_TOOL command
-Again, not much more than passing the buck to `iocontrol` by sending it
-an EMC_TOOL_LOAD message, and waiting until `iocontrol` has done its
-thing.
+Again, not much more than passing the buck to `iocontrol` by sending it an EMC_TOOL_LOAD message,
+and waiting until `iocontrol` has done its thing.
[[remap:iocontrol-action-on-load]]
.Iocontrol action on EMC_TOOL_LOAD
@@ -2559,8 +2421,7 @@ When that has happened:
From there on, the interpreter has complete knowledge of the world model and continues with read ahead.
.Building the prolog and epilog for M6
-See the Python functions `change_prolog` and `change_epilog` in
-`configs/sim/axis/remap/toolchange/python/toolchange.py`.
+See the Python functions `change_prolog` and `change_epilog` in `configs/sim/axis/remap/toolchange/python/toolchange.py`.
=== How M61 (Change tool number) works
@@ -2568,9 +2429,7 @@ M61 requires a non-negative `Q`parameter (tool number).
If zero, this means 'unload tool', else 'set current tool number to Q'.
.Building the replacement for M61
-An example Python redefinition for M61 can be found in the
-`set_tool_number` function in
-`configs/sim/axis/remap/toolchange/python/toolchange.py`.
+An example Python redefinition for M61 can be found in the `set_tool_number` function in `configs/sim/axis/remap/toolchange/python/toolchange.py`.
== Status
@@ -2585,16 +2444,13 @@ An example Python redefinition for M61 can be found in the
== Changes
-- the method to return error messages and fail used to be
- 'self.set_errormsg(text)' followed by 'return INTERP_ERROR'.
+- the method to return error messages and fail used to be 'self.set_errormsg(text)' followed by 'return INTERP_ERROR'.
This has been replaced by merely returning a string from a Python handler or oword subroutine.
- This sets the error message and aborts the program. Previously there was no clean way to abort a Python oword
- subroutine.
+ This sets the error message and aborts the program. Previously there was no clean way to abort a Python oword subroutine.
== Debugging
-In the '[EMC]' section of the INI file the 'DEBUG' parameter can be changed to
-get various levels of debug messages when LinuxCNC is started from a terminal.
+In the '[EMC]' section of the INI file the 'DEBUG' parameter can be changed to get various levels of debug messages when LinuxCNC is started from a terminal.
----
Debug level, 0 means no messages. See src/emc/nml_intf/debugflags.h for others
diff --git a/docs/src/tooldatabase/tooldatabase.adoc b/docs/src/tooldatabase/tooldatabase.adoc
index 643cdd9608..85b29c3dcf 100644
--- a/docs/src/tooldatabase/tooldatabase.adoc
+++ b/docs/src/tooldatabase/tooldatabase.adoc
@@ -10,21 +10,16 @@
:hal: {basebackend@docbook:'':hal}
:ngc: {basebackend@docbook:'':ngc}
-Tool data is conventionally described by a tool table file specified
-by an inifile setting: [EMCIO]TOOL_TABLE=tooltable_filename. A tool
-table file consists of a text line for each available tool describing
-the tool's parameters, see <<sec:tool-table,Tool Table Format>>.
+Tool data is conventionally described by a tool table file specified by an inifile setting: [EMCIO]TOOL_TABLE=tooltable_filename.
+A tool table file consists of a text line for each available tool describing the tool's parameters, see <<sec:tool-table,Tool Table Format>>.
-The tool database interface provides an alternative method for
-obtaining tool data via a separate program that manages a database of
-tools.
+The tool database interface provides an alternative method for obtaining tool data via a separate program that manages a database of tools.
== Interface
=== INI file Settings
-INI file settings enable the (optional) operation of a user-provided
-tool database program:
+INI file settings enable the (optional) operation of a user-provided tool database program:
[source,{ini}]
----
@@ -32,108 +27,71 @@ tool database program:
DB_PROGRAM = db_program [args]
----
-When included, *db_program* specifies the path to a user-provided
-executable program that provides tooldata. Up to 10
-space-separated args may be included and passed to the
-*db_program* at startup.
+When included, *db_program* specifies the path to a user-provided executable program that provides tooldata.
+Up to 10 space-separated args may be included and passed to the *db_program* at startup.
[NOTE]
-INI file settings for [EMCIO]TOOL_TABLE are ignored when a *db_program*
-is specified.
+INI file settings for [EMCIO]TOOL_TABLE are ignored when a *db_program* is specified.
[NOTE]
-The *db_program* may be implemented in any language currently
-supported in LinuxCNC (e.g., BASH scripts, Python or Tcl scripts,
-C/C++ programs) as long as it conforms to the interface messages
-received on stdin and replied on stdout. A *db_program* could
-manage data from a flat file, a relational database (SQLite for
-example), or other data sources.
+The *db_program* may be implemented in any language currently supported in LinuxCNC (e.g., BASH scripts, Python or Tcl scripts, C/C++ programs)
+as long as it conforms to the interface messages received on stdin and replied on stdout.
+A *db_program* could manage data from a flat file, a relational database (SQLite for example), or other data sources.
=== *db_program* operation (v2.1)
When a *db_progam* is specified, operation is as follows:
-. At startup, LinuxCNC starts the *db_program* and connects
- to its stdin and stdout.
-
-. The *db_program* must respond by writing a single line acknowledgement
- consisting of a version string (e.g., "v2.1"). No tools will be
- available if the version is not compatible with the LinuxCNC database
- interface version.
-
-. Upon a successful acknowledgement, LinuxCNC issues a 'g' (*get*)
- command to request all tools. The *db_program* must respond with a
- sequence of replies to identify each available tool. The textual
- reply format is identical to the text line format used in conventional tool
- table files. A final response of "FINI" terminates the reply.
-
-. The *db_program* then enters an event wait loop to receive commands
- that indicate that tool data has been changed by LinuxCNC. Tool data
- changes include:
+. At startup, LinuxCNC starts the *db_program* and connects to its stdin and stdout.
+. The *db_program* must respond by writing a single line acknowledgement consisting of a version string (e.g., "v2.1").
+ No tools will be available if the version is not compatible with the LinuxCNC database interface version.
+. Upon a successful acknowledgement, LinuxCNC issues a 'g' (*get*) command to request all tools.
+ The *db_program* must respond with a sequence of replies to identify each available tool.
+ The textual reply format is identical to the text line format used in conventional tool table files.
+ A final response of "FINI" terminates the reply.
+. The *db_program* then enters an event wait loop to receive commands that indicate that tool data has been changed by LinuxCNC.
+ Tool data changes include:
* a) spindle loading(T__n__ M6)/unloading(T0 M6)
* b) tool parameter changes (G10L1P__n__ for example)
* c) tool substitutions (M61Q__n__).
-When a tool data change occurs, LinuxCNC sends a command to the
-*db_program* consisting of an identifying command letter followed by a
-full or abbreviated tool data line. The *db_program* must respond with
-a reply to confirm receipt. If the reply includes the text "'NAK'", a
-message is printed to stdout but execution continues. The "'NAK'"
-message signifies a lack of synchronization between the *db_program* and
-LinuxCNC -- accompanying text should give an indication for the cause of
-the fault.
+When a tool data change occurs, LinuxCNC sends a command to the *db_program* consisting of an identifying command letter followed by a full or abbreviated tool data line.
+The *db_program* must respond with a reply to confirm receipt.
+If the reply includes the text "'NAK'", a message is printed to stdout but execution continues.
+The "'NAK'" message signifies a lack of synchronization between the *db_program* and LinuxCNC -- accompanying text should give an indication for the cause of the fault.
The commands issued for tool data changes are:
-* "p" put data changes caused by G10L1, G10L10, G10L11 G-codes.
- The tool data line will include all elements of a tool table
- text line.
-
-* "l" spindle_load (T__n__M6). The tool data line includes only the 'T' and
- 'P' items identifying the relevant tool number and pocket number.
-
-* "u" spindle_unload (T0M6). The tool data line includes only the 'T'
- and 'P' items identifying the relevant tool number and pocket number
+* "p" put data changes caused by G10L1, G10L10, G10L11 G-codes. The tool data line will include all elements of a tool table text line.
+* "l" spindle_load (T__n__M6). The tool data line includes only the 'T' and 'P' items identifying the relevant tool number and pocket number.
+* "u" spindle_unload (T0M6). The tool data line includes only the 'T' and 'P' items identifying the relevant tool number and pocket number.
[NOTE]
-When a NON_RANDOM tool changer is specified using
-[EMCIO]RANDOM_TOOL_CHANGER=0 (the default), the spindle_load command
-issued for T__n__M6 (or M61Q__n__) is: 'l T__n__ P0' (pocket 0 is the spindle).
+When a NON_RANDOM tool changer is specified using [EMCIO]RANDOM_TOOL_CHANGER=0 (the default),
+the spindle_load command issued for T__n__M6 (or M61Q__n__) is: 'l T__n__ P0' (pocket 0 is the spindle).
The spindle_unload command issued for T0M6 is 'u T0 P0'.
[NOTE]
-When a RANDOM tool changer is specified using
-[EMCIO]RANDOM_TOOL_CHANGER=1, a pair of spindle_unload/spindle_load
-commands are issued at each tool exchange. The pair of commands
-issued for T__n__M6 (or M61Q__n__) are 'u T__u__ P__m__' followed by 'l T__n__ P0' where
-__u__ is the current tool to be sent to pocket __m__ and __n__ is the new
-tool to load in the spindle (pocket '0'). By convention, a tool
-number of 0 is used to specify an empty tool,
+When a RANDOM tool changer is specified using [EMCIO]RANDOM_TOOL_CHANGER=1, a pair of spindle_unload/spindle_load commands are issued at each tool exchange.
+The pair of commands issued for T__n__M6 (or M61Q__n__) are 'u T__u__ P__m__' followed by 'l T__n__ P0',
+where __u__ is the current tool to be sent to pocket __m__ and __n__ is the new tool to load in the spindle (pocket '0').
+By convention, a tool number of 0 is used to specify an empty tool,
=== Usage
-Using a *db_program* does not change the way LinuxCNC operates but
-provides support for new database functionality for tool management.
-
-For example, a *db_program* database application can maintain the
-operating hours for all tools by tracking each load/unload of a tool.
-A machine could then have three 6 mm endmills in pockets 111, 112, and
-113 with the database application programmed to assign tool number 110
-to the 6 mm endmill with the fewest operating hours. Then, when a
-LinuxCNC program requests tool 110, the database would specify the
-appropriate pocket based on tool usage history.
-
-Tool data changes made within LinuxCNC ('p','u','l' commands) are
-pushed immediately to the *db_program* which is expected to
-synchronize its source data. By default, LinuxCNC requests for tool
-data ('g' commands) are made at startup only. A database program may
-update tool usage data on a continuous basis so long-lived LinuxCNC
-applications may benefit by refreshing the tool data provided by the
-*db_program*. The G-code command *G10L0* can be used to request a
-tool data reload ('g' command) from within G-code programs or by MDI.
-A reload operation is also typically provided by a Graphical User
-Interface (GUI) so that on-demand reloads can be requested. For
-example, a Python GUI application can use:
+Using a *db_program* does not change the way LinuxCNC operates but provides support for new database functionality for tool management.
+
+For example, a *db_program* database application can maintain the operating hours for all tools by tracking each load/unload of a tool.
+A machine could then have three 6 mm endmills in pockets 111, 112, and 113 with the database application programmed to assign tool number 110
+to the 6 mm endmill with the fewest operating hours.
+Then, when a LinuxCNC program requests tool 110, the database would specify the appropriate pocket based on tool usage history.
+
+Tool data changes made within LinuxCNC ('p','u','l' commands) are pushed immediately to the *db_program* which is expected to synchronize its source data.
+By default, LinuxCNC requests for tool data ('g' commands) are made at startup only.
+A database program may update tool usage data on a continuous basis so long-lived LinuxCNC applications may benefit by refreshing the tool data provided by the *db_program*.
+The G-code command *G10L0* can be used to request a tool data reload ('g' command) from within G-code programs or by MDI.
+A reload operation is also typically provided by a Graphical User Interface (GUI) so that on-demand reloads can be requested.
+For example, a Python GUI application can use:
[source,python]
----
@@ -142,11 +100,9 @@ from linuxcnc import command
command().load_tool_table()
----
-Alternatively, a *db_program* may push its local data changes to
-synchronize its data with LinuxCNC by using the load_tool_table()
-interface command. Commands which push changes to LinuxCNC may be
-rejected if the interpreter is running. The interpreter state can be
-checked before issuing a load_tool_table() command. Example:
+Alternatively, a *db_program* may push its local data changes to synchronize its data with LinuxCNC by using the load_tool_table() interface command.
+Commands which push changes to LinuxCNC may be rejected if the interpreter is running.
+The interpreter state can be checked before issuing a load_tool_table() command. Example:
[source,python]
----
@@ -160,31 +116,23 @@ else: # defer until interp not idle
...
----
-If the database application adds or removes tools after
-initialization, a call to tooldb_tools() must be issued with an
-updated user_tools list. The updated list of tools will
-be used on subsequent get commands or load_tool_table()
-requests.
+If the database application adds or removes tools after initialization, a call to tooldb_tools() must be issued with an updated user_tools list.
+The updated list of tools will be used on subsequent get commands or load_tool_table() requests.
[NOTE]
-Removal of a tool number should only be done if the tool number
-is not currently loaded in spindle.
+Removal of a tool number should only be done if the tool number is not currently loaded in spindle.
==== Debug Environmental Variables
-Exporting the environmental variable DB_SHOW enables LinuxCNC prints (to
-stdout) that show tool data retrieved from the *db_program* at startup
-and at subsequent reloading of tool data.
+Exporting the environmental variable DB_SHOW enables LinuxCNC prints (to stdout) that show tool data retrieved from the *db_program* at startup and at subsequent reloading of tool data.
-Exporting the environmental variable DB_DEBUG enables LinuxCNC prints (to
-stdout) for additional debugging information about interface activity.
+Exporting the environmental variable DB_DEBUG enables LinuxCNC prints (to stdout) for additional debugging information about interface activity.
=== Example program
-An example *db_program* (implemented as a Python script) is provided
-with the simulation examples. The program demonsrates the
-required operations to:
+An example *db_program* (implemented as a Python script) is provided with the simulation examples.
+The program demonsrates the required operations to:
. acknowledge startup version
. receive tool data requests: 'g' (*get* command)
@@ -194,14 +142,10 @@ required operations to:
=== Python tooldb module
-The example program uses a LinuxCNC provided Python module ('tooldb')
-that manages the low-level details for communication and version
-verification. This module uses callback functions specified by the
-*db_program* to respond to the 'g' (get) command and the commands that
-indicate tool data changes ('p', 'l', 'u').
+The example program uses a LinuxCNC provided Python module ('tooldb') that manages the low-level details for communication and version verification.
+This module uses callback functions specified by the *db_program* to respond to the 'g' (get) command and the commands that indicate tool data changes ('p', 'l', 'u').
-The *db_program* uses the 'tooldb' module by implementing the
-following Python code:
+The *db_program* uses the 'tooldb' module by implementing the following Python code:
[source,python]
----
@@ -237,51 +181,40 @@ tooldb_loop()
----
[NOTE]
-Use of 'tooldb' is not required -- it is provided as a demonstration
-of the required interface and as a convenience for implementing
-Python-based applications that interface with an external database.
+Use of 'tooldb' is not required -- it is provided as a demonstration of the required interface
+and as a convenience for implementing Python-based applications that interface with an external database.
== Simulation configs
-Simulation configs using the axis gui:
+Simulation configs using the AXIS gui:
. configs/sim/axis/db_demo/*db_ran*.ini (random_toolchanger)
. configs/sim/axis/db_demo/*db_nonran*.ini (nonrandom_toolchanger)
-Each sim config simulates a *db_program* implementing a database
-with 10 tools numbered 10--19.
+Each sim config simulates a *db_program* implementing a database with 10 tools numbered 10--19.
-The *db_program* is provided by a single script (db.py) and symbolic
-links to it for alternative uses: db_ran.py and db_nonran.py.
+The *db_program* is provided by a single script (db.py) and symbolic links to it for alternative uses: db_ran.py and db_nonran.py.
By default, the script implements random_toolchanger functionality.
-Nonrandom toolchanger functions are substituted if the link name
-includes the text "'nonran'".
-
-The sim configs demonstrate the use of the Python 'tooldb' interface
-module and implement a basic flat-file database that tracks tool time
-usage for multiple tools having equal diameters. The database rules
-support selection of the tool having the lowest operating time.
-
-The sim configs use a primary task to monitor and respond to tool
-updates initiated from within LinuxCNC. A periodic task updates
-tool time usage at reguar intervals. Separate, concurrent tasks
-are implemented as threads to demonstrate the code required when changes
-are initiated by the *db_program* and demonstrate methods for synchronizing
-LinuxCNC internal tooldata.
+Nonrandom toolchanger functions are substituted if the link name includes the text "'nonran'".
+
+The sim configs demonstrate the use of the Python 'tooldb' interface module and implement a basic flat-file database
+that tracks tool time usage for multiple tools having equal diameters.
+The database rules support selection of the tool having the lowest operating time.
+
+The sim configs use a primary task to monitor and respond to tool updates initiated from within LinuxCNC.
+A periodic task updates tool time usage at reguar intervals.
+Separate, concurrent tasks are implemented as threads to demonstrate the code required
+when changes are initiated by the *db_program* and demonstrate methods for synchronizing LinuxCNC internal tooldata.
Examples include:
. updates of tool parameters
. addition and removal of tool numbers
-A mutual exclusion lock is used to protect data from inconsistencies due
-to race conditions between LinuxCNC tooldata updates and the database
-application updates.
+A mutual exclusion lock is used to protect data from inconsistencies due to race conditions between LinuxCNC tooldata updates and the database application updates.
=== Notes
-When a *db_program* is used in conjunction with a random tool changer
-([EMCIO]RANDOM_TOOLCHANGER), LinuxCNC maintains a file
-('db_spindle.tbl' in the configuration directory) that consists of a
-single tool table line identifying the current tool in the spindle.
+When a *db_program* is used in conjunction with a random tool changer ([EMCIO]RANDOM_TOOLCHANGER),
+LinuxCNC maintains a file ('db_spindle.tbl' in the configuration directory) that consists of a single tool table line identifying the current tool in the spindle.
// vim: set syntax=asciidoc:
diff --git a/docs/src/user/starting-linuxcnc.adoc b/docs/src/user/starting-linuxcnc.adoc
index ae659870c7..9894e39bda 100644
--- a/docs/src/user/starting-linuxcnc.adoc
+++ b/docs/src/user/starting-linuxcnc.adoc
@@ -12,7 +12,7 @@ LinuxCNC is started with the script file 'linuxcnc'.
linuxcnc [options] [<INI-file>]
----
-.linuxcnc script options
+.`linuxcnc` script options
----
linuxcnc: Run LINUXCNC
@@ -21,10 +21,10 @@ Usage:
This help
$ linuxcnc [Options]
- Choose the configuration inifile graphically
+ Choose the configuration INI file graphically
$ linuxcnc [Options] path/to/your_ini_file
- Name the configuration inifile using its path
+ Name the configuration INI file using its path
$ linuxcnc [Options] -l
Use the previously used configuration inifile
@@ -32,15 +32,15 @@ Usage:
Options:
-d: Turn on "debug" mode
-v: Turn on "verbose" mode
- -k: Continue in the presence of errors in .hal files
+ -k: Continue in the presence of errors in HAL files
-t "tpmodulename [parameters]"
specify custom trajectory_planning_module
- overrides optional ini setting [TRAJ]TPMOD
+ overrides optional INI setting [TRAJ]TPMOD
-m "homemodulename [parameters]"
specify custom homing_module
- overrides optional ini setting [EMCMOT]HOMEMOD
- -H "dirname": search dirname for Halfiles before searching
- ini directory and system library:
+ overrides optional INI setting [EMCMOT]HOMEMOD
+ -H "dirname": search dirname for HAL files before searching
+ INI directory and system library:
/home/git/linuxcnc-dev/lib/hallib
Note:
The -H "dirname" option may be specified multiple times
diff --git a/docs/src/user/user-concepts.adoc b/docs/src/user/user-concepts.adoc
index ac84b13dc1..879141e656 100644
--- a/docs/src/user/user-concepts.adoc
+++ b/docs/src/user/user-concepts.adoc
@@ -19,29 +19,28 @@ before attempting to run a CNC machine with G-code.
[[sub:trajectory-planning]]
=== Trajectory Planning(((Trajectory Planning,TP)))
-Trajectory planning, in general, is the means by which LinuxCNC follows the
-path specified by your G-code program, while still operating within the
-limits of your machinery.
+Trajectory planning, in general,
+is the means by which LinuxCNC follows the path specified by your G-code program,
+while still operating within the limits of your machinery.
-A G-code program can never be fully obeyed. For example, imagine you
-specify as a single-line program the following move:
+A G-code program can never be fully obeyed.
+For example, imagine you specify as a single-line program the following move:
[source,{ngc}]
----
G1 X1 F10 (G1 is linear move, X1 is the destination, F10 is the speed)
----
-In reality, the whole move can't be made at F10, since the machine
-must accelerate from a stop, move toward X=1, and then decelerate to
-stop again. Sometimes part of the move is done at F10, but for many
-moves, especially short ones, the specified feed rate is never reached
-at all. Having short moves in your G-code can cause your machine to
-slow down and speed up for the longer moves if the 'naive cam detector'
-is not employed with G64 P__n__.
-
-The basic acceleration and deceleration described above is not complex
-and there is no compromise to be made. In the INI file the specified
-machine constraints such as maximum axis velocity and axis acceleration
+In reality, the whole move can't be made at F10,
+since the machine must accelerate from a stop, move toward X=1,
+and then decelerate to stop again.
+Sometimes part of the move is done at F10, but for many moves,
+especially short ones, the specified feed rate is never reached at all.
+Having short moves in your G-code can cause your machine to slow down
+and speed up for the longer moves if the 'naive cam detector' is not employed with G64 P__n__.
+
+The basic acceleration and deceleration described above is not complex and there is no compromise to be made.
+In the INI file the specified machine constraints, such as maximum axis velocity and axis acceleration,
must be obeyed by the trajectory planner.
For more information on the Trajectory Planner INI options see the
@@ -50,9 +49,9 @@ For more information on the Trajectory Planner INI options see the
[[sub:path-following]]
=== Path Following(((Trajectory Planning:Path Following)))
-A less straightforward problem is that of path following. When you
-program a corner in G-code, the trajectory planner can do several
-things, all of which are right in some cases:
+A less straightforward problem is that of path following.
+When you program a corner in G-code, the trajectory planner can do several things,
+all of which are right in some cases:
* It can decelerate to a stop exactly at the coordinates of the corner,
and then accelerate in the new direction.
@@ -60,85 +59,70 @@ things, all of which are right in some cases:
which is to keep the feed rate up while going through the corner,
making it necessary to round the corner off in order to obey machine constraints.
-You can see that there is a trade off here: you can slow down to get
-better path following, or keep the speed up and have worse path
-following. Depending on the particular cut, the material, the tooling,
-etc., the programmer may want to compromise differently.
+You can see that there is a trade off here: you can slow down to get better path following,
+or keep the speed up and have worse path following.
+Depending on the particular cut, the material, the tooling, etc., the programmer may want to compromise differently.
-Rapid moves also obey the current trajectory control. With moves long
-enough to reach maximum velocity on a machine with low acceleration and
-no path tolerance specified, you can get a fairly round corner.
+Rapid moves also obey the current trajectory control.
+With moves long enough to reach maximum velocity on a machine with low acceleration and no path tolerance specified,
+you can get a fairly round corner.
[[sub:programming-the-planner]]
=== Programming the Planner(((Trajectory Planning:Programming the Planner)))
The trajectory control commands are as follows:
-`G61`:: (Exact Path Mode) `G61` visits the programmed point exactly, even though
- that means it might temporarily come to a complete stop in order to
- change direction to the next programmed point.
-
-`G61.1`:: (Exact Stop Mode) `G61.1` tells the planner to come to an exact stop at every
- segment's end. The path will be followed exactly but complete feed stops can be destructive for the part or tool, depending on the specifics of the machining.
-
-`G64`:: (Blend Without Tolerance Mode) `G64` is the default setting when you
- start LinuxCNC. G64 is just blending and the naive cam detector is not
- enabled. G64 and G64 P0 tell the planner to sacrifice path following
- accuracy in order to keep the feed rate up. This is necessary for some
- types of material or tooling where exact stops are harmful, and can
- work great as long as the programmer is careful to keep in mind that
- the tool's path will be somewhat more curvy than the program specifies.
- When using G0 (rapid) moves with G64 use caution on clearance moves and
- allow enough distance to clear obstacles based on the acceleration
+`G61`:: (Exact Path Mode) `G61` visits the programmed point exactly,
+ even though that means it might temporarily come to a complete stop in order to change direction to the next programmed point.
+
+`G61.1`:: (Exact Stop Mode) `G61.1` tells the planner to come to an exact stop at every segment's end.
+ The path will be followed exactly but complete feed stops can be destructive for the part or tool, depending on the specifics of the machining.
+
+`G64`:: (Blend Without Tolerance Mode) `G64` is the default setting when you start LinuxCNC.
+ G64 is just blending and the naive cam detector is not enabled.
+ G64 and G64 P0 tell the planner to sacrifice path following accuracy in order to keep the feed rate up.
+ This is necessary for some types of material or tooling where exact stops are harmful,
+ and can work great as long as the programmer is careful to keep in mind
+ that the tool's path will be somewhat more curvy than the program specifies.
+ When using G0 (rapid) moves with G64 use caution on clearance moves and allow enough distance to clear obstacles based on the acceleration
capabilities of your machine.
-`G64 P- Q-`:: (Blend With Tolerance Mode) This enables the 'naive cam detector' and
- enables blending with a tolerance. If you program G64 P0.05, you tell
- the planner that you want continuous feed, but at programmed corners
- you want it to slow down enough so that the tool path can stay within
- 0.05 user units of the programmed path. The exact amount of slowdown
- depends on the geometry of the programmed corner and the machine
- constraints, but the only thing the programmer needs to worry about is
- the tolerance. This gives the programmer complete control over the path
- following compromise. The blend tolerance can be changed throughout the
- program as necessary. Beware that a specification of G64 P0 has the
- same effect as G64 alone (above), which is necessary for backward
- compatibility for old G-code programs. See the <<gcode:g64,G64 section>>
- of the G-code chapter.
-
-Blending without tolerance:: The controlled point will touch each specified
- movement at at least one point. The machine will never move at such a speed
- that it cannot come to an exact stop at the end of the current movement (or
- next movement, if you pause when blending has already started). The
- distance from the end point of the move is as large as it needs to be to
- keep up the best contouring feed.
+`G64 P- Q-`:: (Blend With Tolerance Mode) This enables the 'naive cam detector' and enables blending with a tolerance.
+ If you program G64 P0.05, you tell the planner that you want continuous feed,
+ but at programmed corners you want it to slow down enough so that the tool path can stay within 0.05 user units of the programmed path.
+ The exact amount of slowdown depends on the geometry of the programmed corner and the machine constraints,
+ but the only thing the programmer needs to worry about is the tolerance.
+ This gives the programmer complete control over the path following compromise.
+ The blend tolerance can be changed throughout the program as necessary.
+ Beware that a specification of G64 P0 has the same effect as G64 alone (above),
+ which is necessary for backward compatibility for old G-code programs.
+ See the <<gcode:g64,G64 section>> of the G-code chapter.
+
+Blending without tolerance:: The controlled point will touch each specified movement at at least one point.
+ The machine will never move at such a speed that it cannot come to an exact stop at the end of the current movement
+ (or next movement, if you pause when blending has already started).
+ The distance from the end point of the move is as large as it needs to be to keep up the best contouring feed.
Naive CAM Detector:: Successive G1 moves that involve only the XYZ axes
- that deviate less than Q- from a straight line are merged into a single
- straight line. This merged movement replaces the individual G1 movements
- for the purposes of blending with tolerance. Between successive movements,
- the controlled point will pass no more than P- from the actual endpoints of
- the movements. The controlled point will touch at least one point on
- each movement. The machine will never move at such a speed that it
- cannot come to an exact stop at the end of the current movement (or
- next movement, if you pause when blending has already started) On G2/3
- moves in the G17 (XY) plane when the maximum deviation of an arc from a
- straight line is less than the G64 Q- tolerance the arc is broken into
- two lines (from start of arc to midpoint, and from midpoint to end).
- those lines are then subject to the naive cam algorithm for lines.
- Thus, line-arc, arc-arc, and arc-line cases as well as line-line
- benefit from the 'naive cam detector'. This improves contouring
- performance by simplifying the path.
-
-In the following figure the blue line represents the actual machine
-velocity. The red lines are the acceleration capability of the machine.
-The horizontal lines below each plot is the planned move. The upper
-plot shows how the trajectory planner will slow the machine down when
-short moves are encountered to stay within the limits of the machines
-acceleration setting to be able to come to an exact stop at the end of
-the next move. The bottom plot shows the effect of the Naive Cam
-Detector to combine the moves and do a better job of keeping the
-velocity as planned.
+ that deviate less than Q- from a straight line are merged into a single straight line.
+ This merged movement replaces the individual G1 movements for the purposes of blending with tolerance.
+ Between successive movements, the controlled point will pass no more than P- from the actual endpoints of the movements.
+ The controlled point will touch at least one point on each movement.
+ The machine will never move at such a speed that it cannot come to an exact stop at the end of the current movement
+ (or next movement, if you pause when blending has already started).
+ On G2/3 moves in the G17 (XY) plane,
+ when the maximum deviation of an arc from a straight line is less than the G64 Q- tolerance,
+ the arc is broken into two lines (from start of arc to midpoint, and from midpoint to end).
+ Those lines are then subject to the naive cam algorithm for lines.
+ Thus, line-arc, arc-arc, and arc-line cases as well as line-line benefit from the 'naive cam detector'.
+ This improves contouring performance by simplifying the path.
+
+In the following figure the blue line represents the actual machine velocity.
+The red lines are the acceleration capability of the machine.
+The horizontal lines below each plot is the planned move.
+The upper plot shows how the trajectory planner will slow the machine down when short moves are encountered,
+to stay within the limits of the machines acceleration setting to be able to come to an exact stop at the end of the next move.
+The bottom plot shows the effect of the Naive Cam Detector to combine the moves and do a better job of keeping the velocity as planned.
.Naive CAM Detector
image::images/naive-cam.png["Naive CAM Detector",align="center"]
@@ -147,53 +131,40 @@ image::images/naive-cam.png["Naive CAM Detector",align="center"]
=== Planning Moves(((Trajectory Planning:Planning Moves)))
Make sure moves are 'long enough' to suit your machine/material.
-Principally because of the rule that the machine will never move at
-such a speed that it cannot come to a complete stop at the end of the
-current movement, there is a minimum movement length that will allow
-the machine to keep up a requested feed rate with a given acceleration
-setting.
-
-The acceleration and deceleration phase each use half the ini file
-MAX_ACCELERATION. In a blend that is an exact reversal, this causes the
-total axis acceleration to equal the ini file MAX_ACCELERATION. In
-other cases, the actual machine acceleration is somewhat less than the
-ini file acceleration
+Principally because of the rule that the machine will never move at such a speed
+that it cannot come to a complete stop at the end of the current movement,
+there is a minimum movement length that will allow the machine to keep up a requested feed rate with a given acceleration setting.
+
+The acceleration and deceleration phase each use half the INI file MAX_ACCELERATION.
+In a blend that is an exact reversal, this causes the total axis acceleration to equal the INI file MAX_ACCELERATION.
+In other cases, the actual machine acceleration is somewhat less than the INI file acceleration
//NOTE This is a duplicate paragraph to the one below without latexmath.
-To keep up the feed rate, the move must be longer than the distance it
-takes to accelerate from 0 to the desired feed rate and then stop
-again. Using A as *1/2* the ini file MAX_ACCELERATION
-and F as the feed rate *in units per second*, the acceleration time is
-*t~a~ = F/A* and the acceleration distance is
-*d~a~ = F*t~a~/2*. The deceleration time
-and distance are the same, making the critical distance
-*d = d~a~ + d~d~ = 2 * d~a~ = F^2^/A*.
+To keep up the feed rate,
+the move must be longer than the distance it takes to accelerate from 0 to the desired feed rate and then stop again.
+Using A as *1/2* the INI file MAX_ACCELERATION and F as the feed rate *in units per second*,
+the acceleration time is *t~a~ = F/A* and the acceleration distance is *d~a~ = F*t~a~/2*.
+The deceleration time and distance are the same, making the critical distance *d = d~a~ + d~d~ = 2 * d~a~ = F^2^/A*.
-For example, for a feed rate of 1 inch per second and an acceleration of
-*10 inches/sec^2^*, the critical distance is
-*1^2^/10 = 1/10 = 0.1 inches*.
+For example, for a feed rate of 1 inch per second and an acceleration of *10 inches/sec^2^*,
+the critical distance is *1^2^/10 = 1/10 = 0.1 inches*.
-For a feed rate of 0.5 inch per second, the critical distance is
-*5^2^/100 = 25/100 = 0.025* inches.
+For a feed rate of 0.5 inch per second, the critical distance is *5^2^/100 = 25/100 = 0.025* inches.
////
This section has been commented out until latexmath is working again.
-To keep up the feed rate, the move must be longer than the distance it
-takes to accelerate from 0 to the desired feed rate and then stop
-again. Using A as latexmath:[$\frac{1}{2}$] the ini file MAX_ACCELERATION
-and F as the feed rate *in units per second*, the acceleration time is
-latexmath:[$ ta = \frac{F}{A} $] and the acceleration distance is
-latexmath:[$ da = \frac{1}{2} \times F \times ta $]. The deceleration time
-and distance are the same, making the critical distance
-latexmath:[$ d = da + dd = 2 \times da = \frac{F^{2}}{A} $].
-
-For example, for a feed rate of 1 inch per second and an acceleration of
-latexmath:[$ 10 \frac{inch}{sec^{2}} $], the critical distance is
-latexmath:[$\frac{1^{2}}{10} = \frac{1}{10} = 0.1$] inch.
-For a feed rate of 0.5 inch per second, the critical distance is
-latexmath:[$ \frac{0.5^{2}}{10} = \frac{0.25}{10} = 0.025$] inch.
+To keep up the feed rate, the move must be longer than the distance it takes to accelerate from 0 to the desired feed rate and then stop again.
+Using A as latexmath:[$\frac{1}{2}$] the INI file MAX_ACCELERATION and F as the feed rate *in units per second*,
+the acceleration time is latexmath:[$ ta = \frac{F}{A} $]
+and the acceleration distance is latexmath:[$ da = \frac{1}{2} \times F \times ta $].
+The deceleration time and distance are the same,
+making the critical distance latexmath:[$ d = da + dd = 2 \times da = \frac{F^{2}}{A} $].
+
+For example, for a feed rate of 1 inch per second and an acceleration of latexmath:[$ 10 \frac{inch}{sec^{2}} $],
+the critical distance is latexmath:[$\frac{1^{2}}{10} = \frac{1}{10} = 0.1$] inch.
+For a feed rate of 0.5 inch per second, the critical distance is latexmath:[$ \frac{0.5^{2}}{10} = \frac{0.25}{10} = 0.025$] inch.
////
[[sec:g-code]]
@@ -201,124 +172,101 @@ latexmath:[$ \frac{0.5^{2}}{10} = \frac{0.25}{10} = 0.025$] inch.
=== Defaults
-When LinuxCNC first starts up many G- and M-codes are loaded by default. The
-current active G- and M-codes can be viewed on the MDI tab in the
-'Active G-Codes:' window in the AXIS interface. These G- and M-codes
-define the behavior of LinuxCNC and it is important that you understand what
-each one does before running LinuxCNC. The defaults can be changed when
-running a G-Code file and left in a different state than when you
-started your LinuxCNC session. The best practice is to set the defaults
-needed for the job in the preamble of your G-Code file and not assume
-that the defaults have not changed. Printing out the G-Code
-<<gcode:quick-reference-table,Quick Reference>> page can help you remember
-what each one is.
+When LinuxCNC first starts up many G- and M-codes are loaded by default.
+The current active G- and M-codes can be viewed on the MDI tab in the 'Active G-Codes:' window in the AXIS interface.
+These G- and M-codes define the behavior of LinuxCNC and
+it is important that you understand what each one does before running LinuxCNC.
+The defaults can be changed when running a G-Code file and left in a different state than when you started your LinuxCNC session.
+The best practice is to set the defaults needed for the job in the preamble of your G-Code file
+and not assume that the defaults have not changed.
+Printing out the G-Code <<gcode:quick-reference-table,Quick Reference>> page can help you remember what each one is.
=== Feed Rate
-How the feed rate is applied depends on if an axis involved with the
-move is a rotary axis. Read and understand the <<sub:feed-rate,Feed Rate>>
-section if you have a rotary axis or a lathe.
+How the feed rate is applied depends on if an axis involved with the move is a rotary axis.
+Read and understand the <<sub:feed-rate,Feed Rate>> section if you have a rotary axis or a lathe.
=== Tool Radius Offset
-Tool Radius Offset (G41/42) requires that the tool be able to touch
-somewhere along each programmed move without gouging the two adjacent
-moves. If that is not possible with the current tool diameter you will
-get an error. A smaller diameter tool may run without an error on the
-same path. This means you can program a cutter to pass down a path that
-is narrower than the cutter without any errors. See the
-<<sec:cutter-radius-compensation,Cutter Compensation>> Section
-for more information.
+Tool Radius Offset (G41/42) requires that the tool be able to touch somewhere along each programmed move
+without gouging the two adjacent moves.
+If that is not possible with the current tool diameter you will get an error.
+A smaller diameter tool may run without an error on the same path.
+This means you can program a cutter to pass down a path that is narrower than the cutter without any errors.
+See the <<sec:cutter-radius-compensation,Cutter Compensation>> section for more information.
== Homing
-After starting LinuxCNC each axis must be homed prior to running a program
-or running a MDI command.
+After starting LinuxCNC each axis must be homed prior to running a program or running a MDI command.
-If your machine does not have home switches a match mark on each axis
-can aid in homing the machine coordinates to the same place each time.
+If your machine does not have home switches a match mark on each axis can aid in homing the machine coordinates to the same place each time.
-Once homed your soft limits that are set in the ini file will be used.
+Once homed your soft limits that are set in the INI file will be used.
-If you want to deviate from the default behavior, or want to use the
-Mini interface you will need to set the option NO_FORCE_HOMING = 1 in
-the [TRAJ] section of your ini file.
+If you want to deviate from the default behavior, or want to use the Mini interface,
+you will need to set the option NO_FORCE_HOMING = 1 in the [TRAJ] section of your INI file.
More information on homing can be found in the Integrator Manual.
== Tool Changes
-There are several options when doing manual tool changes. See the
-<<sub:ini:sec:emcio,[EMCIO] section>> for information on configuration
-of these options. Also see the <<gcode:g28-g28.1,G28>> and <<gcode:g30-g30.1,G30>>
-section of the G-code chapter.
+There are several options when doing manual tool changes.
+See the <<sub:ini:sec:emcio,[EMCIO] section>> for information on configuration of these options.
+Also see the <<gcode:g28-g28.1,G28>> and <<gcode:g30-g30.1,G30>> section of the G-code chapter.
== Coordinate Systems
-The Coordinate Systems can be confusing at first. Before running a CNC
-machine you must understand the basics of the coordinate systems used
-by LinuxCNC. In depth information on the LinuxCNC Coordinate Systems
-is in the <<cha:coordinate-system,Coordinate System>> Section of this
-manual.
+The Coordinate Systems can be confusing at first.
+Before running a CNC machine you must understand the basics of the coordinate systems used by LinuxCNC.
+In depth information on the LinuxCNC Coordinate Systems is in the <<cha:coordinate-system,Coordinate System>> section of this manual.
=== G53 Machine Coordinate
-When you home LinuxCNC you set the G53 Machine Coordinate System to 0 for
-each axis homed.
+When you home LinuxCNC you set the G53 Machine Coordinate System to 0 for each axis homed.
No other coordinate systems or tool offsets are changed by homing.
-The only time you move in the G53 machine coordinate system is when
-you program a G53 on the same line as a move. Normally you are in the
-G54 coordinate system.
+The only time you move in the G53 machine coordinate system is when you program a G53 on the same line as a move.
+Normally you are in the G54 coordinate system.
=== G54-59.3 User Coordinates
-Normally you use the G54 Coordinate System. When an offset is applied to a
-current user coordinate system a small blue ball with lines will be at the
-<<sec:machine-coordinate-system, machine origin>> when your DRO is displaying
-'Position: Relative Actual' in Axis. If your offsets are temporary use the Zero
-Coordinate System from the Machine menu or program 'G10 L2 P1 X0 Y0 Z0'
-at the end of your G-code file. Change the 'P' number to suit the
-coordinate system you wish to clear the offset in.
+Normally you use the G54 Coordinate System.
+When an offset is applied to a current user coordinate system a small blue ball with lines
+will be at the <<sec:machine-coordinate-system, machine origin>> when your DRO is displaying 'Position: Relative Actual' in AXIS.
+If your offsets are temporary use the Zero Coordinate System from the Machine menu or program 'G10 L2 P1 X0 Y0 Z0'
+at the end of your G-code file.
+Change the 'P' number to suit the coordinate system you wish to clear the offset in.
-* Offsets stored in a user coordinate system are retained when LinuxCNC is
- shut down.
-* Using the 'Touch Off' button in Axis sets an offset for the chosen
- User Coordinate System.
+* Offsets stored in a user coordinate system are retained when LinuxCNC is shut down.
+* Using the 'Touch Off' button in AXIS sets an offset for the chosen User Coordinate System.
=== When You Are Lost
-If you're having trouble getting 0,0,0 on the DRO when you think you
-should, you may have some offsets programmed in and need to remove
-them.
+If you're having trouble getting 0,0,0 on the DRO when you think you should,
+you may have some offsets programmed in and need to remove them.
* Move to the Machine origin with G53 G0 X0 Y0 Z0
* Clear any G92 offset with G92.1
* Use the G54 coordinate system with G54
-* Set the G54 coordinate system to be the same as the
- machine coordinate system with G10 L2 P1 X0 Y0 Z0 R0
+* Set the G54 coordinate system to be the same as the machine coordinate system with 'G10 L2 P1 X0 Y0 Z0 R0'.
* Turn off tool offsets with G49
* Turn on the Relative Coordinate Display from the menu
-Now you should be at the machine origin X0 Y0 Z0 and the relative
-coordinate system should be the same as the machine coordinate system.
+Now you should be at the machine origin X0 Y0 Z0
+and the relative coordinate system should be the same as the machine coordinate system.
[[sec:machine-configurations]]
== Machine Configurations
-The following diagram shows a typical mill showing direction of travel
-of the tool and the mill table and limit switches. Notice how the mill table
-moves in the opposite direction of the Cartesian coordinate system arrows
-shown by the 'Tool Direction' image. This makes the 'tool' move in the
-correct direction in relation to the material.
-
-Note also the position of the limit switches and the direction of activation of
-their cams. Several combinations are possible, for example it is possible
-(contrary to the drawing) to place a single fixed limit switch in the middle of
-the table and two mobile cams to activate it. In this case the limits will be
-reversed, +X will be on the right of the table and -X on the left. This
-inversion does not change anything from the point of view of the direction of
-movement of the tool.
+The following diagram shows a typical mill showing direction of travel of the tool and the mill table and limit switches.
+Notice how the mill table moves in the opposite direction of the Cartesian coordinate system arrows shown by the 'Tool Direction' image.
+This makes the 'tool' move in the correct direction in relation to the material.
+
+Note also the position of the limit switches and the direction of activation of their cams.
+Several combinations are possible, for example it is possible (contrary to the drawing)
+to place a single fixed limit switch in the middle of the table and two mobile cams to activate it.
+In this case the limits will be reversed, +X will be on the right of the table and -X on the left.
+This inversion does not change anything from the point of view of the direction of movement of the tool.
.Typical Mill Configuration
image::images/mill-diagram_en.svg["Typical Mill Configuration",align="center"]
diff --git a/docs/src/user/user-intro.adoc b/docs/src/user/user-intro.adoc
index 60db9d9aa4..9e990fed40 100644
--- a/docs/src/user/user-intro.adoc
+++ b/docs/src/user/user-intro.adoc
@@ -6,101 +6,97 @@
== Introduction
-This document is focused on the use of LinuxCNC, it is intended for readers who
-have already installed and configured it.
+This document is focused on the use of LinuxCNC, it is intended for readers who have already installed and configured it.
Some information on installation is given in the following chapters.
-The complete documentation on installation and configuration can be
-found in the integrator's manual.
+The complete documentation on installation and configuration can be found in the integrator's manual.
[[sec:how-linuxcnc-works]]
== How LinuxCNC Works
-LinuxCNC is a suite of highly-customisable applications for the control of a Computer Numerically
-Controlled (CNC) mills and lathes, 3D printers, robots, laser cutters, plasma cutters and other automated
-devices. It is capable of providing coordinated control of up to 9 axes of movement.
+LinuxCNC is a suite of highly-customisable applications for the control of a Computer Numerically Controlled (CNC) mills and lathes,
+3D printers, robots, laser cutters, plasma cutters and other automated devices.
+It is capable of providing coordinated control of up to 9 axes of movement.
-At its heart, LinuxCNC consists of several key components that are integrated together to form one
-complete system:
+At its heart, LinuxCNC consists of several key components that are integrated together to form one complete system:
-* a Graphical User Interface (GUI), which forms the basic interface between the operator, the software
- and the CNC machine itself;
-* the <<cha:hal-introduction,Hardware Abstraction Layer>> (HAL), which provides a method of linking all
- the various internal virtual signals generated and received by LinuxCNC with the outside world, and
-* the high level controllers that coordinate the generation and execution of motion control of the CNC
- machine, namely the motion controller (EMCMOT), the discrete input/output controller (EMCIO) and the
- task executor (EMCTASK).
+* a Graphical User Interface (GUI), which forms the basic interface between the operator, the software and the CNC machine itself;
+* the <<cha:hal-introduction,Hardware Abstraction Layer>> (HAL),
+ which provides a method of linking all the various internal virtual signals generated and received by LinuxCNC with the outside world, and
+* the high level controllers that coordinate the generation and execution of motion control of the CNC machine,
+ namely the motion controller (EMCMOT), the discrete input/output controller (EMCIO) and the task executor (EMCTASK).
-The below illustration is a simple block diagram showing what a typical 3-axis CNC mill with stepper
-motors might look like:
+The below illustration is a simple block diagram showing what a typical 3-axis CNC mill with stepper motors might look like:
.Simple LinuxCNC Controlled Machine
image::images/whatstep1.png["Simple LinuxCNC Controlled Machine",align="center"]
-A computer running LinuxCNC sends a sequence of pulses via the parallel port to the stepper drives, each of
-which has one stepper motor connected to it. Each drive receives two independent signals; one signal to
-command the drive to move its associated stepper motor in a clockwise or anti-clockwise direction, and a
-second signal that defines the speed at which that stepper motor rotates.
+A computer running LinuxCNC sends a sequence of pulses via the parallel port to the stepper drives,
+each of which has one stepper motor connected to it. Each drive receives two independent signals;
+one signal to command the drive to move its associated stepper motor in a clockwise or anti-clockwise direction,
+and a second signal that defines the speed at which that stepper motor rotates.
-While a stepper motor system under parallel port control is illustrated, a LinuxCNC system can also take
-advantage of a wide variety of dedicated hardware motion control interfaces for increased speed and I/O
-capabilities. A full list of interfaces supported by LinuxCNC can be found on
-the https://wiki.linuxcnc.org/cgi-bin/wiki.pl?LinuxCNC_Supported_Hardware[Supported Hardware] page of the
-Wiki.
+While a stepper motor system under parallel port control is illustrated,
+a LinuxCNC system can also take advantage of a wide variety of dedicated hardware motion control interfaces for increased speed and I/O capabilities.
+A full list of interfaces supported by LinuxCNC can be found on the https://wiki.linuxcnc.org/cgi-bin/wiki.pl?LinuxCNC_Supported_Hardware[Supported Hardware] page of the Wiki.
-In most circumstances, users will create a configuration specific to their mill setup using either the
-<<cha:stepconf-wizard,Stepper Configuration Wizard>> (for CNC systems operating using the computers'
-parallel port) or the <<cha:pncconf-wizard,Mesa Hardware Wizard>> (for more advanced systems utilising a
-Mesa Anything I/O PCI card).
-Running either wizard will create several folders on the computers' hard drive containing a number of configuration files specific to that CNC machine, and an icon placed on the desktop to allow easy launching of LinuxCNC.
+In most circumstances,
+users will create a configuration specific to their mill setup using either the <<cha:stepconf-wizard,Stepper Configuration Wizard>>
+(for CNC systems operating using the computers' parallel port)
+or the <<cha:pncconf-wizard,Mesa Hardware Wizard>> (for more advanced systems utilising a Mesa Anything I/O PCI card).
+Running either wizard will create several folders on the computers' hard drive
+containing a number of configuration files specific to that CNC machine,
+and an icon placed on the desktop to allow easy launching of LinuxCNC.
-For example, if the Stepper Configuration Wizard was used to create a setup for the 3-axis CNC mill
-illustrated above entitled 'My_CNC', the folders created by the wizard would typically contain the
-following files:
+For example, if the Stepper Configuration Wizard was used to create a setup for the 3-axis CNC mill illustrated above entitled 'My_CNC',
+the folders created by the wizard would typically contain the following files:
* *Folder: `My_CNC`*
** *`My_CNC.ini`* +
- The INI file contains all the basic hardware information regarding the operation of the CNC mill such
- as the number of steps each stepper motor must turn to complete one full revolution, the maximum rate at
- which each stepper may operate at, the limits of travel of each axis or the configuration and behaviour of
- limit switches on each axis.
+ The INI file contains all the basic hardware information regarding the operation of the CNC mill,
+ such as the number of steps each stepper motor must turn to complete one full revolution,
+ the maximum rate at which each stepper may operate at,
+ the limits of travel of each axis or the configuration and behaviour of limit switches on each axis.
** *`My_CNC.hal`* +
- This HAL file contains information that tells LinuxCNC how to link the internal virtual signals to
- physical connections beyond the computer. For example, specifying pin 4 on the parallel port to send out
- the Z axis step direction signal, or directing LinuxCNC to cease driving the X axis motor when a limit
- switch is triggered on parallel port pin 13.
+ This HAL file contains information that tells LinuxCNC
+ how to link the internal virtual signals to physical connections beyond the computer.
+ For example, specifying pin 4 on the parallel port to send out the Z axis step direction signal,
+ or directing LinuxCNC to cease driving the X axis motor when a limit switch is triggered on parallel port pin 13.
** *`custom.HAL`* +
- Customisations to the mill configuration beyond the scope of the wizard may be performed by including
- further links to other virtual points within LinuxCNC in this HAL file. When starting a LinuxCNC session,
- this file is read and processed before the GUI is loaded. An example may include initiating Modbus
- communications to the spindle motor so that it is confirmed as operational before the GUI is displayed.
+ Customisations to the mill configuration beyond the scope of the wizard may be performed
+ by including further links to other virtual points within LinuxCNC in this HAL file.
+ When starting a LinuxCNC session, this file is read and processed before the GUI is loaded.
+ An example may include initiating Modbus communications to the spindle motor
+ so that it is confirmed as operational before the GUI is displayed.
** *`custom_postgui.hal`* +
- The custom_postgui HAL file allows further customisation of LinuxCNC, but differs from custom.HAL in
- that it is processed after the GUI is displayed. For example, after establishing Modbus communications to
- the spindle motor in custom.hal, LinuxCNC can use the custom_postgui file to link the spindle speed readout
- from the motor drive to a bargraph displayed on the GUI.
+ The custom_postgui HAL file allows further customisation of LinuxCNC,
+ but differs from custom.HAL in that it is processed after the GUI is displayed.
+ For example, after establishing Modbus communications to the spindle motor in custom.hal,
+ LinuxCNC can use the custom_postgui file to link the spindle speed readout from the motor drive to a bargraph displayed on the GUI.
** *`postgui_backup.hal`* +
- This is provided as a backup copy of the custom_postgui.hal file to allow the user to quickly restore a
- previously-working postgui HAL configuration. This is especially useful if the user wants to run the
- Configuration Wizard again under the same 'My_CNC' name in order to modify some parameters of the mill.
- Saving the mill configuration in the Wizard will overwrite the existing custom_postgui file while leaving
- the postgui_backup file untouched.
+ This is provided as a backup copy of the custom_postgui.hal file to allow the user
+ to quickly restore a previously-working postgui HAL configuration.
+ This is especially useful if the user wants to run the Configuration Wizard again under the same 'My_CNC' name
+ in order to modify some parameters of the mill.
+ Saving the mill configuration in the Wizard will overwrite the existing custom_postgui file
+ while leaving the postgui_backup file untouched.
** *`tool.tbl`* +
- A tool table file contains a parameterised list of any cutting tools used by the mill. These parameters
- can include cutter diameter and length, and is used to provide a catalogue of data that tells LinuxCNC how
- to compensate its motion for different sized tools within a milling operation.
+ A tool table file contains a parameterised list of any cutting tools used by the mill.
+ These parameters can include cutter diameter and length,
+ and is used to provide a catalogue of data that tells LinuxCNC
+ how to compensate its motion for different sized tools within a milling operation.
* *Folder: `nc_files`* +
- The nc_files folder is provided as a default location to store the G-code programs used to drive the
- mill. It also includes a number of subfolders with G-code examples.
+ The nc_files folder is provided as a default location to store the G-code programs used to drive the mill.
+ It also includes a number of subfolders with G-code examples.
[[sec:graphical-user-interfaces]]
== Graphical User Interfaces(((Graphical User Interfaces)))
A graphical user interface is the part of the LinuxCNC that the machine tool operator interacts with.
-LinuxCNC comes with several types of user interfaces which may be chosen from by editing
-certain fields contained in the <<cha:ini-configuration,INI file>>:
+LinuxCNC comes with several types of user interfaces
+which may be chosen from by editing certain fields contained in the <<cha:ini-configuration,INI file>>:
-AXIS:: <<cha:axis-gui,AXIS>>, the standard keyboard GUI interface. This is also the default GUI launched when a
- Configuration Wizard is used to create a desktop icon launcher:
+AXIS:: <<cha:axis-gui,AXIS>>, the standard keyboard GUI interface.
+ This is also the default GUI launched when a Configuration Wizard is used to create a desktop icon launcher:
[[fig:axis-graphical-interface]]
.AXIS, the standard keyboard GUI interface
@@ -125,9 +121,9 @@ GMOCCAPY:: <<cha:gmoccapy,GMOCCAPY>>, a touch screen GUI based on Gscreen. GMOCC
.GMOCCAPY, a touch screen GUI based on Gscreen
image::../gui/images/gmoccapy_3_axis.png["GMOCCAPY, a touch screen GUI based on Gscreen",align="center"]
-NGCGUI:: <<cha:ngcgui,NGCGUI>>, a subroutine GUI that provides wizard-style programming of G code. NGCGUI may be
- run as a standalone program or embedded into another GUI as a series of tabs. The following screen shot
- shows NGCGUI embedded into Axis:
+NGCGUI:: <<cha:ngcgui,NGCGUI>>, a subroutine GUI that provides wizard-style programming of G code.
+ NGCGUI may be run as a standalone program or embedded into another GUI as a series of tabs.
+ The following screenshot shows NGCGUI embedded into AXIS:
[[fig:ngcgui-graphical-interface-into-axis]]
.NGCGUI, a graphical interface integrated into AXIS
@@ -142,42 +138,40 @@ image::images/tklinuxcnc_fr.png["TkLinuxCNC graphical interface",align="center"]
Xemc:: an X-Window program
-halui:: A HAL based user interface allowing to control LinuxCNC using
- buttons and switches
+halui:: A HAL based user interface allowing to control LinuxCNC using buttons and switches
-linuxcncrsh:: A telnet based user interface allowing to send commands
- from remote computers.
+linuxcncrsh:: A telnet based user interface allowing to send commands from remote computers.
== Virtual Control Panels
As mentioned above, many of LinuxCNC's GUIs may be customized by the user.
-This may be done to add indicators, readouts, switches or sliders to the basic appearance of one of the GUIs for increased
-flexibility or functionality.
+This may be done to add indicators, readouts,
+switches or sliders to the basic appearance of one of the GUIs for increased flexibility or functionality.
Two styles of Virtual Control Panel are offered in LinuxCNC:
-PyVCP:: <<cha:pyvcp,'PyVCP'>>, a Python-based virtual control panel that can be added to the Axis GUI. PyVCP only
- utilises virtual signals contained within the Hardware Abstraction Layer, such as the spindle-at-speed
- indicator or the Emergency Stop output signal, and has a simple no-frills appearance. This makes it an
- excellent choice if the user wants to add a Virtual Control Panel with minimal fuss.
+PyVCP:: <<cha:pyvcp,'PyVCP'>>, a Python-based virtual control panel that can be added to the AXIS GUI.
+ PyVCP only utilises virtual signals contained within the Hardware Abstraction Layer,
+ such as the spindle-at-speed indicator or the Emergency Stop output signal, and has a simple no-frills appearance.
+ This makes it an excellent choice if the user wants to add a Virtual Control Panel with minimal fuss.
.PyVCP Example Embedded Into AXIS GUI
image::../gui/images/axis-pyvcp.png["PyVCP embedded into AXIS",align="center"]
-GladeVCP:: <<cha:glade-vcp,'GladeVCP'>>, a Glade-based virtual control panel that can be added to the Axis or Touchy
- GUIs. GladeVCP has the advantage over PyVCP in that it is not limited to the display or control of HAL
- virtual signals, but can include other external interfaces outside LinuxCNC such as window or network
- events. GladeVCP is also more flexible in how it may be configured to appear on the GUI:
+GladeVCP:: <<cha:glade-vcp,'GladeVCP'>>, a Glade-based virtual control panel that can be added to the AXIS or Touchy GUIs.
+ GladeVCP has the advantage over PyVCP in that it is not limited to the display or control of HAL virtual signals,
+ but can include other external interfaces outside LinuxCNC such as window or network events.
+ GladeVCP is also more flexible in how it may be configured to appear on the GUI:
.GladeVCP Example Embedded Into AXIS GUI
image::../gui/images/axis-gladevcp.png["GladeVCP embedded into AXIS",align="center"]
== Languages
-LinuxCNC uses translation files to translate LinuxCNC User Interfaces into many languages including French,
-German, Italian, Finnish, Russian, Romanian, Portuguese and Chinese. Assuming a translation has been
-created, LinuxCNC will automatically use whatever native language you log in with when starting the Linux
-operating system. If your language has not been translated, contact a developer on IRC, the mailing
-list or the User Forum for assistance.
+LinuxCNC uses translation files to translate LinuxCNC User Interfaces into many languages including
+French, German, Italian, Finnish, Russian, Romanian, Portuguese and Chinese.
+Assuming a translation has been created,
+LinuxCNC will automatically use whatever native language you log in with when starting the Linux operating system.
+If your language has not been translated, contact a developer on IRC, the mailing list or the User Forum for assistance.
[[sec:thinking-operator]]
== Think Like a CNC Operator
@@ -209,8 +203,7 @@ In human terms a manual command might be "turn on coolant" or "jog X at 25 inche
These are roughly equivalent to flipping a switch or turning the hand wheel for an axis.
These commands are normally handled on one of the graphical interfaces
by pressing a button with the mouse or holding down a key on the keyboard.
-In auto mode, a similar button or key press might be used to load or start the running of a whole program of G-code
-that is stored in a file.
+In auto mode, a similar button or key press might be used to load or start the running of a whole program of G-code that is stored in a file.
In the MDI mode the operator might type in a block of code and tell the machine to execute it
by pressing the <return> or <enter> key on the keyboard.
diff --git a/lib/python/glnav.py b/lib/python/glnav.py
index 4c3ffe4279..e1159f70ba 100644
--- a/lib/python/glnav.py
+++ b/lib/python/glnav.py
@@ -320,10 +320,10 @@ class GlNavBase:
self.recordMouse(x, y)
- def set_viewangle(self, lat, lon):
+ def set_viewangle(self, lat, lon, forcerotate=0):
self.lat = lat
self.lon = lon
- if self.perspective:
+ if forcerotate or self.perspective:
glRotateScene(self, 0.5, self.xcenter, self.ycenter, self.zcenter, 0, 0, 0, 0)
self._redraw()
diff --git a/lib/python/qtvcp/qt_pstat.py b/lib/python/qtvcp/qt_pstat.py
index 02da379277..51e84e78ba 100644
--- a/lib/python/qtvcp/qt_pstat.py
+++ b/lib/python/qtvcp/qt_pstat.py
@@ -42,18 +42,21 @@ class _PStat(object):
try:
self.WORKINGDIR = os.getcwd()
+
# widget directory
here = os.path.dirname(os.path.realpath(__file__))
self.LIBDIR = os.path.join(here,"lib")
self.WIDGETDIR = os.path.join(here, "widgets")
self.PLUGINDIR = os.path.join(here,"plugins")
+ self.VISMACHDIR = os.path.join(self.LIBDIR, "qt_vismach")
+
# Linuxcnc project base directory
self.BASEDIR = os.path.abspath(os.path.join(os.path.dirname(sys.argv[0]), ".."))
self.IMAGEDIR = os.path.join(self.BASEDIR, "share", "qtvcp", "images")
self.SCREENDIR = os.path.join(self.BASEDIR, "share", "qtvcp", "screens")
self.PANELDIR = os.path.join(self.BASEDIR, "share", "qtvcp", "panels")
self.RIPCONFIGDIR = os.path.join(self.BASEDIR, "configs", "sim", "qtvcp_screens")
- self.VISMACHDIR = os.path.join(self.BASEDIR, "lib", "python", "qtvcp", "lib", "qt_vismach")
+
# python RIP library directory
self.PYDIR = os.path.join(self.BASEDIR, "lib", "python")
sys.path.insert(0, self.PYDIR)
diff --git a/lib/python/qtvcp/widgets/camview_widget.py b/lib/python/qtvcp/widgets/camview_widget.py
index 798a5bbe53..0708c16260 100644
--- a/lib/python/qtvcp/widgets/camview_widget.py
+++ b/lib/python/qtvcp/widgets/camview_widget.py
@@ -40,9 +40,11 @@ LOG = logger.getLogger(__name__)
LIB_GOOD = True
try:
import cv2 as CV
+ DEFAULT_API = CV.CAP_ANY
except:
LOG.error('Qtvcp Error with camview - is python3-opencv installed?')
LIB_GOOD = False
+ DEFAULT_API = 0 # CV.CAP_ANY
import numpy as np
@@ -403,7 +405,7 @@ class CamView(QtWidgets.QWidget, _HalWidgetBase):
camera_number = QtCore.pyqtProperty(int, get_camnum, set_camnum, reset_camnum)
class WebcamVideoStream:
- def __init__(self, src=0, api=CV.CAP_ANY):
+ def __init__(self, src=0, api=DEFAULT_API):
# initialize the video camera stream and read the first frame
# from the stream
try:
diff --git a/lib/python/qtvcp/widgets/round_gauge.py b/lib/python/qtvcp/widgets/round_gauge.py
index d162947c0e..6182cae17f 100644
--- a/lib/python/qtvcp/widgets/round_gauge.py
+++ b/lib/python/qtvcp/widgets/round_gauge.py
@@ -77,11 +77,12 @@ class Gauge(QtWidgets.QWidget, _HalWidgetBase):
def draw_zones(self, qp, event, w):
segment1 = -45
- span1 = ((self._max_value - self._threshold) * 270) / self._max_value
+ span1 = int(((self._max_value - self._threshold) * 270) / self._max_value)
segment2 = span1 - 45
span2 = 270 - span1
rect = QRect()
- rect.setSize(QSize(w/2, w/2))
+ w = int(w/2)
+ rect.setSize(QSize(w, w))
rect.moveCenter(event.rect().center())
qp.setPen(QPen(self._zone1_color, self.arc_width, cap = Qt.FlatCap))
qp.drawArc(rect, segment1*16, span1*16)
@@ -90,6 +91,7 @@ class Gauge(QtWidgets.QWidget, _HalWidgetBase):
def draw_gauge(self, qp, event, w):
w *= 0.6
+ w =int(w)
rect = QRect()
rect.setSize(QSize(w, w))
rect.moveCenter(event.rect().center())
@@ -127,6 +129,7 @@ class Gauge(QtWidgets.QWidget, _HalWidgetBase):
def draw_center(self, qp, event, w):
w *= 0.2
+ w = int(w)
rect = QRect()
rect.setSize(QSize(w, w))
rect.moveCenter(event.rect().center())
@@ -162,13 +165,13 @@ class Gauge(QtWidgets.QWidget, _HalWidgetBase):
def draw_readout(self, qp, event, w):
center = event.rect().center()
rect = QRect()
- rect.setSize(QSize(w/4, w/8))
- rect.moveCenter(QPoint(center.x(), center.y() + w/4))
+ rect.setSize(QSize(int(w/4), int(w/8)))
+ rect.moveCenter(QPoint(center.x(), center.y() + int(w/4)))
text = "{}".format(self.value)
qp.setPen(QPen(Qt.white, 4))
qp.setFont(QFont('Lato Heavy', self._value_font_size))
qp.drawText(rect, Qt.AlignCenter, text)
- rect.moveCenter(QPoint(center.x(), center.y() + w/3))
+ rect.moveCenter(QPoint(center.x(), center.y() + int(w/3)))
text = self._gauge_label
qp.setFont(QFont('Lato Heavy', self._label_font_size))
qp.drawText(rect, Qt.AlignCenter, text)
diff --git a/lib/python/qtvcp/widgets/round_progress.py b/lib/python/qtvcp/widgets/round_progress.py
index 967518089c..5437f5f9ab 100644
--- a/lib/python/qtvcp/widgets/round_progress.py
+++ b/lib/python/qtvcp/widgets/round_progress.py
@@ -232,7 +232,7 @@ class RoundProgressBar(QWidget):
# !!! to revise
f = self.font()
# f.setPixelSize(innerRadius * max(0.05, (0.35 - self.decimals * 0.08)))
- f.setPixelSize(innerRadius * 1.8 / len(text))
+ f.setPixelSize(int(innerRadius * 1.8 / len(text)))
p.setFont(f)
textRect = innerRect
diff --git a/lib/python/vismach.py b/lib/python/vismach.py
index fff3ecc6f4..39f03731e9 100644
--- a/lib/python/vismach.py
+++ b/lib/python/vismach.py
@@ -1019,7 +1019,7 @@ def main(model, tool, work, size=10, hud=0, rotation_vectors=None, lat=0, lon=0)
# we want to be able to see the model from all angles
t.set_latitudelimits(-180, 180)
# set starting viewpoint if desired
- t.after(100, lambda: t.set_viewangle(lat, lon))
+ t.after(100, lambda: t.set_viewangle(lat, lon, forcerotate=1))
vcomp = hal.component("vismach")
vcomp.newpin("plotclear",hal.HAL_BIT,hal.HAL_IN)
diff --git a/scripts/linuxcnc.in b/scripts/linuxcnc.in
index 0fa78303ad..f8d5f18471 100644
--- a/scripts/linuxcnc.in
+++ b/scripts/linuxcnc.in
@@ -94,7 +94,7 @@ program_available () {
usage () {
P=${0##*/}
cat <<EOF
-$P: Run LINUXCNC
+$P: Run LinuxCNC
Usage:
$ $P -h
@@ -112,7 +112,7 @@ Usage:
Options:
-d: Turn on "debug" mode
-v: Turn on "verbose" mode
- -k: Continue in the presence of errors in .hal files
+ -k: Continue in the presence of errors in HAL files
-t "tpmodulename [parameters]"
specify custom trajectory_planning_module
overrides optional INI setting [TRAJ]TPMOD
diff --git a/share/qtvcp/screens/qtdragon/qtdragon_handler.py b/share/qtvcp/screens/qtdragon/qtdragon_handler.py
index 8601623faa..da0ab9560f 100644
--- a/share/qtvcp/screens/qtdragon/qtdragon_handler.py
+++ b/share/qtvcp/screens/qtdragon/qtdragon_handler.py
@@ -54,7 +54,8 @@ class HandlerClass:
self.h = halcomp
self.w = widgets
self.gcodes = GCodes(widgets)
- self.valid = QtGui.QDoubleValidator(-999.999, 999.999, 3)
+ # This validator precludes using comma as a decimal
+ self.valid = QtGui.QRegExpValidator(QtCore.QRegExp('-?[0-9]{0,6}[.][0-9]{0,3}'))
KEYBIND.add_call('Key_F11','on_keycall_F11')
KEYBIND.add_call('Key_F12','on_keycall_F12')
KEYBIND.add_call('Key_Pause', 'on_keycall_pause')
diff --git a/share/qtvcp/screens/qtdragon_hd/qtdragon_hd_handler.py b/share/qtvcp/screens/qtdragon_hd/qtdragon_hd_handler.py
index dc098b86e4..9277933bf0 100644
--- a/share/qtvcp/screens/qtdragon_hd/qtdragon_hd_handler.py
+++ b/share/qtvcp/screens/qtdragon_hd/qtdragon_hd_handler.py
@@ -55,7 +55,8 @@ class HandlerClass:
self.h = halcomp
self.w = widgets
self.gcodes = GCodes(widgets)
- self.valid = QtGui.QDoubleValidator(-999.999, 999.999, 3)
+ # This validator precludes using comma as a decimal
+ self.valid = QtGui.QRegExpValidator(QtCore.QRegExp('-?[0-9]{0,6}[.][0-9]{0,3}'))
self.styleeditor = SSE(widgets, paths)
KEYBIND.add_call('Key_F4', 'on_keycall_F4')
KEYBIND.add_call('Key_F12','on_keycall_F12')
diff --git a/src/Makefile b/src/Makefile
index bcc73fec0e..26ace8c83d 100644
--- a/src/Makefile
+++ b/src/Makefile
@@ -729,8 +729,9 @@ install-kernel-indep: install-dirs
$(EXE) ../bin/update_ini $(DESTDIR)$(bindir)
$(EXE) ../scripts/halreport $(DESTDIR)$(bindir)
$(FILE) $(filter ../lib/%.a ../lib/%.so.0,$(TARGETS)) $(DESTDIR)$(libdir)
- cp --no-dereference $(filter ../lib/%.so, $(TARGETS)) $(DESTDIR)$(libdir)
+ cp --no-dereference $(wildcard ../lib/*.so) $(DESTDIR)$(libdir)
-ldconfig $(DESTDIR)$(libdir)
+ $(FILE) ../lib/linuxcnc/canterp.so $(DESTDIR)$(libdir)/linuxcnc
$(FILE) $(HEADERS) $(DESTDIR)$(includedir)/linuxcnc/
$(TREE) $(NC_FILES) $(DESTDIR)$(ncfilesdir)
$(EXE) ../nc_files/M101 $(DESTDIR)$(ncfilesdir)
diff --git a/src/emc/canterp/Submakefile b/src/emc/canterp/Submakefile
index e765844302..37e616ae58 100644
--- a/src/emc/canterp/Submakefile
+++ b/src/emc/canterp/Submakefile
@@ -1,9 +1,9 @@
-LIBCANTERPSRCS := emc/canterp/canterp.cc
-USERSRCS += $(LIBCANTERPSRCS)
-TARGETS += ../lib/libcanterp.so ../lib/libcanterp.so.0
-$(call TOOBJSDEPS, $(LIBCANTERPSRCS)) : EXTRAFLAGS=-fPIC
-../lib/libcanterp.so.0: $(patsubst %.cc,objects/%.o,$(LIBCANTERPSRCS)) ../lib/liblinuxcncini.so ../lib/librs274.so
+CANTERPSRCS := emc/canterp/canterp.cc
+USERSRCS += $(CANTERPSRCS)
+TARGETS += ../lib/linuxcnc/canterp.so
+$(call TOOBJSDEPS, $(CANTERPSRCS)) : EXTRAFLAGS=-fPIC
+../lib/linuxcnc/canterp.so: $(patsubst %.cc,objects/%.o,$(CANTERPSRCS)) ../lib/liblinuxcncini.so ../lib/librs274.so
$(ECHO) Linking $(notdir $@)
- @mkdir -p ../lib
- @rm -f $@
- @$(CXX) $(LDFLAGS) -Wl,-soname,$(notdir $@) -shared -o $@ $^ $(LIBDL)
+ $(Q)mkdir -p ../lib/linuxcnc
+ $(Q)rm -f $@
+ $(Q)$(CXX) $(LDFLAGS) -Wl,-soname,$(notdir $@) -shared -o $@ $^ $(LIBDL)
diff --git a/src/emc/rs274ngc/interp_base.cc b/src/emc/rs274ngc/interp_base.cc
index cb8359c2ed..d598b6ae2f 100644
--- a/src/emc/rs274ngc/interp_base.cc
+++ b/src/emc/rs274ngc/interp_base.cc
@@ -24,20 +24,29 @@
InterpBase::~InterpBase() {}
InterpBase *interp_from_shlib(const char *shlib) {
- fprintf(stderr, "interp_from_shlib(%s)\n", shlib);
+ void * interp_lib;
+ char relative_interp[PATH_MAX];
+ char const * interp_path;
+
dlopen(NULL, RTLD_GLOBAL);
- void *interp_lib = dlopen(shlib, RTLD_NOW);
- if(!interp_lib) {
- fprintf(stderr, "emcTaskInit: could not open interpreter '%s': %s\n", shlib, dlerror());
- char relative_interp[PATH_MAX];
- snprintf(relative_interp, sizeof(relative_interp), "%s/%s",
- EMC2_HOME "/lib/emc2", shlib);
- interp_lib = dlopen(relative_interp, RTLD_NOW);
+
+ if (shlib[0] == '/') {
+ // The passed-in .so name is an absolute path, use it directly.
+ interp_path = shlib;
+ } else {
+ // The passed-in .so name is a relative path or just a bare
+ // filename, look for it in `${EMC2_HOME}/lib/linuxcnc`.
+ snprintf(relative_interp, sizeof(relative_interp), "%s/%s", EMC2_HOME "/lib/linuxcnc", shlib);
+ interp_path = relative_interp;
}
+
+ interp_lib = dlopen(interp_path, RTLD_NOW);
if(!interp_lib) {
- fprintf(stderr, "emcTaskInit: could not open interpreter '%s': %s\n", shlib, dlerror());
- return 0;
+ fprintf(stderr, "emcTaskInit: could not open interpreter '%s': %s\n", interp_path, dlerror());
+ return 0;
}
+ fprintf(stderr, "emcTaskInit: using custom interpreter '%s'\n", interp_path);
+
typedef InterpBase* (*Constructor)();
Constructor constructor = (Constructor)dlsym(interp_lib, "makeInterp");
if(!constructor) {
diff --git a/src/emc/task/emctask.cc b/src/emc/task/emctask.cc
index 153dbf79b5..5a5fb4b169 100644
--- a/src/emc/task/emctask.cc
+++ b/src/emc/task/emctask.cc
@@ -443,6 +443,10 @@ int emcTaskPlanInit()
if((inistring = inifile.Find("INTERPRETER", "TASK"))) {
pinterp = interp_from_shlib(inistring);
fprintf(stderr, "interp_from_shlib() -> %p\n", pinterp);
+ if (!pinterp) {
+ fprintf(stderr, "failed to load [TASK]INTERPRETER (%s)\n", inistring);
+ return -1;
+ }
}
inifile.Close();
}
diff --git a/src/emc/usr_intf/axis/extensions/emcmodule.cc b/src/emc/usr_intf/axis/extensions/emcmodule.cc
index d8b5e95c4f..9eedd02630 100644
--- a/src/emc/usr_intf/axis/extensions/emcmodule.cc
+++ b/src/emc/usr_intf/axis/extensions/emcmodule.cc
@@ -327,7 +327,13 @@ static PyMemberDef Stat_members[] = {
// task
{(char*)"task_mode", T_INT, O(task.mode), READONLY},
- {(char*)"task_state", T_INT, O(task.state), READONLY},
+ {(char*)"task_state", T_INT, O(task.state), READONLY,
+ "Current Task state. Possible values:\n"
+ " STATE_ESTOP: E-Stop is active.\n"
+ " STATE_ESTOP_RESET: E-Stop is reset (cleared) but machine is off.\n"
+ " STATE_OFF: Same as STATE_ESTOP_RESET, this one is not used.\n"
+ " STATE_ON: Machine is out of E-Stop and is powered on.\n"
+ },
{(char*)"exec_state", T_INT, O(task.execState), READONLY},
{(char*)"interp_state", T_INT, O(task.interpState), READONLY},
{(char*)"call_level", T_INT, O(task.callLevel), READONLY},
@@ -1435,7 +1441,14 @@ static PyMethodDef Command_methods[] = {
{"teleop_enable", (PyCFunction)teleop, METH_VARARGS},
{"traj_mode", (PyCFunction)set_traj_mode, METH_VARARGS},
{"wait_complete", (PyCFunction)wait_complete, METH_VARARGS},
- {"state", (PyCFunction)state, METH_VARARGS},
+ {"state", (PyCFunction)state, METH_VARARGS,
+ "state(NEW_STATE) - Set the machine E-Stop & Power-On state.\n"
+ "Possible values for `NEW_STATE` are:\n"
+ " STATE_ESTOP: Power off and enter E-Stop mode.\n"
+ " STATE_ESTOP_RESET: Reset (leave) E-Stop mode, but remain powered off.\n"
+ " STATE_ON: Power on (only works from STATE_ESTOP_RESET state).\n"
+ " STATE_OFF: Power off (only works from STATE_ON state).\n"
+ },
{"mdi", (PyCFunction)mdi, METH_VARARGS},
{"mode", (PyCFunction)mode, METH_VARARGS},
{"feedrate", (PyCFunction)feedrate, METH_VARARGS},
@@ -1451,7 +1464,10 @@ static PyMethodDef Command_methods[] = {
{"abort", (PyCFunction)emcabort, METH_NOARGS},
{"task_plan_synch", (PyCFunction)task_plan_synch, METH_NOARGS},
{"override_limits", (PyCFunction)override_limits, METH_NOARGS},
- {"home", (PyCFunction)home, METH_VARARGS},
+ {"home", (PyCFunction)home, METH_VARARGS,
+ "home(JOINT) - Home the specified joint.\n"
+ "JOINT can be a valid joint number (0-9), or -1 to home all joints.\n"
+ },
{"unhome", (PyCFunction)unhome, METH_VARARGS},
{"jog", (PyCFunction)jog, METH_VARARGS,
"jog(JOG_CONTINUOUS, joint_flag, index, speed)\n"
diff --git a/src/emc/usr_intf/gmoccapy/getiniinfo.py b/src/emc/usr_intf/gmoccapy/getiniinfo.py
index 67a944b7e5..c11f949029 100644
--- a/src/emc/usr_intf/gmoccapy/getiniinfo.py
+++ b/src/emc/usr_intf/gmoccapy/getiniinfo.py
@@ -472,3 +472,15 @@ class GetIniInfo:
print("**** GMOCCAPY GETINIINFO **** \nERROR getting machine units \n"
"please check [TRAJ] LINEAR_UNITS for a valid entry, found {0}".format(units))
return None
+
+ def get_user_command_file(self):
+ temp = self.inifile.find("DISPLAY", "USER_COMMAND_FILE")
+ if temp:
+ print("**** USER_COMMAND_FILE = " + temp)
+ return temp
+
+ def get_user_css_file(self):
+ temp = self.inifile.find("DISPLAY", "USER_CSS_FILE")
+ if temp:
+ print("**** USER_CSS_FILE = " + temp)
+ return temp
diff --git a/src/emc/usr_intf/gmoccapy/gmoccapy.glade b/src/emc/usr_intf/gmoccapy/gmoccapy.glade
index ee33e52cd3..19defd1555 100644
--- a/src/emc/usr_intf/gmoccapy/gmoccapy.glade
+++ b/src/emc/usr_intf/gmoccapy/gmoccapy.glade
@@ -6292,13 +6292,15 @@ to test your settings.</property>
<child>
<object class="GtkToggleButton" id="tbtn_estop">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Estop the machine
[F1]</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_emergency</property>
<signal name="toggled" handler="on_tbtn_estop_toggled" swapped="no"/>
</object>
@@ -6311,13 +6313,15 @@ to test your settings.</property>
<child>
<object class="GtkToggleButton" id="tbtn_on">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Turn the machine on/off
[F2]</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_machine_off</property>
<signal name="toggled" handler="on_tbtn_on_toggled" swapped="no"/>
</object>
@@ -6330,13 +6334,15 @@ to test your settings.</property>
<child>
<object class="GtkRadioButton" id="rbt_manual">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">enter manual mode to jog axis by hand or touch off
[F3]</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_manual</property>
<property name="active">True</property>
<property name="draw_indicator">False</property>
@@ -6353,13 +6359,15 @@ to test your settings.</property>
<child>
<object class="GtkRadioButton" id="rbt_mdi">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">enter MDI mode to launch G-code commands
[F5]</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_mdi</property>
<property name="draw_indicator">False</property>
<property name="group">rbt_auto</property>
@@ -6375,12 +6383,14 @@ to test your settings.</property>
<child>
<object class="GtkRadioButton" id="rbt_auto">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">enter auto mode to run programs</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_auto</property>
<property name="draw_indicator">False</property>
<signal name="pressed" handler="on_rbt_auto_pressed" swapped="no"/>
@@ -6395,12 +6405,14 @@ to test your settings.</property>
<child>
<object class="GtkToggleButton" id="tbtn_setup">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Enter the settings page, the default code is "123"</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_settings</property>
<signal name="toggled" handler="on_tbtn_setup_toggled" swapped="no"/>
</object>
@@ -6413,12 +6425,14 @@ to test your settings.</property>
<child>
<object class="GtkToggleButton" id="tbtn_user_tabs">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">show user tabs</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_user_tabs</property>
<signal name="toggled" handler="on_tbtn_user_tabs_toggled" swapped="no"/>
</object>
@@ -6458,6 +6472,7 @@ Date</property>
</child>
<child>
<object class="GtkNotebook" id="ntb_button">
+ <property name="height_request">62</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
<property name="show_tabs">False</property>
@@ -6471,12 +6486,14 @@ Date</property>
<child>
<object class="GtkButton" id="btn_homing">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">open homing button list</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_ref_menu</property>
<signal name="clicked" handler="on_btn_homing_clicked" swapped="no"/>
</object>
@@ -6489,12 +6506,14 @@ Date</property>
<child>
<object class="GtkButton" id="btn_touch">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">open touch off button list</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_touch_off</property>
<signal name="clicked" handler="on_btn_touch_clicked" swapped="no"/>
</object>
@@ -6506,7 +6525,7 @@ Date</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_0">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -6520,12 +6539,14 @@ Date</property>
<child>
<object class="GtkButton" id="btn_tool">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Open the tooleditor page</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_tools</property>
<property name="image_position">top</property>
<signal name="clicked" handler="on_btn_tool_clicked" swapped="no"/>
@@ -6538,7 +6559,7 @@ Date</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_1">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -6551,7 +6572,7 @@ Date</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_2">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -6567,13 +6588,15 @@ Date</property>
<property name="label" translatable="yes">World
Mode</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Switch motion mode between Joint and World mode
F12 or $ key does the same</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="toggled" handler="on_tbtn_switch_mode_toggled" swapped="no"/>
</object>
<packing>
@@ -6584,7 +6607,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_replace_mode_btn">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -6597,7 +6620,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_3">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -6611,12 +6634,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkToggleButton" id="tbtn_fullsize_preview0">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">make the preview as large as possible</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_fullsize_preview0_open</property>
<signal name="toggled" handler="on_tbtn_fullsize_preview_toggled" swapped="no"/>
</object>
@@ -6629,12 +6654,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_exit">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Close gmoccapy / leave the program</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_close</property>
<signal name="clicked" handler="on_btn_exit_clicked" swapped="no"/>
</object>
@@ -6718,12 +6745,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_load">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Load a new program</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_open</property>
<signal name="clicked" handler="on_btn_load_clicked" swapped="no"/>
</object>
@@ -6736,11 +6765,13 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_reload">
<property name="related_action">hal_action_reload</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="use_underline">True</property>
<child>
<object class="GtkImage" id="img_reload1">
@@ -6759,12 +6790,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_run">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Run the loaded program</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_run</property>
<signal name="clicked" handler="on_btn_run_clicked" swapped="no"/>
</object>
@@ -6777,12 +6810,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_stop">
<property name="related_action">hal_action_stop</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Stop the running program</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_stop</property>
<signal name="clicked" handler="on_btn_stop_clicked" swapped="no"/>
</object>
@@ -6795,12 +6830,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkToggleButton" id="tbtn_pause">
<property name="related_action">hal_tgl_pause</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Pause the running program</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_pause</property>
<signal name="toggled" handler="on_tbtn_pause_toggled" swapped="no"/>
</object>
@@ -6813,12 +6850,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_step">
<property name="related_action">hal_action_step</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Run the loaded program step by step</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_step</property>
</object>
<packing>
@@ -6830,12 +6869,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_from_line">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">run the program from a certain line, attention, that is dangerous, because the previous lines will not checked!</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_run_from</property>
<signal name="clicked" handler="on_btn_from_line_clicked" swapped="no"/>
</object>
@@ -6848,12 +6889,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkToggleButton" id="tbtn_optional_blocks">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Machine or not the optional blocks of the program. If the button is pressed, the optional blocks will not be machined. The button will indicate this by a yellow background.</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_skip_optional_inactive</property>
<signal name="toggled" handler="on_tbtn_optional_blocks_toggled" swapped="no"/>
</object>
@@ -6866,11 +6909,13 @@ F12 or $ key does the same</property>
<child>
<object class="GtkToggleButton" id="tbtn_fullsize_preview1">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_fullsize_preview1_open</property>
<signal name="toggled" handler="on_tbtn_fullsize_preview_toggled" swapped="no"/>
</object>
@@ -6883,12 +6928,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_edit">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Edit the loaded program</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_editor</property>
<signal name="clicked" handler="on_btn_edit_clicked" swapped="no"/>
</object>
@@ -7031,15 +7078,25 @@ F12 or $ key does the same</property>
<property name="homogeneous">True</property>
<child>
<object class="GtkButton" id="btn_delete">
- <property name="label" translatable="yes">delete MDI</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">delete MDI history</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_delete_clicked" swapped="no"/>
+ <child>
+ <object class="GtkLabel">
+ <property name="visible">True</property>
+ <property name="can_focus">False</property>
+ <property name="label" translatable="yes">Delete
+MDI history</property>
+ <property name="justify">center</property>
+ </object>
+ </child>
</object>
<packing>
<property name="expand">False</property>
@@ -7049,7 +7106,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_4">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7062,7 +7119,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_version">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7078,7 +7135,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_5">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7093,12 +7150,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_classicladder">
<property name="label" translatable="yes">Cl.-ladder</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Open classicladder</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_classicladder_clicked" swapped="no"/>
</object>
<packing>
@@ -7111,12 +7170,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_hal_scope">
<property name="label" translatable="yes">Hal-Scope</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">launch hal scope</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_hal_scope_clicked" swapped="no"/>
</object>
<packing>
@@ -7129,12 +7190,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_status">
<property name="label" translatable="yes">Status</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">launch linuxcnc status</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_status_clicked" swapped="no"/>
</object>
<packing>
@@ -7147,12 +7210,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_hal_meter">
<property name="label" translatable="yes">Hal Meter</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">launch hal meter</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="xalign">0.51999998092651367</property>
<signal name="clicked" handler="on_btn_hal_meter_clicked" swapped="no"/>
</object>
@@ -7166,12 +7231,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_calibration">
<property name="label" translatable="yes">Calibration</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">launch calibration</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_calibration_clicked" swapped="no"/>
</object>
<packing>
@@ -7184,12 +7251,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_show_hal">
<property name="label" translatable="yes">Halshow</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">opens the show hal tool</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_show_hal_clicked" swapped="no"/>
</object>
<packing>
@@ -7221,7 +7290,7 @@ F12 or $ key does the same</property>
<property name="homogeneous">True</property>
<child>
<object class="GtkLabel" id="lbl_space_6">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7235,9 +7304,13 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_reload_edit">
<property name="related_action">hal_action_reload</property>
+ <property name="width_request">90</property>
+ <property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_edit_menu_reload</property>
<property name="use_underline">True</property>
</object>
@@ -7250,10 +7323,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_save">
<property name="related_action">hal_action_save</property>
+ <property name="width_request">90</property>
+ <property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">save the file using the original name</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_edit_menu_save</property>
</object>
<packing>
@@ -7265,12 +7342,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_save_as">
<property name="related_action">hal_action_saveas</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">save the file with a new name</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_edit_menu_save_as</property>
</object>
<packing>
@@ -7281,7 +7360,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_7">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7294,7 +7373,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_8">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7308,12 +7387,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_new">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">clear the edit field and make a new file</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_edit_menu_new</property>
<signal name="clicked" handler="on_btn_new_clicked" swapped="no"/>
</object>
@@ -7325,7 +7406,7 @@ F12 or $ key does the same</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_9">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7339,12 +7420,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_keyb">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">Show or hide the virtual keyboard</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_edit_menu_keyboard</property>
<signal name="clicked" handler="on_btn_show_kbd_clicked" swapped="no"/>
</object>
@@ -7357,12 +7440,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_back_edit">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
<property name="receives_default">False</property>
<property name="tooltip_text" translatable="yes">Go back to main button list</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_edit_menu_close</property>
<signal name="clicked" handler="on_btn_back_clicked" swapped="no"/>
</object>
@@ -7396,12 +7481,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_delete_tool">
<property name="label" translatable="yes">Delete</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">delete selected tool or tools</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_delete_tool_clicked" swapped="no"/>
</object>
<packing>
@@ -7414,12 +7501,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_add_tool">
<property name="label" translatable="yes">Add</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">add a new tool to tool table</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_add_tool_clicked" swapped="no"/>
</object>
<packing>
@@ -7432,12 +7521,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_reload_tooltable">
<property name="label" translatable="yes">Reload</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">reload tool table from file</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_reload_tooltable_clicked" swapped="no"/>
</object>
<packing>
@@ -7450,12 +7541,14 @@ F12 or $ key does the same</property>
<object class="GtkButton" id="btn_apply_tool_changes">
<property name="label" translatable="yes">Apply</property>
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">apply the changes you made, G43 will be executed only if it is active G-code</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_apply_tool_changes_clicked" swapped="no"/>
</object>
<packing>
@@ -7467,12 +7560,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_select_tool_by_no">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Select a tool by number</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_select_tool_by_no_clicked" swapped="no"/>
<child>
<object class="GtkImage" id="img_tool_by_no">
@@ -7490,12 +7585,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_index_tool">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">change tool with the command M61 Q?, no machine move will be done</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_selected_tool_clicked" swapped="no"/>
<child>
<object class="GtkImage" id="img_index_tool">
@@ -7513,12 +7610,14 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_change_tool">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">change tool to the selected one</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_toolchange</property>
<signal name="clicked" handler="on_btn_selected_tool_clicked" swapped="no"/>
</object>
@@ -7531,13 +7630,15 @@ F12 or $ key does the same</property>
<child>
<object class="GtkButton" id="btn_tool_touchoff_x">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="sensitive">False</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">touch off the tool and set the value to the tool table</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_tool_touchoff_clicked" swapped="no"/>
<child>
<object class="GtkLabel">
@@ -7557,7 +7658,7 @@ tool x</property>
</child>
<child>
<object class="GtkLabel" id="lbl_hide_tto_x">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7571,13 +7672,15 @@ tool x</property>
<child>
<object class="GtkButton" id="btn_tool_touchoff_z">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="sensitive">False</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">touch off the tool and set the value to the tool table</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<signal name="clicked" handler="on_btn_tool_touchoff_clicked" swapped="no"/>
<child>
<object class="GtkLabel" id="btn_tool_touchoff_z_label">
@@ -7598,12 +7701,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_back_tool">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Go back to main button list</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_back_tool</property>
<signal name="clicked" handler="on_btn_back_clicked" swapped="no"/>
</object>
@@ -7637,12 +7742,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_home">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Move to your home directory</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_home</property>
<signal name="clicked" handler="on_btn_home_clicked" swapped="no"/>
</object>
@@ -7655,12 +7762,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_dir_up">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Move to parent directory</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_dir_up</property>
<signal name="clicked" handler="on_btn_dir_up_clicked" swapped="no"/>
</object>
@@ -7672,7 +7781,7 @@ tool z</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_10">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7686,12 +7795,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_sel_prev">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Select the previous file</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_sel_prev</property>
<property name="image_position">top</property>
<signal name="clicked" handler="on_btn_sel_prev_clicked" swapped="no"/>
@@ -7705,12 +7816,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_sel_next">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Select the next file</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_sel_next</property>
<property name="image_position">top</property>
<signal name="clicked" handler="on_btn_sel_next_clicked" swapped="no"/>
@@ -7724,12 +7837,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_jump_to">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Jump to user defined directory</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_jump_to</property>
<property name="image_position">top</property>
<signal name="clicked" handler="on_btn_jump_to_clicked" swapped="no"/>
@@ -7742,7 +7857,7 @@ tool z</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_11">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7756,12 +7871,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_select">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">select the highlighted file and return the path</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_select</property>
<property name="image_position">top</property>
<signal name="clicked" handler="on_btn_select_clicked" swapped="no"/>
@@ -7774,7 +7891,7 @@ tool z</property>
</child>
<child>
<object class="GtkLabel" id="lbl_space_12">
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">False</property>
@@ -7788,12 +7905,14 @@ tool z</property>
<child>
<object class="GtkButton" id="btn_back_file_load">
<property name="use_action_appearance">False</property>
- <property name="width_request">85</property>
+ <property name="width_request">90</property>
<property name="height_request">56</property>
<property name="visible">True</property>
<property name="can_focus">True</property>
<property name="receives_default">True</property>
<property name="tooltip_text" translatable="yes">Close without returning a file path</property>
+ <property name="halign">center</property>
+ <property name="valign">center</property>
<property name="image">img_back_file_load</property>
<signal name="clicked" handler="on_btn_back_clicked" swapped="no"/>
</object>
diff --git a/src/emc/usr_intf/gmoccapy/gmoccapy.py b/src/emc/usr_intf/gmoccapy/gmoccapy.py
index ba874759cf..eca7d42b79 100644
--- a/src/emc/usr_intf/gmoccapy/gmoccapy.py
+++ b/src/emc/usr_intf/gmoccapy/gmoccapy.py
@@ -83,7 +83,7 @@ sys.excepthook = excepthook
# constants
# # gmoccapy #"
-_RELEASE = " 3.4.0"
+_RELEASE = " 3.4.1"
_INCH = 0 # imperial units are active
_MM = 1 # metric units are active
@@ -101,7 +101,7 @@ _BB_LOAD_FILE = 8
#_BB_HOME_JOINTS will not be used, we will reorder the notebooks to get the correct page shown
# Default button size for bottom buttons
-_DEFAULT_BB_SIZE = (85, 56)
+_DEFAULT_BB_SIZE = (90, 56)
_TEMPDIR = tempfile.gettempdir() # Now we know where the tempdir is, usually /tmp
@@ -155,10 +155,6 @@ class gmoccapy(object):
gettext.install("gmoccapy", localedir=LOCALEDIR)
# CSS styling
- screen = Gdk.Screen.get_default()
- provider = Gtk.CssProvider()
- style_context = Gtk.StyleContext()
- style_context.add_provider_for_screen(screen, provider, Gtk.STYLE_PROVIDER_PRIORITY_APPLICATION)
css = b"""
button {
padding: 0;
@@ -167,11 +163,12 @@ class gmoccapy(object):
padding: 3px;
margin: 1px;
}
- #notification_close {
- padding: 8px;
- }
"""
+ screen = Gdk.Screen.get_default()
+ provider = Gtk.CssProvider()
provider.load_from_data(css)
+ style_context = Gtk.StyleContext()
+ style_context.add_provider_for_screen(screen, provider, Gtk.STYLE_PROVIDER_PRIORITY_APPLICATION)
# needed components to communicate with hal and linuxcnc
self.halcomp = hal.component("gmoccapy")
@@ -516,6 +513,44 @@ class gmoccapy(object):
cycle_time = self.get_ini_info.get_cycle_time()
GLib.timeout_add( cycle_time, self._periodic ) # time between calls to the function, in milliseconds
+ # This allows sourcing an user defined file
+ rcfile = "~/.gmoccapyrc"
+ user_command_file = self.get_ini_info.get_user_command_file()
+ if user_command_file:
+ rcfile = user_command_file
+ rcfile = os.path.expanduser(rcfile)
+ if os.path.exists(rcfile):
+ try:
+ exec(compile(open(rcfile, "rb").read(), rcfile, 'exec'))
+ except:
+ tb = traceback.format_exc()
+ print(tb, file=sys.stderr)
+ self.notification.add_message(_("Error in ") + rcfile + "\n" \
+ + _("Please check the console output."), ALERT_ICON)
+
+ # Custom css file, e.g.:
+ # button:checked {
+ # background: rgba(230,230,50,0.8);
+ # }
+
+ css_file = "~/.gmoccapy_css"
+ user_css_file = self.get_ini_info.get_user_css_file()
+ if user_css_file:
+ css_file = user_css_file
+ css_file = os.path.expanduser(css_file)
+ if os.path.exists(css_file):
+ provider_custom = Gtk.CssProvider()
+ try:
+ provider_custom.load_from_path(css_file)
+ style_context.add_provider_for_screen(screen, provider_custom, Gtk.STYLE_PROVIDER_PRIORITY_APPLICATION)
+ except:
+ tb = traceback.format_exc()
+ print(tb, file=sys.stderr)
+ self.notification.add_message(_("Error in ") + css_file + "\n" \
+ + _("Please check the console output."), ALERT_ICON)
+
+
+
def _get_ini_data(self):
self.get_ini_info = getiniinfo.GetIniInfo()
# get the axis list from INI
@@ -768,6 +803,8 @@ class gmoccapy(object):
def _new_button_with_predefined_image(self, name, size, image = None, image_name = None):
btn = Gtk.Button()
btn.set_size_request(*size)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.set_property("name", name)
try:
if image:
@@ -791,6 +828,8 @@ class gmoccapy(object):
image.set_size_request(72,48)
btn = Gtk.Button.new()
btn.set_size_request(*_DEFAULT_BB_SIZE)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.set_property("name", name)
try:
if filepath:
@@ -962,6 +1001,9 @@ class gmoccapy(object):
lbl.set_visible(True)
lbl.set_justify(Gtk.Justification.CENTER)
btn = Gtk.ToggleButton.new()
+ btn.set_size_request(*_DEFAULT_BB_SIZE)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.add(lbl)
btn.connect("toggled", self.on_tbtn_edit_offsets_toggled)
btn.set_property("tooltip-text", _("Press to edit the offsets"))
@@ -1020,6 +1062,9 @@ class gmoccapy(object):
lbl.show()
btn = self.widgets.offsetpage1.wTree.get_object("zero_g92_button")
+ btn.set_size_request(*_DEFAULT_BB_SIZE)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
self.widgets.offsetpage1.buttonbox.remove(btn)
btn.connect("clicked", self.on_btn_zero_g92_clicked)
btn.set_property("tooltip-text", _("Press to reset all G92 offsets"))
@@ -1029,6 +1074,9 @@ class gmoccapy(object):
if self.tool_measure_OK:
btn = Gtk.Button.new_with_label(_(" Block\nHeight"))
+ btn.set_size_request(*_DEFAULT_BB_SIZE)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.connect("clicked", self.on_btn_block_height_clicked)
btn.set_property("tooltip-text", _("Press to enter new value for block height"))
btn.set_property("name", "block_height")
@@ -1039,6 +1087,9 @@ class gmoccapy(object):
lbl.set_visible(True)
lbl.set_justify(Gtk.Justification.CENTER)
btn = Gtk.Button.new()
+ btn.set_size_request(*_DEFAULT_BB_SIZE)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.add(lbl)
btn.connect("clicked", self._on_btn_set_selected_clicked)
btn.set_property("tooltip-text", _("Press to set the selected coordinate system to be the active one"))
@@ -1253,6 +1304,8 @@ class gmoccapy(object):
for direction in ["+","-"]:
name = "{0}{1}".format(str(axis), direction)
btn = Gtk.Button.new_with_label(name.upper())
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.set_property("name", name)
btn.connect("pressed", self._on_btn_jog_pressed, name)
btn.connect("released", self._on_btn_jog_released, name)
@@ -1272,6 +1325,8 @@ class gmoccapy(object):
for direction in ["+","-"]:
name = "{0}{1}".format(str(joint), direction)
btn = Gtk.Button.new_with_label(name.upper())
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.set_property("name", name)
btn.connect("pressed", self._on_btn_jog_pressed, name)
btn.connect("released", self._on_btn_jog_released, name)
@@ -1328,6 +1383,9 @@ class gmoccapy(object):
if len(lbl) > 11:
lbl = lbl[0:10] + "\n" + lbl[11:20]
btn = Gtk.Button.new_with_label(lbl)
+ btn.set_size_request(*_DEFAULT_BB_SIZE)
+ btn.set_halign(Gtk.Align.CENTER)
+ btn.set_valign(Gtk.Align.CENTER)
btn.set_property("name","macro_{0}".format(pos))
btn.set_property("tooltip-text", _("Press to run macro {0}".format(name)))
btn.connect("clicked", self._on_btn_macro_pressed, name)
diff --git a/src/emc/usr_intf/gmoccapy/notification.py b/src/emc/usr_intf/gmoccapy/notification.py
index dabba0dffb..2e4508d526 100755
--- a/src/emc/usr_intf/gmoccapy/notification.py
+++ b/src/emc/usr_intf/gmoccapy/notification.py
@@ -114,7 +114,7 @@ class Notification(Gtk.Window):
default_style = Gtk.Button().get_style_context()
pixbuf = icon_theme_helper.load_symbolic_from_icon_theme(self.icon_theme, icon_name, self.icon_size, default_style)
icon.set_from_pixbuf(pixbuf)
- hbox.pack_start(icon, False, False, 0)
+ hbox.pack_start(icon, False, False, 3)
label = Gtk.Label()
label.set_line_wrap(True)
label.set_line_wrap_mode(Pango.WrapMode.WORD_CHAR)
@@ -132,6 +132,7 @@ class Notification(Gtk.Window):
label.set_markup(text)
else:
label.set_text(text)
+ label.set_xalign(0)
hbox.pack_start(label, False, False, 0)
btn_close = Gtk.Button()
btn_close.set_name("notification_close")
@@ -307,8 +308,8 @@ def main():
notification.icon_theme.append_search_path("../../../../share/gmoccapy/icons/") # relative from this file location
notification.icon_theme.append_search_path("../share/gmoccapy/icons/")
notification.icon_theme.append_search_path("/usr/share/gmoccapy/icons/")
- # notification.icon_theme.set_custom_theme("classic")
- notification.icon_theme.set_custom_theme("material")
+ notification.icon_theme.set_custom_theme("classic")
+ # notification.icon_theme.set_custom_theme("material")
# notification.icon_theme.set_custom_theme("material-light")
notification.add_message('This is a warning', 'dialog_warning')
notification.add_message('Hallo World this is a long string that have a linebreak ', 'dialog_information')
diff --git a/src/emc/usr_intf/gmoccapy/release_notes.txt b/src/emc/usr_intf/gmoccapy/release_notes.txt
index c2aa7dc0b6..7d0afebd4c 100644
--- a/src/emc/usr_intf/gmoccapy/release_notes.txt
+++ b/src/emc/usr_intf/gmoccapy/release_notes.txt
@@ -1,6 +1,14 @@
-- fixed sensitizing of user tab button on toggling "edit offsets" (#2111)
-- fix error on creating new G-code file when RS274NGC_STARTUP_CODE is not set
- (#2057)
+ver 3.4.1
+
+ New features:
+ - added possibility for sourcing an user defined file (rcfile)
+ - added option to use external CSS file
+
+ Fixes:
+ - some optical fixes (button properties, left align text in notification)
+ - fixed sensitizing of user tab button on toggling "edit offsets" (#2111)
+ - fix error on creating new G-code file when RS274NGC_STARTUP_CODE is not set
+ (#2057)
ver 3.4.0
diff --git a/src/hal/components/axistest.comp b/src/hal/components/axistest.comp
index de7ca2f7da..b1bdc541d0 100644
--- a/src/hal/components/axistest.comp
+++ b/src/hal/components/axistest.comp
@@ -20,7 +20,7 @@ param r float elapsed "Current value of the internal timer";
variable int timer_on;
function update;
license "GPL";
-author "Chris S Morley";
+author "Chris S. Morley";
;;
extern double fabs(double);
diff --git a/src/hal/components/bldc.comp b/src/hal/components/bldc.comp
index 731afce412..751ff092f4 100644
--- a/src/hal/components/bldc.comp
+++ b/src/hal/components/bldc.comp
@@ -5,11 +5,9 @@ component bldc """BLDC and AC-servo control component
pin in bit hall1 if personality & 0x01 "Hall sensor signal 1";
pin in bit hall2 if personality & 0x01 "Hall sensor signal 2";
pin in bit hall3 if personality & 0x01 "Hall sensor signal 3";
-pin out bit hall_error if personality & 0x01 """Indicates that the selected hall
-pattern gives inconsistent rotor position data. This can be due to the pattern
-being wrong for the motor, or one or more sensors being unconnected or broken.
-A consistent pattern is not neceesarily valid, but an inconsistent one can never
-be valid.""";
+pin out bit hall_error if personality & 0x01 """Indicates that the selected hall pattern gives inconsistent rotor position data.
+This can be due to the pattern being wrong for the motor, or one or more sensors being unconnected or broken.
+A consistent pattern is not neceesarily valid, but an inconsistent one can never be valid.""";
pin in bit C1 if (personality & 0x10) "Fanuc Gray-code bit 0 input";
pin in bit C2 if (personality & 0x10) "Fanuc Gray-code bit 1 input";
@@ -22,44 +20,32 @@ pin in float lead-angle = 90 if personality & 0x06
"The phase lead between the electrical vector and the rotor position in degrees";
pin in bit rev
-"""Set this pin true to reverse the motor. Negative PWM amplitudes will also
-reverse the motor and there will generally be a Hall pattern that runs the motor
-in each direction too.""";
+"""Set this pin true to reverse the motor. Negative PWM amplitudes will alsoreverse the motor and there will generally be a Hall pattern that runs the motor in each direction too.""";
-pin in float frequency if (personality & 0x0F)==0 """Frequency input for motors
-with no feedback at all, or those with only an index (which is ignored)""";
+pin in float frequency if (personality & 0x0F)==0 """Frequency input for motors with no feedback at all, or those with only an index (which is ignored)""";
-pin in float initvalue = 0.2 if personality & 0x04 """The current to be used for
-the homing sequence in applications where an incremental encoder is used with no
-hall-sensor feedback""";
+pin in float initvalue = 0.2 if personality & 0x04 """The current to be used for the homing sequence in applications where an incremental encoder is used with no hall-sensor feedback""";
pin in signed rawcounts = 0 if personality & 0x06
-"""Encoder counts input. This must be linked to the encoder rawcounts pin or
-encoder index resets will cause the motor commutation to fail""";
+"""Encoder counts input. This must be linked to the encoder rawcounts pin or encoder index resets will cause the motor commutation to fail.""";
-pin io bit index-enable if personality & 0x08 """This pin should be connected to
-the associated encoder index-enable pin to zero the encoder when it passes index
-This is only used indicate to the bldc control component that an index has been
-seen.""";
+pin io bit index-enable if personality & 0x08 """This pin should be connected to the associated encoder index-enable pin to zero the encoder when it passes index.
+This is only used indicate to the bldc control component that an index has been seen.""";
pin in bit init if (personality & 0x05) == 4
-"""A rising edge on this pin starts the motor alignment sequence. This pin
-should be connected in such a way that the motors re-align any time that
-encoder monitoring has been interrupted. Typically this will only be at machine
-power-off.
-The alignment process involves powering the motor phases in such a way as to
-put the motor in a known position. The encoder counts are then stored in the
-\\fBoffset\\fP parameter. The alignment process will tend to cause a following
-error if it is triggered while the axis is enabled, so should be set before the
-matching axis.N.enable pin. The complementary \\fBinit-done\\fP pin can be used
-to handle the required sequencing.
-
-Both pins can be ignored if the encoder offset is known explicitly, such as is
-the case with an absolute encoder. In that case the \\fBoffset\\fP parameter
-can be set directly in the HAL file.""";
+"""A rising edge on this pin starts the motor alignment sequence.
+This pinshould be connected in such a way that the motors re-align any time that encoder monitoring has been interrupted.
+Typically this will only be at machine power-off.
+The alignment process involves powering the motor phases in such a way as to put the motor in a known position.
+The encoder counts are then stored in the \\fBoffset\\fP parameter.
+The alignment process will tend to cause a following error if it is triggered while the axis is enabled, so should be set before the matching axis.N.enable pin.
+The complementary \\fBinit-done\\fP pin can be used to handle the required sequencing.
+
+Both pins can be ignored if the encoder offset is known explicitly, such as is the case with an absolute encoder.
+In that case the \\fBoffset\\fP parameter can be set directly in the HAL file.""";
pin out bit init-done = 0 if (personality & 0x05) == 4
-"Indicates homing sequence complete";
+"Indicates homing sequence complete.";
pin out float A-value if (personality & 0xF00)==0 "Output amplitude for phase A";
pin out float B-value if (personality & 0xF00)==0 "Output amplitude for phase B";
@@ -90,18 +76,16 @@ pin out bit C4-out if (personality & 0x800) "Fanuc Gray-code bit 2 output";
pin out bit C8-out if (personality & 0x800) "Fanuc Gray-code bit 3 output";
pin out float phase-angle = 0
-"""Phase angle including lead/lag angle after encoder zeroing etc. Useful for
-angle/current drives. This value has a range of 0 to 1 and measures electrical
-revolutions. It will have two zeros for a 4 pole motor, three for a 6-pole etc.""";
+"""Phase angle including lead/lag angle after encoder zeroing, etc. Useful for angle/current drives.
+This value has a range of 0 to 1 and measures electrical revolutions.
+It will have two zeros for a 4 pole motor, three for a 6-pole, etc.""";
pin out float rotor-angle = 0
-"""Rotor angle after encoder zeroing etc. Useful for angle/current drives which
-add their own phase offset such as the 8I20. This value has a range of 0 to 1
-and measures electrical revolutions. It will have two zeros for a 4 pole motor,
-three for a 6-pole etc.""";
+"""Rotor angle after encoder zeroing etc. Useful for angle/current drives which add their own phase offset such as the 8I20.
+This value has a range of 0 to 1 and measures electrical revolutions. It will have two zeros for a 4 pole motor, three for a 6-pole, etc.""";
pin out float out
-"Current output, including the effect of the dir pin and the alignment sequence";
+"Current output, including the effect of the dir pin and the alignment sequence.";
pin out bit out-dir
"Direction output, high if /fBvalue/fR is negative XOR /fBrev/fR is true.";
@@ -122,22 +106,18 @@ param rw signed encoder-offset = 0 if personality & 0x0A
encoder zero modulo the number of counts per electrical revolution""";
param r signed offset_measured = 0 if personality & 0x04
"""The encoder offset measured by the homing sequence (in certain modes)""";
-param rw float drive-offset = 0 """The angle, in degrees,
-applied to the commanded angle by the drive in degrees. This value is only used
-during the homing sequence of drives with incremental encoder feedback. It is
-used to back-calculate from commanded angle to actual phase angle. It is only
-relevant to drives which expect rotor-angle input rather than phase-angle
-demand. Should be 0 for most drives.""";
+param rw float drive-offset = 0 """The angle, in degrees, applied to the commanded angle by the drive in degrees.
+This value is only used during the homing sequence of drives with incremental encoder feedback.
+It is used to back-calculate from commanded angle to actual phase angle.
+It is only relevant to drives which expect rotor-angle input rather than phase-angle demand. Should be 0 for most drives.""";
param rw unsigned output-pattern=25 if personality & 0x400
-"""Commutation pattern to be output in Hall Signal translation mode. See the
-description of /fBpattern/fR for details.""";
+"""Commutation pattern to be output in Hall Signal translation mode. See the description of /fBpattern/fR for details.""";
param rw unsigned pattern=25 if personality & 0x01
"""Commutation pattern to use, from 0 to 47. Default is type 25.
-Every plausible combination is included. The table shows the excitation pattern
-along the top, and the pattern code on the left hand side. The table entries
-are the hall patterns in H1, H2, H3 order.
+Every plausible combination is included. The table shows the excitation pattern along the top, and the pattern code on the left hand side.
+The table entries are the hall patterns in H1, H2, H3 order.
Common patterns are:
0 (30 degree commutation) and 26, its reverse.
17 (120 degree).
@@ -146,8 +126,7 @@ Common patterns are:
22 (240 degree).
25 (60 degree commutation).
-Note that a number of incorrect commutations will have non-zero net torque
-which might look as if they work, but don't really.
+Note that a number of incorrect commutations will have non-zero net torque which might look as if they work, but don't really.
If your motor lacks documentation it might be worth trying every pattern.
@@ -276,70 +255,58 @@ _
""";
description """
-This component is designed as an interface between the most common forms of
-three-phase motor feedback devices and the corresponding types of drive. However
-there is no requirement that the motor and drive should necessarily be of
-inherently compatible types.
+This component is designed as an interface between the most common forms of three-phase motor feedback devices and the corresponding types of drive.
+However, there is no requirement that the motor and drive should necessarily be of inherently compatible types.
-Each instance of the component is defined by a group of letters describing the
-input and output types. A comma separates individual instances of the component.
-For example \\fBloadrt bldc cfg=qi6,aH\\fR
+Each instance of the component is defined by a group of letters describing the input and output types.
+A comma separates individual instances of the component. For example \\fBloadrt bldc cfg=qi6,aH\\fR.
.SH Tags
Input type definitions are all lower-case.
-\\fBn\\fR No motor feedback. This mode could be used to drive AC
-induction motors, but is also potentially useful for creating free-running motor
-simulators for drive testing.
+\\fBn\\fR No motor feedback. This mode could be used to drive AC induction motors,
+but is also potentially useful for creating free-running motor simulators for drive testing.
-\\fBh\\fR Hall sensor input. Brushless DC motors (electronically commutated
-permanent magnet 3-phase motors) typically use a set of three Hall sensors to
-measure the angular position of the rotor. A lower-case \\fBh\\fR in the cfg
-string indicates that these should be used.
+\\fBh\\fR Hall sensor input.
+Brushless DC motors (electronically commutated permanent magnet 3-phase motors) typically use a set of three Hall sensors to measure the angular position of the rotor.
+A lower-case \\fBh\\fR in the cfg string indicates that these should be used.
-\\fBa\\fR Absolute encoder input. (Also possibly used by some forms of Resolver
-conversion hardware). The presence of this tag over-rides all other inputs. Note
-that the component still requires to be be connected to the \\fBrawcounts\\fR
-encoder pin to prevent loss of commutation on index-reset.
+\\fBa\\fR Absolute encoder input. (Also possibly used by some forms of Resolver conversion hardware).
+The presence of this tag over-rides all other inputs.
+Note that the component still requires to be be connected to the \\fBrawcounts\\fR encoder pin to prevent loss of commutation on index-reset.
-\\fBq\\fR Incremental (quadrature) encoder input. If this input is used then
-the rotor will need to be homed before the motor can be run.
+\\fBq\\fR Incremental (quadrature) encoder input.
+If this input is used then the rotor will need to be homed before the motor can be run.
\\fBi\\fR Use the index of an incremental encoder as a home reference.
-\\fBf\\fR Use a 4-bit Gray-scale patttern to determine rotor alignment. This
-scheme is only used on the Fanuc "Red Cap" motors. This mode could be used to
-control one of these motors using a non-Fanuc drive.
+\\fBf\\fR Use a 4-bit Gray-scale patttern to determine rotor alignment.
+This scheme is only used on the Fanuc "Red Cap" motors.
+This mode could be used to control one of these motors using a non-Fanuc drive.
Output type descriptions are all upper-case.
-\\fBDefaults\\fR The component will always calculate rotor angle, phase angle
-and the absolute value of the input \\fBvalue\\fR for interfacing with drives
-such as the Mesa 8I20. It will also default to three individual, bipolar phase
-output values if no other output type modifiers are used.
+\\fBDefaults\\fR The component will always calculate rotor angle, phase angle and the absolute value of the input \\fBvalue\\fR for interfacing with drives such as the Mesa 8I20.
+It will also default to three individual, bipolar phase output values if no other output type modifiers are used.
-\\fBB\\fR Bit level outputs. Either 3 or 6 logic-level outputs indicating which
-high or low gate drivers on an external drive should be used.
+\\fBB\\fR Bit level outputs. Either 3 or 6 logic-level outputs indicating which high or low gate drivers on an external drive should be used.
-\\fB6\\fR Create 6 rather than the default 3 outputs. In the case of numeric
-value outputs these are separate positive and negative drive amplitudes. Both
-have positive magnitude.
+\\fB6\\fR Create 6 rather than the default 3 outputs.
+In the case of numeric value outputs these are separate positive and negative drive amplitudes.
+Both have positive magnitude.
-\\fBH\\fR Emulated Hall sensor output. This mode can be used to control a drive
-which expects 3x Hall signals, or to convert between a motor with one hall
-pattern and a drive which expects a different one.
+\\fBH\\fR Emulated Hall sensor output.
+This mode can be used to control a drive which expects 3x Hall signals,
+or to convert between a motor with one hall pattern and a drive which expects a different one.
-\\fBF\\fR Emulated Fanuc Red Cap Gray-code encoder output. This mode might be
-used to drive a non-Fanuc motor using a Fanuc drive intended for the "Red-Cap"
-motors.
+\\fBF\\fR Emulated Fanuc Red Cap Gray-code encoder output.
+This mode might be used to drive a non-Fanuc motor using a Fanuc drive intended for the "Red-Cap" motors.
\\fBT\\fR Force Trapezoidal mode.
.SH OPERATING MODES
-The component can control a drive in either Trapezoidal or Sinusoidal mode, but
-will always default to sinusoidal if the input and output modes allow it. This
-can be over-ridden by the \\fBT\\fR tag. Sinusoidal commutation is significantly
-smoother (trapezoidal commutation induces 13% torque ripple).
+The component can control a drive in either Trapezoidal or Sinusoidal mode, but will always default to sinusoidal if the input and output modes allow it.
+This can be over-ridden by the \\fBT\\fR tag. Sinusoidal commutation is significantly smoother (trapezoidal commutation induces 13% torque ripple).
.SH ROTOR HOMING.
To use an encoder for commutation a reference 0-degrees point must be found.
diff --git a/src/hal/components/feedcomp.comp b/src/hal/components/feedcomp.comp
index 32cfed75f1..2235bff35b 100644
--- a/src/hal/components/feedcomp.comp
+++ b/src/hal/components/feedcomp.comp
@@ -14,13 +14,13 @@
// along with this program; if not, write to the Free Software
// Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
-component feedcomp "Multiply the input by the ratio of current velocity to the feed rate";
+component feedcomp "Multiply the input by the ratio of current velocity to the feed rate.";
pin out float out "Proportionate output value";
pin in float in "Reference value";
-pin in bit enable "Turn compensation on or off";
+pin in bit enable "Turn compensation on or off.";
pin in float vel "Current velocity";
param rw float feed "Feed rate reference value";
-notes "Note that if enable is false, out = in";
+notes "Note that if enable is false, out = in.";
function _;
license "GPL";
diff --git a/src/hal/components/gantry.comp b/src/hal/components/gantry.comp
index a0abecc78f..0f832fcfdf 100644
--- a/src/hal/components/gantry.comp
+++ b/src/hal/components/gantry.comp
@@ -38,37 +38,35 @@
*
******************************************************************************/
-component gantry "LinuxCNC HAL component for driving multiple joints from a single axis";
+component gantry "LinuxCNC HAL component for driving multiple joints from a single axis.";
pin out float joint.##.pos-cmd [7 : personality] "Per-joint commanded position";
pin in float joint.##.pos-fb [7 : personality] "Per-joint position feedback";
pin in bit joint.##.home [7 : personality] "Per-joint home switch";
-pin out float joint.##.offset [7 : personality] "(debugging) Per-joint offset value, updated when homing";
+pin out float joint.##.offset [7 : personality] "(debugging) Per-joint offset value, updated when homing.";
pin in float position-cmd "Commanded position from motion";
pin out float position-fb "Position feedback to motion";
-pin out bit home "Combined home signal, true if all joint home inputs are true";
-pin out bit limit "Combined limit signal, true if any joint home input is true";
+pin out bit home "Combined home signal, true if all joint home inputs are true.";
+pin out bit limit "Combined limit signal, true if any joint home input is true.";
pin in float search-vel "HOME_SEARCH_VEL from INI file";
-function read fp "Update position-fb and home/limit outputs based on joint values";
-function write fp "Update joint pos-cmd outputs based on position-cmd in";
+function read fp "Update position-fb and home/limit outputs based on joint values.";
+function write fp "Update joint pos-cmd outputs based on position-cmd in.";
description """
Drives multiple physical motors (joints) from a single axis input
.LP
The `personality' value is the number of joints to control. Two is typical, but
up to seven is supported (a three joint setup has been tested with hardware).
.LP
-All controlled joints track the commanded position (with a per-joint offset)
-unless in the process of homing. Homing is when the commanded position is
-moving towards the homing switches (as determined by the sign of search-vel)
-and the joint home switches are not all in the same state. When the system is
-homing and a joint home switch activates, the command value sent to that joint
-is "frozen" and the joint offset value is updated instead. Once all home
-switches are active, there are no more adjustments made to the offset values
-and all joints run in lock-step once more.
+All controlled joints track the commanded position (with a per-joint offset) unless in the process of homing.
+Homing is when the commanded position is moving towards the homing switches
+(as determined by the sign of search-vel)
+and the joint home switches are not all in the same state.
+When the system is homing and a joint home switch activates,
+the command value sent to that joint is "frozen" and the joint offset value is updated instead.
+Once all home switches are active,
+there are no more adjustments made to the offset values and all joints run in lock-step once more.
.LP
-For best results, set HOME_SEARCH_VEL and HOME_LATCH_VEL to the same direction
-and as slow as practical. When a joint home switch trips, the commanded
-velocity will drop immediately from HOME_SEARCH_VEL to zero, with no limit on
-acceleration.
+For best results, set HOME_SEARCH_VEL and HOME_LATCH_VEL to the same direction and as slow as practical.
+When a joint home switch trips, the commanded velocity will drop immediately from HOME_SEARCH_VEL to zero, with no limit on acceleration.
""";
license "GPL";
author "Charles Steinkuehler";
diff --git a/src/hal/components/lut5.comp b/src/hal/components/lut5.comp
index 677f41dcb6..4d4fc25959 100644
--- a/src/hal/components/lut5.comp
+++ b/src/hal/components/lut5.comp
@@ -9,15 +9,13 @@ param rw u32 function;
function _ nofp;
description """
.B lut5
-constructs a logic function with up to 5 inputs using a
-\\fBl\\fRook-\\fBu\\fRp \\fBt\\fRable. The value for \\fBfunction\\fR can be
-determined by writing the truth table, and computing the sum of \\fBall\\fR
-the \\fBweights\\fR for which the output value would be \\fRTRUE\\fR.
-The weights are hexadecimal not decimal so hexadecimal math must be used to
-sum the weights. A wiki page has a calculator to assist in computing the proper
-value for function.
+constructs a logic function with up to 5 inputs using a \\fBl\\fRook-\\fBu\\fRp \\fBt\\fRable.
+The value for \\fBfunction\\fR can be determined by writing the truth table,
+and computing the sum of \\fBall\\fR the \\fBweights\\fR for which the output value would be \\fRTRUE\\fR.
+The weights are hexadecimal not decimal so hexadecimal math must be used to sum the weights.
+A wiki page has a calculator to assist in computing the proper value for function.
.PP
-http://wiki.linuxcnc.org/cgi-bin/wiki.pl?Lut5
+https://wiki.linuxcnc.org/cgi-bin/wiki.pl?Lut5
.PP
Note that LUT5 will generate any of the 4,294,967,296
logical functions of 5 inputs so \\fBAND\\fR, \\fBOR\\fR, \\fBNAND\\fR,
diff --git a/src/hal/components/moveoff.comp b/src/hal/components/moveoff.comp
index ecbc19995e..5a79e40f05 100644
--- a/src/hal/components/moveoff.comp
+++ b/src/hal/components/moveoff.comp
@@ -2,86 +2,60 @@ component moveoff "Component for HAL-only offsets";
description
"""
-The moveoff component is used to offset joint positions using custom HAL
-connections. Implementing an offset-while-program-is-paused functionality is
-supported with appropriate connections for the input pins. Nine joints are
-supported.
-
-The axis offset pin values (offset-in-M) are continuously applied (respecting
-limits on value, velocity, and acceleration) to the output pins
-(offset-current-M, pos-plusoffset-M, fb-minusoffset-M) when both enabling input
-pins (apply-offsets and move-enable) are TRUE. The two enabling inputs are
-anded internally. A \\fBwarning\\fR pin is set and a message issued if the
-apply-offsets pin is deasserted while offsets are applied. The warning pin
-remains TRUE until the offsets are removed or the apply-offsets pin is set.
-
-Typically, the move-enable pin is connected to external controls and the
-apply-offsets pin is connected to halui.program.is-paused (for offsets only
-while paused) or set to TRUE (for continuously applied offsets).
-
-Applied offsets are \\fBautomatically returned\\fR to zero (respecting limits)
-when either of the enabling inputs is deactivated. The zero value
-tolerance is specified by the epsilon input pin value.
-
-Waypoints are recorded when the moveoff componenent is enabled. Waypoints are
-managed with the waypoint-sample-secs and waypoint-threshold pins. When the
-backtrack-enable pin is TRUE, the auto-return path follows the recorded
-waypoints. When the memory available for waypoints is exhausted, offsets are
-frozen and the waypoint-limit pin is asserted. This restriction applies
-regardless of the state of the backtrack-enable pin. An enabling pin must be
-deasserted to allow a return to the original (non-offset position).
-
-Backtracking through waypoints results in \\fBslower\\fR movement rates as the
-moves are point-to-point respecting velocity and acceleration settings. The
-velocity and acceleration limit pins can be managed dynamically to control
-offsets at all times.
-
-When backtrack-enable is FALSE, the auto-return move is \\fBNOT\\fR
-coordinated, each axis returns to zero at its own rate. If a controlled path
-is wanted in this condition, each axis should be manually returned to zero
-before deasserting an enabling pin.
-
-The waypoint-sample-secs, waypoint-threshold, and epsilon pins are evaluated
-only when the component is idle.
-
-The offsets-applied output pin is provided to indicate the current state to a
-GUI so that program resumption can be managed. If the offset(s) are non-zero
-when the apply-offsets pin is deasserted (for example when resuming a program
-when offsetting during a pause), offsets are returned to zero (respecting
-limits) and an \\fBError\\fR message is issued.
-
-\\fBCaution:\\fR If offsets are enabled and applied and the machine is turned off
-for any reason, any \\fBexternal\\fR HAL logic that manages the enabling pins
-and the offset-in-M inputs is responsible for their state when the
-machine is subsequently turned on again.
-
-This HAL-only means of offsetting is typically not known to LinuxCNC
-nor available in GUI preview displays. \\fBNo protection is provided\\fR for
-offset moves that exceed soft limits managed by LinuxCNC. Since soft limits
-are not honored, an offset move may encounter hard limits (or \\fBCRASH\\fR if
-there are no limit switches). Use of the offset-min-M and offset-max-M inputs
-to limit travel is recommended. Triggering a hard limit will turn off
-the machine -- see \\fBCaution\\fR above.
-
-The offset-in-M values may be set with inifile settings, controlled by a GUI,
-or managed by other HAL components and connections. Fixed values may be
-appropriate in simple cases where the direction and amount of offset is
-well-defined but a control method is required to deactivate an enabling
-pin in order to return offsets to zero. GUIs may provide means for users to
-set, increment, decrement, and accumulate offset values for each axis and may
-set offset-in-M values to zero before deasserting an enabling pin.
-
-The default values for accel, vel, min, max, epsilon, waypoint-sample-secs, and
-waypoint-threshold may not be suitable for any particular application. This
-HAL component is unaware of limits enforced elsewhere by LinuxCNC.
-Users should test usage in a simulator application and understand all
-hazards \\fBbefore\\fR use on hardware.
-
-The module personality item sets the number of joints supported (default==3,
-maximum is 9).
-
-Use of the names= option for naming is \\fBrequired\\fR for compatibility
-with the gui provided as scripts/moveoff_gui:
+The moveoff component is used to offset joint positions using custom HAL connections.
+Implementing an offset-while-program-is-paused functionality is supported with appropriate connections for the input pins.
+Nine joints are supported.
+
+The axis offset pin values (offset-in-M) are continuously applied (respecting limits on value, velocity, and acceleration)
+to the output pins (offset-current-M, pos-plusoffset-M, fb-minusoffset-M) when both enabling input pins (apply-offsets and move-enable) are TRUE.
+The two enabling inputs are anded internally.
+A \\fBwarning\\fR pin is set and a message issued if the apply-offsets pin is deasserted while offsets are applied.
+The warning pin remains TRUE until the offsets are removed or the apply-offsets pin is set.
+
+Typically, the move-enable pin is connected to external c
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment