extrajoints support in motion

New motmod parameter: num_extrajoints

1) An 'extra' joint uses the normal joint homing process but
   transfers control to a new hal pin (joint.N.posthome-cmd)
   after homing.  An independent motion planner/controller
   (limit3 component typically) must be employed to manage
   the 'extra' joint  motion using this input.

2) Includes: simulation configs:
      1extrajoint.ini  XYYZ (4joints) +  1 extra ( 5 joints total)
      2extrajoints.ini XYYZ (4joints) +  2 extra ( 6 joints total)
     12extrajoints.ini XYYZ (4joints) + 12 extra (16 joints total)
   and example M144 command to set extra joints jN.limit3.in

3) motion man page update

Notes:
 1) if num_extrajoints is nonzero, require KINEMATICS_BOTH
    in order to make sensible axis gui displays

 2) by legacy, [KINS]JOINTS=  sets the *total* number of joints
    e.g., num_joints + num_extrajoints
    Example non-motion source files using [KINS]JOINTS:
        a) src/emc/ini/initraj.cc
        b) src/emc/usr_intf/halui.cc
        c) src/emc/usr_intf/axis/scripts/axis.py

------------------------------------------------------------
updates:
rebased to origin/master ae6e7e00a Thu Sep 5 22:27:20 2019 -0700

   1) report numExtraJoints to task
   2) axis.py update joint jog radiobuttons for homing
   3) use #define for ALL_JOINTS,NO_OF_KINS_JOINTS,IS_EXTRAJOINT
   4) axis.py formerly would not 'unhome all' unless machine on
   5) add demo ini for 16 joints (12 extra)
   6) glcanon.py posstrs minor format

------------------------------------------------------------
This commit is contained in:
Dewey Garrett 2019-01-21 13:48:55 -07:00
parent 76963bc538
commit ee816bd9b5
27 changed files with 1012 additions and 113 deletions

View file

@ -0,0 +1,227 @@
[EMC]
MACHINE = 12extrajoints
VERSION = 1.1
[APPLICATIONS]
APP = halshow --fformat %.6f extrajoints.halshow
# joint4 example:
APP = sim_pin --title "j4 extrajoint" \
j4.limit3.min \
j4.limit3.max \
j4.limit3.maxv \
j4.limit3.maxa \
j4.limit3.in
[KINS]
JOINTS = 16
#NOTE: 4 conventional joints, 12 extra (motmod) total=16
KINEMATICS = trivkins coordinates=XYYZ kinstype=both
[EMCMOT]
EMCMOT = motmod num_extrajoints=12
SERVO_PERIOD = 1000000
[HAL]
TWOPASS = on
HALFILE = LIB:basic_sim.tcl
HALFILE = ./12extrajoints.tcl
HALUI = halui
[DISPLAY]
DISPLAY = axis
MAX_LINEAR_VELOCITY = 1
PROGRAM_PREFIX = .
[TASK]
TASK = milltask
CYCLE_TIME = 0.001
[RS274NGC]
PARAMETER_FILE = sim.var
[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
[TRAJ]
COORDINATES = XYYZ
LINEAR_UNITS = inch
ANGULAR_UNITS = degree
[JOINT_0]
TYPE = LINEAR
HOME_SEQUENCE = 0
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_1]
TYPE = LINEAR
HOME_SEQUENCE = -1
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_2]
TYPE = LINEAR
HOME_SEQUENCE = -1
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_3]
TYPE = LINEAR
HOME_SEQUENCE = 2
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_4]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 3
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_5]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 4
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_6]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 5
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_7]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 6
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_8]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 7
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_9]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 8
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_10]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 9
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_11]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 10
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_12]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 11
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_13]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 12
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_14]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 13
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_15]
# Uses IMMEDIATE homing
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 14
HOME_SEARCH_VEL = 0
HOME_LATCH_VEL = 0
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100

View file

@ -0,0 +1,23 @@
# 12extrajoints.tcl (requires [HAL]TWOPASS
set min_joint_num 4 ;# first extra joint
set max_joint_num 15 ;# last extra joint
for {set j $min_joint_num} {$j <= $max_joint_num} {incr j} {
# use limit3 for motion planning:
loadrt limit3 names=j${j}.limit3
addf j${j}.limit3 servo-thread
# These constraints apply to homing managed by
# LinuxCNC and post-homing managed by the limit3 component:
setp j${j}.limit3.min [set ::JOINT_[set j](MIN_LIMIT)]
setp j${j}.limit3.max [set ::JOINT_[set j](MAX_LIMIT)]
setp j${j}.limit3.maxv [set ::JOINT_[set j](MAX_VELOCITY)]
setp j${j}.limit3.maxa [set ::JOINT_[set j](MAX_ACCELERATION)]
net J${j}:out <= j${j}.limit3.out
net J${j}:out => joint.${j}.posthome-cmd
net J${j}.enable <= joint.${j}.homed
net J${j}.enable => j${j}.limit3.enable
}

View file

@ -0,0 +1,61 @@
# 1extrajoint demo
# immediate homing -- jog joint4 to make a motor-offset before homing
loadrt [KINS]KINEMATICS
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS
addf motion-command-handler servo-thread
addf motion-controller servo-thread
net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in
net J0:loop <= joint.0.motor-pos-cmd
net J0:loop => joint.0.motor-pos-fb
net J1:loop <= joint.1.motor-pos-cmd
net J1:loop => joint.1.motor-pos-fb
net J2:loop <= joint.2.motor-pos-cmd
net J2:loop => joint.2.motor-pos-fb
net J3:loop <= joint.3.motor-pos-cmd
net J3:loop => joint.3.motor-pos-fb
#--------------------------------------------
# extra joint (joint4)
# For simulation just connect pos-cmd to pos-fb:
net J4:loop <= joint.4.motor-pos-cmd
net J4:loop => joint.4.motor-pos-fb
# NOTE: For a stepgen in position control mode:
# net J4:loop <= joint.4.motor-pos-cmd
# net J4:loop => joint.4.motor-pos-fb
# net J4:loop => stepgen_position_command
# NOTE: A stepgen can be also used in velocity control mode
# with a PID loop but it is not necessarily required
# and position mode control is much simpler
# NOTE: For a pid motor controller (motor/amplifier/encoder):
# net J4:cmd <= joint.4.motor-pos-cmd
# net J4:cmd => pid_command_input
# net J4:fb <= encoder_measurement_output
# net J4:fb => joint.4.motor-pos-fb
#-----------------------------------------------------------
# motion planner for extra joint (joint4)
loadrt limit3 names=j4.limit3
# These constraints apply to homing managed by
# LinuxCNC and post-homing managed by the limit3 component:
setp j4.limit3.min [JOINT_4]MIN_LIMIT
setp j4.limit3.max [JOINT_4]MAX_LIMIT
setp j4.limit3.maxv [JOINT_4]MAX_VELOCITY
setp j4.limit3.maxa [JOINT_4]MAX_ACCELERATION
addf j4.limit3 servo-thread
net J4:out <= j4.limit3.out
net J4:out => joint.4.posthome-cmd
net J4:enable <= joint.4.homed
net J4:enable => j4.limit3.enable

View file

@ -0,0 +1,86 @@
# This sim config uses 'immediate' homing
# To demonstrate motor-offsets:
# jog the extra joint(4) away from its turn-on position
# then home-all
[EMC]
MACHINE = 1extrajoint
VERSION = 1.1
[APPLICATIONS]
APP = halshow --fformat %.6f extrajoints.halshow
APP = sim_pin --title "j4 extrajoint" \
j4.limit3.min \
j4.limit3.max \
j4.limit3.maxv \
j4.limit3.maxa \
j4.limit3.in
[KINS]
JOINTS = 5
# NOTE: 4 kinematic joints + 1 extra (motmod) total=5
KINEMATICS = trivkins coordinates=XYYZ kinstype=both
[EMCMOT]
EMCMOT = motmod num_extrajoints=1
SERVO_PERIOD = 1000000
[HAL]
HALFILE = 1extrajoint.hal
HALUI = halui
[DISPLAY]
DISPLAY = axis
MAX_LINEAR_VELOCITY = 1
PROGRAM_PREFIX = .
[TASK]
TASK = milltask
CYCLE_TIME = 0.001
[RS274NGC]
PARAMETER_FILE = sim.var
[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
[TRAJ]
COORDINATES = XYYZ
LINEAR_UNITS = inch
ANGULAR_UNITS = degree
[JOINT_0]
TYPE = LINEAR
HOME_SEQUENCE = 1
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_1]
TYPE = LINEAR
HOME_SEQUENCE = -2
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_2]
TYPE = LINEAR
HOME_SEQUENCE = -2
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_3]
TYPE = LINEAR
HOME_SEQUENCE = 3
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_4]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 0
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100

View file

@ -0,0 +1,37 @@
1extrajoint demo
Demo of the motmod num_extrajoints= parameter
a) XYYZ correspond one-to-one to
joints 0123
b) Joint4 is an 'extra joint' that is
not related to any axis letter but
is managed independently by a limit3
component.
c) All joints use 'immediate homing'
d) Using extra joints requires
NON-identity kinematics and all
joints (including joint4) must be
homed before switching to world
mode.
e) A halshow app is opened to display
key pin values
f) A sim_pin app is opened to set key
pin values
Usage:
1) F1 (Estop Off)
2) F2 (Machine On)
3) jog joint4 to create a small offset
4) Ctrl-HOME (Home all)
5) demonstrate joint.4 movement using
the provided M144 mdi command:
M144 P4 Q1.23 ;move joint.4 to 1.23
M144 P4 Q3.21 ;move joint.4 to 3.21
6) Alternately, demonstrate joint.[45]
movement using sim_pin settings:
j4.limit3.min min value
j4.limit3.max max value
j4.limit3.maxv max velocity
j4.limit3.maxa max acceleration
j4.limit3.in requested value

View file

@ -0,0 +1,30 @@
# use limit3 for motion planning:
loadrt limit3 names=j4.limit3,j5.limit3
# These constraints apply to homing managed by
# LinuxCNC and post-homing managed by the limit3 component:
setp j4.limit3.min [JOINT_4]MIN_LIMIT
setp j4.limit3.max [JOINT_4]MAX_LIMIT
setp j4.limit3.maxv [JOINT_4]MAX_VELOCITY
setp j4.limit3.maxa [JOINT_4]MAX_ACCELERATION
addf j4.limit3 servo-thread
net J4:out <= j4.limit3.out
net J4:out => joint.4.posthome-cmd
net J4.enable <= joint.4.homed
net J4.enable => j4.limit3.enable
setp j5.limit3.min [JOINT_5]MIN_LIMIT
setp j5.limit3.max [JOINT_5]MAX_LIMIT
setp j5.limit3.maxv [JOINT_5]MAX_VELOCITY
setp j5.limit3.maxa [JOINT_5]MAX_ACCELERATION
addf j5.limit3 servo-thread
net J5:out <= j5.limit3.out
net J5:out => joint.5.posthome-cmd
net J5.enable <= joint.5.homed
net J5.enable => j5.limit3.enable

View file

@ -0,0 +1,111 @@
[EMC]
MACHINE = 2extrajoints
VERSION = 1.1
[APPLICATIONS]
APP = halshow --fformat %.6f extrajoints.halshow
APP = sim_pin --title "j4 extrajoint" \
j4.limit3.min \
j4.limit3.max \
j4.limit3.maxv \
j4.limit3.maxa \
j4.limit3.in
APP = sim_pin --title "j5 extrajoints" \
j5.limit3.min \
j5.limit3.max \
j5.limit3.maxv \
j5.limit3.maxa \
j5.limit3.in
[KINS]
JOINTS = 6
#NOTE: 4 conventional joints, 2 extra (motmod) total=6
KINEMATICS = trivkins coordinates=XYYZ kinstype=both
[EMCMOT]
EMCMOT = motmod num_extrajoints=2
SERVO_PERIOD = 1000000
[HAL]
HALFILE = LIB:basic_sim.tcl
HALFILE = ./2extrajoints.hal
HALUI = halui
[DISPLAY]
DISPLAY = axis
MAX_LINEAR_VELOCITY = 1
PROGRAM_PREFIX = .
[TASK]
TASK = milltask
CYCLE_TIME = 0.001
[RS274NGC]
PARAMETER_FILE = sim.var
[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
[TRAJ]
COORDINATES = XYYZ
LINEAR_UNITS = inch
ANGULAR_UNITS = degree
[JOINT_0]
TYPE = LINEAR
HOME_SEQUENCE = 1
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_1]
TYPE = LINEAR
HOME_SEQUENCE = -2
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_2]
TYPE = LINEAR
HOME_SEQUENCE = -2
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_3]
TYPE = LINEAR
HOME_SEQUENCE = 3
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MAX_VELOCITY = 10
MAX_ACCELERATION = 100
[JOINT_4]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 0
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100
[JOINT_5]
# this 'extra' joint is managed by a
# limit3 component after homing
TYPE = LINEAR
HOME_SEQUENCE = 0
HOME_SEARCH_VEL = 20
HOME_LATCH_VEL = 20
MIN_LIMIT = -10
MAX_LIMIT = 10
MAX_VELOCITY = 5
MAX_ACCELERATION = 100

View file

@ -0,0 +1,46 @@
2extrajoints demo
Demo of the motmod num_extrajoints= parameter
a) XYYZ correspond one-to-one to
joints 0123
b) joint.4 and joint.5 are 'extra'
joints not related to any axis
letter but managed independently by
limit3 components.
c) The configuration uses basic_sim.tcl
and simulates home switches for all
joints.
d) Using extra joints requires
NON-identity kinematics and all
joints (including joint4) must be
homed before switching to world
mode.
e) A halshow app is opened to display
key pin values
f) A sim_pin app is opened to set key
pin values
Usage:
1) F1 (Estop Off)
2) F2 (Machine On)
3) optionally jog joint.4 and joint.5
prior to homing to observe motor
offset
4) Ctrl-HOME (Home all)
5) demonstrate joint.[45] movement
using the provided M144 mdi
command:
M144 P4 Q1.23 move joint.4 to 1.23
M144 P4 Q4.56 move joint.4 to 4.56
M144 P5 Q3.21 move joint.5 to 3.21
M144 P5 Q2.22 move joint.5 to 2.22
etc.
6) Alternately, demonstrate joint.[45]
movement using sim_pin settings:
j4.limit3.min min value
j4.limit3.max max value
j4.limit3.maxv max velocity
j4.limit3.maxa max acceleration
j4.limit3.in requested value
similar for j5

View file

@ -0,0 +1,35 @@
#!/usr/bin/tclsh
# M144 demo for extra joints
# Usage: M144 [Pjoint_num] [Qposition]
# Mcodes substitute "-1.000000" for omitted p,q values
# so these are handled as special cases
# Note: this also disallows a q value of -1 (sigh)
set min_joint_num 4
set max_joint_num 15
proc fail {msg} {
puts "\nFAIL: $::argv0 $msg"
puts "Usage: $::argv0 P<jointnumber> Q<position>"
exit 1
}
set p [lindex $::argv 0]
set q [lindex $::argv 1]
if {"$p" == "-1.000000"} {fail "Missing Pvalue"}
if {"$q" == "-1.000000"} {fail "Missing Qvalue (or -1)"}
set p [expr int($p)]
if {$p < $min_joint_num || $p > $max_joint_num} {
fail "Bad Pvalue (extra joint number) <$p>"
}
set cmd "halcmd setp j${p}.limit3.in $q"
if [catch {eval exec $cmd} msg] {
fail "Command:$cmd\n$msg"
}
puts "\nOK: $::argv0: $cmd"
exit 0

View file

@ -0,0 +1,18 @@
extrajoints demos
1extrajoint
5 joints total
1 extra joint (joint.4)
immediate homing
(jog joint4 before homing to
create a small motor offset)
2extrajoints
6 joints total
2 extra joints (joint.4,5)
simulated home switches
12extrajoints
16 joints total
12 extra joints (joint.4-15)
simulated home switches

View file

@ -0,0 +1,28 @@
pin+j4.limit3.in
pin+j4.limit3.out
pin+joint.4.posthome-cmd
pin+joint.4.homed
pin+joint.4.motor-pos-cmd
pin+joint.4.motor-pos-fb
pin+joint.4.motor-offset
pin+j4.limit3.max
pin+j4.limit3.min
pin+j4.limit3.maxv
pin+j4.limit3.maxa
pin+j5.limit3.in
pin+j5.limit3.out
pin+joint.5.posthome-cmd
pin+joint.5.homed
pin+joint.5.motor-pos-cmd
pin+joint.5.motor-pos-fb
pin+joint.5.motor-offset
pin+j5.limit3.max
pin+j5.limit3.min
pin+j5.limit3.maxv
pin+j5.limit3.maxa

View file

@ -8,17 +8,23 @@
.SH NAME
motion \- accepts NML motion commands, interacts with HAL in realtime
.SH SYNOPSIS
\fBloadrt motmod [base_period_nsec=\fIperiod\fB] [base_thread_fp=\fI0 or 1\fB] [servo_period_nsec=\fIperiod\fB] [traj_period_nsec=\fIperiod\fB] [num_joints=\fI[1-16]\fB] [num_dio=\fI[1-64]\fB] [num_aio=\fI[1-64]\fB] [num_spindles=\fI[1-8]\fB]\fR \fB[unlock_joints_mask=\fR\fIjointmask\fR\fB]\fR
\fBloadrt motmod [base_period_nsec=\fIperiod\fB] [base_thread_fp=\fI0 or 1\fB] [servo_period_nsec=\fIperiod\fB] [traj_period_nsec=\fIperiod\fB] [num_joints=\fI[1-16]\fB] [num_dio=\fI[1-64]\fB] [num_aio=\fI[1-64]\fB] [num_spindles=\fI[1-8]\fB]\fR \fB[unlock_joints_mask=\fR\fIjointmask\fR\fB]\fR \fB[num_extrajoints=\fI[0-16]\fB]\fR
The limits for the following items are compile-time settings:
.TQ
Number of joints available (num_joints) is set by EMCMOT_MAX_JOINTS.
\fBnum_joints\fR: Maximum number of joints is set by EMCMOT_MAX_JOINTS.
.TQ
Maximum number of digital inputs (num_dio) is set by EMCMOT_MAX_DIO.
\fBnum_dio\fR: Maximum number of digital inputs is set by EMCMOT_MAX_DIO.
.TQ
Maximum number of analog inputs (num_aio) is set by EMCMOT_MAX_AIO.
\fBnum_aio\fR: Maximum number of analog inputs is set by EMCMOT_MAX_AIO.
.TQ
Maximum number of spindles (num_spindles) is set by EMCMOT_MAX_SPINDLES
\fBnum_spindles\fR: Maximum number of spindles is set by EMCMOT_MAX_SPINDLES
.P
Optionally the number of Digital I/O is set with num_dio. The number of Analog I/O is set with num_aio. The default is 4 each.
.P
Pin names starting with "\fBjoint\fR" or "\fBaxis\fR" are are read and updated by the motion-controller function.
.SH DESCRIPTION
By default, the base thread does not support floating point. Software stepping, software encoder counting, and software pwm do not use floating point. \fBbase_thread_fp\fR can be used to enable floating point in the base thread (for example for brushless DC motor control).
@ -27,10 +33,29 @@ By default, the base thread does not support floating point. Software stepping,
These pins and parameters are created by the realtime \fBmotmod\fR module. This module provides a HAL interface for LinuxCNC's motion planner. Basically \fBmotmod\fR takes in a list of waypoints and generates a nice blended and constraint-limited stream of joint positions to be fed to the motor drives.
.P
Optionally the number of Digital I/O is set with num_dio. The number of Analog I/O is set with num_aio. The default is 4 each.
The optional \fBnum_extrajoints\fR parameter specifies a quantity of joints
that participate in homing but are not used by kinematics transformations.
After homing, control of an 'extra' joint is transferred to a posthome command
hal pin (joint.N.posthome-cmd) and the motor feedback value is ignored. 'Extra'
joints must be managed by independent motion planners/controllers (typically
using limit3 hal components). Extra joints maybe unhomed only when motion is
disabled.
.P
Pin names starting with "\fBjoint\fR" or "\fBaxis\fR" are are read and updated by the motion-controller function.
The maximum \fBnum_extrajoints\fR value is equal to the \fBnum_joints\fR value.
(Note that using the maximum value would allow no operation in world
coordinates). The \fBnum_joints\fR value must be equal to the sum of the
number of joints used for kinematics calculations plus the number of 'extra'
joints.
The \fBnum_joints\fR parameter is conventionally set using the ini file
setting \fB[KINS]JOINTS=\fRvalue. The \fBnum_extrajoints\fR is set by
the additional motmod parameter \fB[EMCMOT]motmod num_extrajoints=\fRvalue.
Hal pin numbering for all joints is zero based [\fB0 ... num_joints-1\fR].
When specified, 'extra' joints are assigned the last \fBnum_extrajoints\fR
in the numbering sequence. For example, specifying [KINS]JOINTS=5 and
[EMCMOT]motmod num_extrajoints=2 for a 3 joint trivkins configuration
\fB[KINS] KINEMATICS=trivkins coordinates=xyz\fR uses joints 0,1,2 for
the kinematic joints and joints 3,4 for the 'extra' joints.
.SH MOTION PINS
@ -431,7 +456,13 @@ The joint's commanded velocity
.TP
\fBjoint.\fIN\fB.wheel\-jog\-active\fR OUT BIT \fB(DEBUG)\fR
.SH JOINT UNLOCK PINS
.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.
.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)

View file

@ -1209,6 +1209,15 @@ motion modules, the python interface, the axis gui, and the test suite.
The maximum number of joints (EMCMOT_MAX_JOINTS) increased from 9
to 16. The axis gui now supports display of up to 16 joints.
==== Extra Joints
A new motmod parameter (num_extrajoints) specifies joints that are
homed by conventional joint homing methods but controlled by new hal
pins (joint.N.posthome-cmd) after homing. Such joints may be
managed by independent motion planner/controllers in hal and manipulated
from gcode using custom M-codes. See the motion man page for
more info.
==== Homing
A homing api is provided by src/emc/motion/homing.h to support users'

View file

@ -136,6 +136,25 @@ proc validate_identity_kins_limits {} {
}
return $emsg
} ;# validate_identity_kins_limits
proc check_extrajoints {} {
if ![info exists ::EMCMOT(EMCMOT)] return
if {[string first motmod $::EMCMOT(EMCMOT)] <= 0} return
set mot [split [lindex $::EMCMOT(EMCMOT) 0]]
foreach item $mot {
set pair [split $item =]
set parm [lindex $pair 0]
set val [lindex $pair 1]
if {"$parm" == "num_extrajoints"} {
set ::num_extrajoints $val
}
}
if [info exists ::num_extrajoints] {
lappend ::wmsg [format "Extra joints specified=%d\n \
\[KINS\]JOINTS=%d must accomodate kinematic joints *plus* extra joints " \
$::num_extrajoints $::KINS(JOINTS)]
}
} ;#check_extrajoints
#----------------------------------------------------------------------
# begin
package require Linuxcnc ;# parse_ini
@ -182,6 +201,7 @@ switch $::kins(module) {
exit 0
}
}
check_extrajoints
#parray ::kins

View file

@ -59,18 +59,32 @@ proc check_ini_items {} {
}
}
set n_extrajoints 0
if [info exists ::EMCMOT(EMCMOT)] {
set mot [split [lindex $::EMCMOT(EMCMOT) 0]]
if {[string first motmod $mot] >= 0} {
foreach item $mot {
if {[string first num_extrajoints= $item] < 0} continue
set n_extrajoints [lindex [split $item =] end]
} ;# foreach
}
}
set kins [split [lindex $::KINS(KINEMATICS) 0]]
if {[string first trivkins $kins] >= 0} {
foreach item $kins {
if {[string first coordinates= $item] < 0} continue
set tcoords [lindex [split $item =] end]
set len_tcoords [string len $tcoords]
if {$len_tcoords != $::KINS(JOINTS)} {
set tcoords [lindex [split $item =] end]
set len_tcoords [string len $tcoords]
set expected_joints [expr $len_tcoords + $n_extrajoints]
if {$expected_joints != $::KINS(JOINTS)} {
set m "\ncheck_ini_items: WARNING:\n"
set m "$m trivkins coordinates=$tcoords specifies $len_tcoords joints\n"
set m "$m but \[KINS\]JOINTS is $::KINS(JOINTS)\n"
set m "$m trivkins extrajoints=$n_extrajoints\n"
set m "$m trivkins totaljoints=$expected_joints\n"
set m "$m !!! but \[KINS\]JOINTS=$::KINS(JOINTS)\n"
puts stderr $m
}
}
} ;# foreach
}
return
@ -88,15 +102,13 @@ proc setup_kins {axes} {
puts stderr "setup_kins: cmd=$cmd"
if [catch {eval $cmd} msg] {
puts stderr "msg=$msg"
# if fail, try without coordinates parameters
$cmd
puts stderr "\nmsg=$msg\n"
}
# set up axis indices for known kins
switch $kins_module {
trivkins {indices_for_trivkins $axes}
default {
trivkins {indices_for_trivkins $axes}
default {
puts stderr "setup_kins: unknown \[KINS\]KINEMATICS=<$::KINS(KINEMATICS)>"
}
}
@ -115,13 +127,21 @@ proc core_sim {axes
setup_kins $axes
if {"$emcmot" == "motmod"} {
loadrt $emcmot \
base_period_nsec=$base_period \
servo_period_nsec=$servo_period \
num_joints=$number_of_joints
if [catch {loadrt $emcmot \
base_period_nsec=$base_period \
servo_period_nsec=$servo_period \
num_joints=$number_of_joints} msg
] {
# typ: too many joints attempted
puts stderr "\n"
puts stderr "core_sim: loadrt $emcmot FAIL"
puts stderr " msg=$msg\n"
exit 1
}
} else {
# known special case with additional parameter:
# unlock_joint_mask=0xNN
# num_extrajoints=n
set module [split [lindex $emcmot 0]]
set modname [lindex $module 0]
set modparm [lreplace $module 0 0]
@ -213,7 +233,7 @@ proc make_ddts {number_of_joints} {
incr ddt_ct 2
if {$ddt_ct > $ddt_limit} {
puts stderr "make_ddts: number of ddts limited to $ddt_limit"
continue
break
}
set ddt_names "${ddt_names},J${jno}_vel,J${jno}_accel"
}

View file

@ -1532,7 +1532,7 @@ class GlCanonDraw:
else:
# N.B. no conversion here because joint positions are unitless
# joint_mode and display_joint
posstrs = [" %s:% 9.4f" % i for i in
posstrs = [" %2s:% 9.4f" % i for i in
zip(range(self.get_num_joints()), s.joint_actual_position)]
droposstrs = posstrs
return limit, homed, posstrs, droposstrs

View file

@ -83,7 +83,7 @@ bool checkAllHomed(void)
int joint_num;
emcmot_joint_t *joint;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
joint = &joints[joint_num];
if (!GET_JOINT_ACTIVE_FLAG(joint)) {
/* if joint is not active, don't even look at its limits */
@ -105,7 +105,7 @@ STATIC int limits_ok(void)
int joint_num;
emcmot_joint_t *joint;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
if (!GET_JOINT_ACTIVE_FLAG(joint)) {
@ -141,7 +141,7 @@ STATIC int joint_jog_ok(int joint_num, double vel)
we skip the following tests... */
return 1;
}
if (joint_num < 0 || joint_num >= emcmotConfig->numJoints) {
if (joint_num < 0 || joint_num >= ALL_JOINTS) {
reportError(_("Can't jog invalid joint number %d."), joint_num);
return 0;
}
@ -252,7 +252,7 @@ STATIC int inRange(EmcPose pos, int id, char *move_type)
/* Now, check that the endpoint puts the joints within their limits too */
/* fill in all joints with 0 */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
joint_pos[joint_num] = 0.0;
}
@ -264,7 +264,7 @@ STATIC int inRange(EmcPose pos, int id, char *move_type)
return 0;
}
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
@ -310,7 +310,7 @@ void clearHomes(int joint_num)
int n;
if (emcmotConfig->kinType == KINEMATICS_INVERSE_ONLY) {
if (rehomeAll) {
for (n = 0; n < emcmotConfig->numJoints; n++) {
for (n = 0; n < ALL_JOINTS; n++) {
set_joint_homed(joint_num,0);
}
} else {
@ -462,11 +462,11 @@ void emcmotCommandHandler(void *arg, long period)
abort = 1;
}
if ( !GET_MOTION_TELEOP_FLAG()
&& (joint_num >= emcmotConfig->numJoints || joint_num < 0)
&& (joint_num >= ALL_JOINTS || joint_num < 0)
) {
rtapi_print_msg(RTAPI_MSG_ERR,
"Joint jog requested for undefined joint number=%d (min=0,max=%d)",
joint_num,emcmotConfig->numJoints-1);
joint_num,ALL_JOINTS-1);
return;
}
if (GET_MOTION_TELEOP_FLAG()) {
@ -495,7 +495,7 @@ void emcmotCommandHandler(void *arg, long period)
return;
}
if (joint_num >= 0 && joint_num < emcmotConfig->numJoints) {
if (joint_num >= 0 && joint_num < ALL_JOINTS) {
joint = &joints[joint_num];
if ( ( emcmotCommand->command == EMCMOT_JOG_CONT
|| emcmotCommand->command == EMCMOT_JOG_INCR
@ -544,7 +544,7 @@ void emcmotCommandHandler(void *arg, long period)
} else if (GET_MOTION_COORD_FLAG()) {
tpAbort(&emcmotDebug->coord_tp);
} else {
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
/* tell joint planner to stop */
@ -557,7 +557,7 @@ void emcmotCommandHandler(void *arg, long period)
}
SET_MOTION_ERROR_FLAG(0);
/* clear joint errors (regardless of mode) */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
/* update status flags */
@ -637,14 +637,17 @@ void emcmotCommandHandler(void *arg, long period)
case EMCMOT_SET_NUM_JOINTS:
/* set the global NUM_JOINTS, which must be between 1 and
EMCMOT_MAX_JOINTS, inclusive */
EMCMOT_MAX_JOINTS, inclusive.
Called by task using [KINS]JOINTS= which is typically
the same value as the motmod num_joints= parameter
*/
rtapi_print_msg(RTAPI_MSG_DBG, "SET_NUM_JOINTS");
rtapi_print_msg(RTAPI_MSG_DBG, " %d", emcmotCommand->joint);
if (( emcmotCommand->joint <= 0 ) ||
( emcmotCommand->joint > EMCMOT_MAX_JOINTS )) {
break;
}
emcmotConfig->numJoints = emcmotCommand->joint;
ALL_JOINTS = emcmotCommand->joint;
break;
case EMCMOT_SET_NUM_SPINDLES:
@ -724,7 +727,7 @@ void emcmotCommandHandler(void *arg, long period)
} else {
rtapi_print_msg(RTAPI_MSG_DBG, "override on");
emcmotStatus->overrideLimitMask = 0;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point at joint data */
joint = &joints[joint_num];
/* only override limits that are currently tripped */
@ -737,7 +740,7 @@ void emcmotCommandHandler(void *arg, long period)
}
}
emcmotDebug->overriding = 0;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point at joint data */
joint = &joints[joint_num];
/* clear joint errors */
@ -895,7 +898,7 @@ void emcmotCommandHandler(void *arg, long period)
axis->teleop_tp.max_vel = fabs(emcmotCommand->vel);
axis->teleop_tp.max_acc = axis->acc_limit;
axis->kb_ajog_active = 1;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
joint = &joints[joint_num];
if (joint != 0) { joint->free_tp.enable = 0; }
}
@ -995,7 +998,7 @@ void emcmotCommandHandler(void *arg, long period)
axis->teleop_tp.max_acc = axis->acc_limit;
axis->kb_ajog_active = 1;
axis->teleop_tp.enable = 1;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
joint = &joints[joint_num];
if (joint != 0) { joint->free_tp.enable = 0; }
}
@ -1074,7 +1077,7 @@ void emcmotCommandHandler(void *arg, long period)
axis->teleop_tp.max_acc = axis->acc_limit;
axis->kb_ajog_active = 1;
axis->teleop_tp.enable = 1;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
joint = &joints[joint_num];
if (joint != 0) { joint->free_tp.enable = 0; }
}
@ -1499,7 +1502,7 @@ void emcmotCommandHandler(void *arg, long period)
if (get_home_sequence(joint_num) < 0) {
int jj;
set_home_sequence_state(HOME_SEQUENCE_DO_ONE_SEQUENCE);
for (jj = 0; jj < emcmotConfig->numJoints; jj++) {
for (jj = 0; jj < ALL_JOINTS; jj++) {
if (ABS(get_home_sequence(jj)) == ABS(get_home_sequence(joint_num))) {
// set home_state for all joints at same neg sequence
set_home_start(jj);
@ -1527,7 +1530,7 @@ void emcmotCommandHandler(void *arg, long period)
/* we want all or none, so these checks need to all be done first.
* but, let's only report the first error. There might be several,
* for instance if a homing sequence is running. */
for (n = 0; n < emcmotConfig->numJoints; n++) {
for (n = 0; n < ALL_JOINTS; n++) {
joint = &joints[n];
if(GET_JOINT_ACTIVE_FLAG(joint)) {
if (get_homing(n)) {
@ -1539,19 +1542,25 @@ void emcmotCommandHandler(void *arg, long period)
return;
}
}
if ( (n >= NO_OF_KINS_JOINTS)
&& (emcmotStatus->motion_state != EMCMOT_MOTION_DISABLED)) {
reportError(_("Cannot unhome extrajoint <%d> with motion enabled"), n);
return;
}
}
/* we made it through the checks, so unhome them all */
for (n = 0; n < emcmotConfig->numJoints; n++) {
for (n = 0; n < ALL_JOINTS; n++) {
joint = &joints[n];
if(GET_JOINT_ACTIVE_FLAG(joint)) {
/* legacy notes:
4aa4791cd1 (Chris Radek 2008-02-27 21:07:02 +0000 1310)
Unhome support, partly based on a patch by Bryant. Allow unhoming one joint or
all (-1) via nml message. A special unhome mode (-2) unhomes only the joints
marked as VOLATILE_HOME in the ini. task could use this to unhome some joints,
based on policy, at various state changes. This part is unimplemented so far.
*/
/* legacy notes:
4aa4791cd1 (Chris Radek 2008-02-27 21:07:02 +0000 1310)
Unhome support, partly based on a patch by Bryant.
Allow unhoming one joint or all (-1) via nml message.
A special unhome mode (-2) unhomes only the joints
marked as VOLATILE_HOME in the ini. task could use this
to unhome some joints, based on policy, at various state changes.
This part is unimplemented so far.
*/
/* if -2, only unhome the volatile_home joints */
if( (joint_num != -2) || get_home_is_volatile(n) ) {
set_joint_homed(n, 0);
@ -1559,8 +1568,13 @@ based on policy, at various state changes. This part is unimplemented so far.
}
}
} else if (joint_num < emcmotConfig->numJoints) {
} else if (joint_num < ALL_JOINTS) {
/* request was for only one joint */
if ( (joint_num >= NO_OF_KINS_JOINTS)
&& (emcmotStatus->motion_state != EMCMOT_MOTION_DISABLED)) {
reportError(_("Cannot unhome extrajoint <%d> with motion enabled"), joint_num);
return;
}
if(GET_JOINT_ACTIVE_FLAG(joint)) {
if (get_homing(joint_num) ) {
reportError(_("Cannot unhome while homing, joint %d"), joint_num);
@ -1576,7 +1590,7 @@ based on policy, at various state changes. This part is unimplemented so far.
}
} else {
/* invalid joint number specified */
reportError(_("Cannot unhome invalid joint %d (max %d)"), joint_num, (emcmotConfig->numJoints-1));
reportError(_("Cannot unhome invalid joint %d (max %d)"), joint_num, (ALL_JOINTS-1));
return;
}

View file

@ -273,7 +273,7 @@ void emcmotController(void *arg, long period)
#ifdef EDEBUG
dbg_ct++;
#endif
read_homing_in_pins(emcmotConfig->numJoints);
read_homing_in_pins(ALL_JOINTS);
process_inputs();
do_forward_kins();
process_probe_inputs();
@ -287,7 +287,7 @@ void emcmotController(void *arg, long period)
compute_screw_comp();
plan_external_offsets();
output_to_hal();
write_homing_out_pins(emcmotConfig->numJoints);
write_homing_out_pins(ALL_JOINTS);
update_status();
/* here ends the core of the controller */
emcmotStatus->heartbeat++;
@ -395,7 +395,7 @@ static void process_inputs(void)
}
/* read and process per-joint inputs */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS ; joint_num++) {
/* point to joint HAL data */
joint_data = &(emcmot_hal_data->joint[joint_num]);
/* point to joint data */
@ -421,7 +421,11 @@ static void process_inputs(void)
(joint->backlash_filt + joint->motor_offset);
}
/* calculate following error */
joint->ferror = joint->pos_cmd - joint->pos_fb;
if ( IS_EXTRA_JOINT(joint_num) && get_homed(joint_num) ) {
joint->ferror = 0; // not relevant for homed extrajoints
} else {
joint->ferror = joint->pos_cmd - joint->pos_fb;
}
abs_ferror = fabs(joint->ferror);
/* update maximum ferror if needed */
if (abs_ferror > joint->ferror_high_mark) {
@ -548,7 +552,7 @@ static void do_forward_kins(void)
emcmot_joint_t *joint;
/* copy joint position feedback to local array */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
/* copy feedback */
@ -660,7 +664,7 @@ static void process_probe_inputs(void)
SET_MOTION_ERROR_FLAG(1);
}
for(i=0; i<emcmotConfig->numJoints; i++) {
for(i=0; i<NO_OF_KINS_JOINTS; i++) {
emcmot_joint_t *joint = &joints[i];
if (!GET_JOINT_ACTIVE_FLAG(joint)) {
@ -729,7 +733,7 @@ static void check_for_faults(void)
}
}
/* check for various joint fault conditions */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
/* only check active, enabled axes */
@ -793,7 +797,7 @@ static void set_operating_mode(void)
#endif
/* clear out the motion emcmotDebug->coord_tp and interpolators */
tpClear(&emcmotDebug->coord_tp);
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
/* disable free mode planner */
@ -835,7 +839,7 @@ static void set_operating_mode(void)
}
initialize_external_offsets();
tpSetPos(&emcmotDebug->coord_tp, &emcmotStatus->carte_pos_cmd);
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
joint->free_tp.curr_pos = joint->pos_cmd;
@ -865,7 +869,7 @@ static void set_operating_mode(void)
/* update coordinated emcmotDebug->coord_tp position */
tpSetPos(&emcmotDebug->coord_tp, &emcmotStatus->carte_pos_cmd);
/* drain the cubics so they'll synch up */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
cubicDrain(&(joint->cubic));
@ -887,7 +891,7 @@ static void set_operating_mode(void)
if (!emcmotDebug->teleoperating && GET_MOTION_TELEOP_FLAG()) {
SET_MOTION_TELEOP_FLAG(0);
if (!emcmotDebug->coordinating) {
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
/* update free planner positions */
@ -906,7 +910,7 @@ static void set_operating_mode(void)
tpSetPos(&emcmotDebug->coord_tp, &emcmotStatus->carte_pos_cmd);
/* drain the cubics so they'll synch up */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
cubicDrain(&(joint->cubic));
@ -926,7 +930,7 @@ static void set_operating_mode(void)
/* check entering free space mode */
if (!emcmotDebug->coordinating && GET_MOTION_COORD_FLAG()) {
if (GET_MOTION_INPOS_FLAG()) {
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
/* set joint planner curr_pos to current location */
@ -966,7 +970,7 @@ static void handle_jjogwheels(void)
double distance, pos, stop_dist;
static int first_pass = 1; /* used to set initial conditions */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
double jaccel_limit;
/* point to joint data */
joint_data = &(emcmot_hal_data->joint[joint_num]);
@ -1188,7 +1192,7 @@ static void get_pos_cmds(long period)
int violated_teleop_limit = 0;
/* copy joint position feedback to local array */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
/* copy coarse command */
@ -1207,13 +1211,15 @@ static void get_pos_cmds(long period)
/* in free mode, each joint is planned independently */
/* initial value for flag, if needed it will be cleared below */
SET_MOTION_INPOS_FLAG(1);
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
if (!GET_JOINT_ACTIVE_FLAG(joint)) {
/* if joint is not active, skip it */
continue;
}
// extra joint is not managed herein after homing:
if (IS_EXTRA_JOINT(joint_num) && get_homed(joint_num)) continue;
if(joint->acc_limit > emcmotStatus->acc)
joint->acc_limit = emcmotStatus->acc;
@ -1355,7 +1361,7 @@ static void get_pos_cmds(long period)
if(result == 0)
{
/* copy to joint structures and spline them up */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
if(!isfinite(positions[joint_num]))
{
reportError(_("kinematicsInverse gave non-finite joint location on joint %d"),
@ -1387,7 +1393,7 @@ static void get_pos_cmds(long period)
} // while
/* there is data in the interpolators */
/* run interpolation */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
/* interpolate to get new position and velocity */
@ -1443,7 +1449,7 @@ static void get_pos_cmds(long period)
/* copy to joint structures and spline them up */
if(result == 0)
{
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < NO_OF_KINS_JOINTS; joint_num++) {
if(!isfinite(positions[joint_num]))
{
reportError(_("kinematicsInverse gave non-finite joint location on joint %d"),
@ -1483,7 +1489,7 @@ static void get_pos_cmds(long period)
/* set position commands to match feedbacks, this avoids
disturbances and/or following errors when enabling */
emcmotStatus->carte_pos_cmd = emcmotStatus->carte_pos_fb;
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
/* save old command */
@ -1505,7 +1511,7 @@ static void get_pos_cmds(long period)
2) if homing params are wrong then after homing joint pos_cmd are outside,
the upstream checks will pass it.
*/
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
/* skip inactive or unhomed axes */
@ -1526,7 +1532,7 @@ static void get_pos_cmds(long period)
if ( onlimit ) {
if ( ! emcmotStatus->on_soft_limit ) {
/* just hit the limit */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
if (joint_limit[joint_num][0] == 1) {
joint = &joints[joint_num];
reportError(_("Exceeded NEGATIVE soft limit (%.5f) on joint %d\n"),
@ -1670,7 +1676,7 @@ static void compute_screw_comp(void)
/* compute the correction */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
if (!GET_JOINT_ACTIVE_FLAG(joint)) {
@ -1934,7 +1940,7 @@ static void output_to_hal(void)
} else {
int i;
double v2 = 0.0;
for(i=0; i < emcmotConfig->numJoints; i++)
for(i=0; i < ALL_JOINTS; i++)
if(GET_JOINT_ACTIVE_FLAG(&(joints[i])) && joints[i].free_tp.active)
v2 += joints[i].vel_cmd * joints[i].vel_cmd;
if(v2 > 0.0)
@ -1988,16 +1994,17 @@ static void output_to_hal(void)
*(emcmot_hal_data->tooloffset_w) = emcmotStatus->tool_offset.w;
/* output joint info to HAL for scoping, etc */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint struct */
joint = &joints[joint_num];
joint_data = &(emcmot_hal_data->joint[joint_num]);
/* apply backlash and motor offset to output */
joint->motor_pos_cmd =
joint->pos_cmd + joint->backlash_filt + joint->motor_offset;
/* point to HAL data */
joint_data = &(emcmot_hal_data->joint[joint_num]);
/* write to HAL pins */
*(joint_data->motor_offset) = joint->motor_offset;
*(joint_data->motor_offset) = joint->motor_offset;
*(joint_data->motor_pos_cmd) = joint->motor_pos_cmd;
*(joint_data->joint_pos_cmd) = joint->pos_cmd;
*(joint_data->joint_pos_fb) = joint->pos_fb;
@ -2031,7 +2038,17 @@ static void output_to_hal(void)
*(joint_data->unlock) = 0;
}
} //for joint_num
if (IS_EXTRA_JOINT(joint_num) && get_homed(joint_num)) {
// passthru posthome_cmd with motor_offset
// to hal pin: joint.N.motor-pos-cmd
extrajoint_hal_t *ejoint_data;
int e = joint_num - NO_OF_KINS_JOINTS;
ejoint_data = &(emcmot_hal_data->ejoint[e]);
*(joint_data->motor_pos_cmd) = *(ejoint_data->posthome_cmd)
+ joint->motor_offset;
continue;
}
} // for joint_num
/* output axis info to HAL for scoping, etc */
for (axis_num = 0; axis_num < EMCMOT_MAX_AXIS; axis_num++) {
@ -2067,7 +2084,7 @@ static void update_status(void)
/* copy status info from private joint structure to status
struct in shared memory */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to joint data */
joint = &joints[joint_num];
/* point to joint status */

View file

@ -20,7 +20,13 @@
/* number of joints supported
Note: this is not a global variable but a compile-time parameter
since it sets array sizes, etc. */
// total number of joints available (kinematics_joints + extra_joints)
#define EMCMOT_MAX_JOINTS 16
// number of extra joints (NOT used in kinematics calculations):
#define EMCMOT_MAX_EXTRAJOINTS EMCMOT_MAX_JOINTS
/* number of axes defined by the interp */ //FIXME: shouldn't be here..
#define EMCMOT_MAX_AXIS 9

View file

@ -182,15 +182,15 @@ static void update_home_is_synchronized(void) {
int jno,joint_num;
// first, clear all H[*].home_is_synchronized
for (jno = 0; jno < emcmotConfig->numJoints; jno++) {
for (jno = 0; jno < ALL_JOINTS; jno++) {
H[jno].home_is_synchronized = 0;
}
for (jno = 0; jno < emcmotConfig->numJoints; jno++) {
for (jno = 0; jno < ALL_JOINTS; jno++) {
if (H[jno].home_sequence < 0) {
H[jno].home_is_synchronized = 1;
continue;
}
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
if (joint_num == jno) continue;
if ( ( H[joint_num].home_sequence < 0)
&& (ABS(H[joint_num].home_sequence) == H[jno].home_sequence) ) {
@ -397,7 +397,7 @@ void do_homing_sequence(void)
case HOME_SEQUENCE_DO_ONE_JOINT:
// Expect one joint with home_state==HOME_START
for (i=0; i < emcmotConfig->numJoints; i++) {
for (i=0; i < ALL_JOINTS; i++) {
joint = &joints[i];
if (H[i].home_state == HOME_START) {
H[i].joint_in_sequence = 1;
@ -419,7 +419,7 @@ void do_homing_sequence(void)
// Determine home_sequence and set H[i].joint_in_sequence
// based on home_state[i] == HOME_START
if (!sequence_is_set) {
for (i=0; i < emcmotConfig->numJoints; i++) {
for (i=0; i < ALL_JOINTS; i++) {
joint = &joints[i];
if (H[i].home_state == HOME_START) {
if ( sequence_is_set
@ -465,7 +465,7 @@ void do_homing_sequence(void)
for(i=0; i < MAX_HOME_SEQUENCES; i++) {
H[i].sync_final_move = 0; //reset to allow a rehome
}
for(i=0; i < emcmotConfig->numJoints; i++) {
for(i=0; i < ALL_JOINTS; i++) {
if (!H[i].joint_in_sequence) continue;
joint = &joints[i];
if ( (H[i].home_flags & HOME_NO_REHOME)
@ -478,7 +478,7 @@ void do_homing_sequence(void)
if (H[i].home_sequence < 0) {
// if a H[i].home_sequence is neg, find all joints that
// have the same ABS sequence value and make them the same
for(ii=0; ii < emcmotConfig->numJoints; ii++) {
for(ii=0; ii < ALL_JOINTS; ii++) {
if (H[ii].home_sequence == ABS(H[i].home_sequence)) {
H[ii].home_sequence = H[i].home_sequence;
}
@ -489,14 +489,14 @@ void do_homing_sequence(void)
* synchronize all joints final move
*/
special_case_sync_all = 1; // disprove
for(i=0; i < emcmotConfig->numJoints; i++) {
for(i=0; i < ALL_JOINTS; i++) {
joint = &joints[i];
if (H[i].home_sequence != -1) {special_case_sync_all = 0;}
}
if (special_case_sync_all) {
home_sequence = 1;
}
for(i=0; i < emcmotConfig->numJoints; i++) {
for(i=0; i < ALL_JOINTS; i++) {
if (!H[i].joint_in_sequence) continue;
joint = &joints[i];
if ( H[i].home_state != HOME_IDLE && H[i].home_state != HOME_START) {
@ -511,7 +511,7 @@ void do_homing_sequence(void)
case HOME_SEQUENCE_START_JOINTS:
/* start all joints whose sequence number matches home_sequence */
for(i=0; i < emcmotConfig->numJoints; i++) {
for(i=0; i < ALL_JOINTS; i++) {
joint = &joints[i];
if(ABS(H[i].home_sequence) == home_sequence) {
if (!H[i].joint_in_sequence) continue;
@ -532,7 +532,7 @@ void do_homing_sequence(void)
break;
case HOME_SEQUENCE_WAIT_JOINTS:
for(i=0; i < emcmotConfig->numJoints; i++) {
for(i=0; i < ALL_JOINTS; i++) {
if (!H[i].joint_in_sequence) continue;
joint = &joints[i];
// negative H[i].home_sequence means sync final move
@ -584,7 +584,7 @@ void do_homing(void)
return;
}
/* loop thru joints, treat each one individually */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
if (!H[joint_num].joint_in_sequence) continue;
/* point to joint struct */
joint = &joints[joint_num];
@ -1147,7 +1147,7 @@ void do_homing(void)
int jno;
emcmot_joint_t *jtmp;
H[home_sequence].sync_final_move = 1; //disprove
for (jno = 0; jno < emcmotConfig->numJoints; jno++) {
for (jno = 0; jno < ALL_JOINTS; jno++) {
jtmp = &joints[jno];
if (!H[jno].joint_in_sequence) continue;
if (ABS(H[jno].home_sequence) != home_sequence) {continue;}

View file

@ -1,4 +1,4 @@
/********************************************************************
/*******************************************************************
* Description: mot_priv.h
* Macros and declarations local to the realtime sources.
*
@ -115,6 +115,10 @@ typedef struct {
hal_bit_t *jjog_vel_mode; /* RPI: true for "velocity mode" jogwheel */
} joint_hal_t;
typedef struct {
hal_float_t *posthome_cmd; // IN pin extrajoint
} extrajoint_hal_t;
typedef struct {
hal_float_t *pos_cmd; /* RPI: commanded position */
hal_float_t *teleop_vel_cmd; /* RPI: commanded velocity */
@ -199,6 +203,7 @@ typedef struct {
spindle_hal_t spindle[EMCMOT_MAX_SPINDLES]; /*spindle data */
joint_hal_t joint[EMCMOT_MAX_JOINTS]; /* data for each joint */
extrajoint_hal_t ejoint[EMCMOT_MAX_EXTRAJOINTS]; /* data for each extrajoint */
axis_hal_t axis[EMCMOT_MAX_AXIS]; /* data for each axis */
hal_bit_t *eoffset_active; /* ext offsets active */
@ -234,6 +239,19 @@ extern struct emcmot_config_t *emcmotConfig;
extern struct emcmot_debug_t *emcmotDebug;
extern struct emcmot_error_t *emcmotError;
// total number of joints (typically set with [KINS]JOINTS)
#define ALL_JOINTS emcmotConfig->numJoints
// number of kinematics-only joints:
#define NO_OF_KINS_JOINTS (ALL_JOINTS - emcmotConfig->numExtraJoints)
#define IS_EXTRA_JOINT(jno) (jno >= NO_OF_KINS_JOINTS)
// 0-based Joint numbering:
// kinematic-only jno.s: [0 ... (NO_OF_KINS_JOINTS -1) ]
// extrajoint jno.s: [NO_OF_KINS_JOINTS ... (ALL_JOINTS -1) ]
/***********************************************************************
* PUBLIC FUNCTION PROTOTYPES *
************************************************************************/

View file

@ -51,7 +51,9 @@ static int num_spindles = 1; /* default number of spindles is 1 */
RTAPI_MP_INT (num_spindles, "number of spindles");
int motion_num_spindles;
static int num_joints = EMCMOT_MAX_JOINTS; /* default number of joints present */
RTAPI_MP_INT(num_joints, "number of joints");
RTAPI_MP_INT(num_joints, "number of joints used in kinematics");
static int num_extrajoints = 0; /* default number of extra joints present */
RTAPI_MP_INT(num_extrajoints, "number of extra joints (not used in kinematics)");
static int num_dio = DEFAULT_DIO; /* default number of motion synched DIO */
RTAPI_MP_INT(num_dio, "number of digital inputs/outputs");
static int num_aio = DEFAULT_AIO; /* default number of motion synched AIO */
@ -118,7 +120,12 @@ static int mot_comp_id; /* component ID for motion module */
static int init_hal_io(void);
/* functions called by init_hal_io() */
static int export_joint(int num, joint_hal_t * addr);
// halpins for ALL joints (kinematic joints and extra joints):
static int export_joint(int num, joint_hal_t * addr);
// additional halpins for extrajoints:
static int export_extrajoint(int num, extrajoint_hal_t * addr);
static int export_axis(char c, axis_hal_t * addr);
static int export_spindle(int num, spindle_hal_t * addr);
@ -157,7 +164,7 @@ void switch_to_teleop_mode(void) {
}
}
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
joint = &joints[joint_num];
if (joint != 0) { joint->free_tp.enable = 0; }
}
@ -218,6 +225,23 @@ int rtapi_app_main(void)
return -1;
}
if (( num_extrajoints < 0 ) || ( num_extrajoints > num_joints )) {
rtapi_print_msg(RTAPI_MSG_ERR,
_("\nMOTION: num_extrajoints is %d, must be between 0 and %d\n\n"), num_extrajoints, num_joints);
hal_exit(mot_comp_id);
return -1;
}
if ( (num_extrajoints > 0) && (kinematicsType() != KINEMATICS_BOTH) ) {
rtapi_print_msg(RTAPI_MSG_ERR, _("\nMOTION: nonzero num_extrajoints requires KINEMATICS_BOTH\n\n"));
return -1;
}
if (num_extrajoints > 0) {
rtapi_print_msg(RTAPI_MSG_ERR,
_("\nMOTION: kinematicjoints=%2d\n extrajoints=%2d\n Total joints=%2d\n\n"),
num_joints-num_extrajoints, num_extrajoints, num_joints
);
}
if (( num_spindles < 0 ) || ( num_spindles > EMCMOT_MAX_SPINDLES )) {
rtapi_print_msg(RTAPI_MSG_ERR,
_("MOTION: num_spindles is %d, must be between 0 and %d\n"), num_spindles, EMCMOT_MAX_SPINDLES);
@ -311,8 +335,9 @@ void rtapi_app_exit(void)
static int init_hal_io(void)
{
int n, retval;
joint_hal_t *joint_data;
axis_hal_t *axis_data;
joint_hal_t *joint_data;
extrajoint_hal_t *ejoint_data;
axis_hal_t *axis_data;
rtapi_print_msg(RTAPI_MSG_INFO, "MOTION: init_hal_io() starting...\n");
@ -455,7 +480,6 @@ static int init_hal_io(void)
/* export joint pins and parameters */
for (n = 0; n < num_joints; n++) {
/* point to axis data */
joint_data = &(emcmot_hal_data->joint[n]);
/* export all vars */
retval = export_joint(n, joint_data);
@ -475,6 +499,16 @@ static int init_hal_io(void)
rtapi_print_msg(RTAPI_MSG_ERR, _("MOTION: export_joint_home_pins failed\n"));
return -1;
}
/* export joint pins and parameters */
for (n = 0; n < num_extrajoints; n++) {
ejoint_data = &(emcmot_hal_data->ejoint[n]);
retval = export_extrajoint(n + num_joints - num_extrajoints,ejoint_data);
if (retval != 0) {
rtapi_print_msg(RTAPI_MSG_ERR, _("MOTION: ejoint %d pin/param export failed\n"), n);
return -1;
}
}
/* export axis pins and parameters */
for (n = 0; n < EMCMOT_MAX_AXIS; n++) {
char c = "xyzabcuvw"[n];
@ -626,6 +660,15 @@ static int export_joint(int num, joint_hal_t * addr)
return 0;
}
static int export_extrajoint(int num, extrajoint_hal_t * addr)
{
int retval;
/* export extrajoint pins */
if ((retval = hal_pin_float_newf(HAL_IN, &(addr->posthome_cmd), mot_comp_id,
"joint.%d.posthome-cmd", num)) != 0) return retval;
return 0;
}
static int export_axis(char c, axis_hal_t * addr)
{
int retval, msg;
@ -713,7 +756,11 @@ static int init_comm_buffers(void)
SET_MOTION_TELEOP_FLAG(0);
emcmotDebug->split = 0;
emcmotStatus->heartbeat = 0;
emcmotConfig->numJoints = num_joints;
ALL_JOINTS = num_joints; // emcmotConfig->numJoints from [KINS]JOINTS
emcmotConfig->numExtraJoints = num_extrajoints; // from motmod num_extrajoints=
emcmotStatus->numExtraJoints = num_extrajoints;
emcmotConfig->numSpindles = num_spindles;
emcmotConfig->numDIO = num_dio;
emcmotConfig->numAIO = num_aio;
@ -761,7 +808,7 @@ static int init_comm_buffers(void)
axis->locking_joint = -1;
}
/* init per-joint stuff */
for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) {
for (joint_num = 0; joint_num < ALL_JOINTS; joint_num++) {
/* point to structure for this joint */
joint = &joints[joint_num];
@ -965,7 +1012,7 @@ static int setTrajCycleTime(double secs)
tpSetCycleTime(&emcmotDebug->coord_tp, secs);
/* set the free planners, cubic interpolation rate and segment time */
for (t = 0; t < emcmotConfig->numJoints; t++) {
for (t = 0; t < ALL_JOINTS; t++) {
cubicSetInterpolationRate(&(joints[t].cubic),
emcmotConfig->interpolationRate);
}
@ -996,7 +1043,7 @@ static int setServoCycleTime(double secs)
(int) (emcmotConfig->trajCycleTime / secs + 0.5);
/* set the cubic interpolation rate and PID cycle time */
for (t = 0; t < emcmotConfig->numJoints; t++) {
for (t = 0; t < ALL_JOINTS; t++) {
cubicSetInterpolationRate(&(joints[t].cubic),
emcmotConfig->interpolationRate);
cubicSetSegmentTime(&(joints[t].cubic), secs);

View file

@ -675,7 +675,7 @@ Suggestion: Split this in to an Error and a Status flag register..
unsigned char tail; /* flag count for mutex detect */
int external_offsets_applied;
EmcPose eoffset_pose;
int numExtraJoints;
} emcmot_status_t;
/*********************************
@ -706,9 +706,12 @@ Suggestion: Split this in to an Error and a Status flag register..
int config_num; /* Incremented everytime configuration
changed, should match status.config_num */
int numJoints; /* The number of joints in the system (which
int numJoints; /* The number of total joints in the system (which
must be between 1 and EMCMOT_MAX_JOINTS,
inclusive). Can be changed at insmod time */
inclusive). includes extra joints*/
int numExtraJoints; /* The number of extra joints in the system (which
must be between 1 and EMCMOT_MAX_EXTRAJOINTS,
inclusive). */
int numSpindles; /* The number of spindles, 1 to EMCMOT_MAX_SPINDLES */
KINEMATICS_TYPE kinType;

View file

@ -1223,6 +1223,7 @@ class EMC_MOTION_STAT:public EMC_MOTION_STAT_MSG {
int on_soft_limit;
int external_offsets_applied;
EmcPose eoffset_pose;
int numExtraJoints;
};
// declarations for EMC_TASK classes

View file

@ -1973,6 +1973,8 @@ int emcMotionUpdate(EMC_MOTION_STAT * stat)
stat->analog_output[aio] = emcmotStatus.analog_output[aio];
}
stat->numExtraJoints=emcmotStatus.numExtraJoints;
// set the status flag
error = 0;
exec = 0;

View file

@ -362,6 +362,7 @@ static PyMemberDef Stat_members[] = {
{(char*)"feed_override_enabled", T_BOOL, O(motion.traj.feed_override_enabled), READONLY},
{(char*)"adaptive_feed_enabled", T_BOOL, O(motion.traj.adaptive_feed_enabled), READONLY},
{(char*)"feed_hold_enabled", T_BOOL, O(motion.traj.feed_hold_enabled), READONLY},
{(char*)"num_extrajoints", T_INT, O(motion.numExtraJoints), READONLY},
// EMC_SPINDLE_STAT motion.spindle

View file

@ -930,6 +930,15 @@ class LivePlotter:
widgets.code_text.insert("end", codes)
widgets.code_text.configure(state="disabled")
# disable jog radiobutton for extrajoints that are homed
# since control is transferred to joint.N.posthome-cmd
for jno in range(num_joints - self.stat.num_extrajoints, num_joints):
jname = tabs_manual+".joints.joint"+str(jno)
#print jno,num_joints,num_extrajoints,s.homed[jno],jname
if s.homed[jno]: state="disabled"
else: state="normal"
root_window.call(jname,"configure","-state",state)
user_live_update()
def clear(self):
@ -2611,7 +2620,6 @@ class TclCommands(nf.TclCommands):
go_home(-1)
def unhome_all_joints(event=None):
if not manual_ok(): return
ensure_mode(linuxcnc.MODE_MANUAL)
set_motion_teleop(0)
c.unhome(-1)