Following error joint - robot delta

Dyskusje dotyczące działania obsługi programu LinuxCNC

Autor tematu
radek.c
Nowy użytkownik, używaj wyszukiwarki
Nowy użytkownik, używaj wyszukiwarki
Posty w temacie: 3
Posty: 5
Rejestracja: 27 lut 2017, 09:46
Lokalizacja: krk

Following error joint - robot delta

#1

Post napisał: radek.c » 06 mar 2017, 16:11

Witam, dzięki plikom syntetycznego zabrałem się (na razie) za symulację delty. Mam jednak problem, a mianowicie wyrzuca mi following error w trakcie ruchu/frezowania po osi Z. Jest to kwestia tego, że końcówka nie jest w stanie osiągnąć tej pozycji, czy może błąd w programowaniu? Dodatkowo w pliku konfiguracyjnym mam ustawioną pozycję początkową o koordynatach 0;0;0, ale po uruchomieniu ustawia się w 0;0;-360. Co jest nie tak?

Kod: Zaznacz cały

# Jeśli zmodyfikujesz ten plik zmainy zostaną
# nadpisane gdy uruchomisz ponownie Stepconf

[EMC]
MACHINE                 = DeltaR
DEBUG                   = 0

[DISPLAY]
DISPLAY                 = axis
EDITOR                  = gedit
POSITION_OFFSET         = RELATIVE
POSITION_FEEDBACK       = ACTUAL
MAX_FEED_OVERRIDE       = 1.2
INTRO_GRAPHIC           = emc2.gif
INTRO_TIME              = 5
PROGRAM_PREFIX          = /home/syntetyczny/emc2/nc_files
INCREMENTS              = 5mm 1mm .5mm .1mm .05mm .01mm .005mm

[FILTER]
PROGRAM_EXTENSION       = .png,.gif,.jpg Greyscale Depth Image
PROGRAM_EXTENSION       = .py Python Script
png                     = image-to-gcode
gif                     = image-to-gcode
jpg                     = image-to-gcode
py                      = python

[TASK]
TASK                    = milltask
CYCLE_TIME              = 0.010

[RS274NGC]
PARAMETER_FILE          = emc.var

[EMCMOT]
EMCMOT                  = motmod
COMM_TIMEOUT            = 1.0
COMM_WAIT               = 0.010
BASE_PERIOD             = 100000
SERVO_PERIOD            = 1000000

[HAL]
HALFILE                 = DeltaR.hal
HALFILE                 = custom.hal
POSTGUI_HALFILE         = custom_postgui.hal

[EMCIO]
EMCIO                   = io
CYCLE_TIME              = 0.100
TOOL_TABLE              = tool.tbl

###############################################################################

[TRAJ]

AXES                    = 3
COORDINATES             = X Y Z 
HOME                    = 0 0 90
LINEAR_UNITS            = mm
ANGULAR_UNITS           = deg
CYCLE_TIME              = 0.010
DEFAULT_VELOCITY        = 5.0
MAX_LINEAR_VELOCITY     =          80.0
DEFAULT_ACCELERATION    =  50.0
MAX_ACCELERATION        =      100.0

###############################################################################
# Axes sections
###############################################################################

#+ First axis
[AXIS_0]

TYPE                    = ANGULAR
HOME                    = 0.000
MAX_VELOCITY            = 80.0
MAX_ACCELERATION        = 100.0
STEPGEN_MAXACCEL        = 120.0
SCALE                   = 8.889 
FERROR                  = 20.0
MIN_FERROR              = 5
HOME_OFFSET             = 0.000
MIN_LIMIT               = -360.0
MAX_LIMIT               = 360.0
HOME_SEQUENCE           = 0

#+ Second axis
[AXIS_1]

TYPE                    = ANGULAR
HOME                    = 0.000
MAX_VELOCITY            = 80.0
MAX_ACCELERATION        = 100.0
STEPGEN_MAXACCEL        = 120.0
SCALE                   = 8.889 
FERROR                  = 20.0
MIN_FERROR              = 5
HOME_OFFSET             = 0.000
MIN_LIMIT               = -360.0
MAX_LIMIT               = 360.0
HOME_SEQUENCE           = 0


#+ Third axis
[AXIS_2]

TYPE                    = ANGULAR
HOME                    = 0.000
MAX_VELOCITY            = 80.0
MAX_ACCELERATION        = 100.0
STEPGEN_MAXACCEL        = 120.0
SCALE                   = 8.889 
FERROR                  = 20.0
MIN_FERROR              = 5
HOME_OFFSET             = 0.000
MIN_LIMIT               = -360.0
MAX_LIMIT               = 360.0
HOME_SEQUENCE           = 0

Kod: Zaznacz cały

# Wygenerowane przez Stepconf o Sun Oct 28 10:48:47 2012
# Jeśli zmodyfikujesz ten plik zmainy zostaną
# nadpisane gdy uruchomisz ponownie Stepconf
loadrt deltakins

#e
setp deltakins.e 86.6
#f
setp deltakins.f 485
#re
setp deltakins.re 640
#rf
setp deltakins.rf 422

loadrt [EMCMOT]EMCMOT base_period_nsec=[EMCMOT]BASE_PERIOD servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[TRAJ]AXES

#cos nowego:
#loadrt ddt count=12

#loadrt probe_parport
loadrt hal_parport cfg="0x378 out  "
setp parport.0.reset-time 5000
loadrt stepgen step_type=0,0,0,0,0
# wartość bezwględna???
#loadrt abs count = 1
loadrt pwmgen output_type=0

addf parport.0.read base-thread
addf stepgen.make-pulses base-thread
addf pwmgen.make-pulses base-thread
addf parport.0.write base-thread
addf parport.0.reset base-thread

addf stepgen.capture-position servo-thread
addf motion-command-handler servo-thread
addf motion-controller servo-thread
addf stepgen.update-freq servo-thread
addf pwmgen.update servo-thread

###cos od serva
#addf abs.0 servo-thread

net spindle-cmd <= motion.spindle-speed-out => pwmgen.0.value
net spindle-enable <= motion.spindle-on => pwmgen.0.enable
net spindle-pwm <= pwmgen.0.pwm
setp pwmgen.0.pwm-freq 100.0
setp pwmgen.0.scale 1166.66666667
setp pwmgen.0.offset 0.114285714286
setp pwmgen.0.dither-pwm true
net spindle-cw <= motion.spindle-forward

net estop-out => parport.0.pin-01-out
net xstep => parport.0.pin-02-out
setp parport.0.pin-02-out-reset 1
net xdir => parport.0.pin-03-out
net ystep => parport.0.pin-04-out
setp parport.0.pin-04-out-reset 1
net ydir => parport.0.pin-05-out
net zstep => parport.0.pin-06-out
setp parport.0.pin-06-out-reset 1
net zdir => parport.0.pin-07-out
net astep => parport.0.pin-08-out
setp parport.0.pin-08-out-reset 1
net adir => parport.0.pin-09-out
net spindle-cw => parport.0.pin-14-out
net spindle-pwm => parport.0.pin-16-out
net xenable => parport.0.pin-17-out




setp stepgen.0.position-scale [AXIS_0]SCALE
setp stepgen.0.steplen 1
setp stepgen.0.stepspace 0
setp stepgen.0.dirhold 35000
setp stepgen.0.dirsetup 35000
setp stepgen.0.maxaccel [AXIS_0]STEPGEN_MAXACCEL
net xpos-cmd axis.0.motor-pos-cmd => stepgen.0.position-cmd
net xpos-fb stepgen.0.position-fb => axis.0.motor-pos-fb
net xstep <= stepgen.0.step
net xdir <= stepgen.0.dir
net xenable axis.0.amp-enable-out => stepgen.0.enable

setp stepgen.1.position-scale [AXIS_1]SCALE
setp stepgen.1.steplen 1
setp stepgen.1.stepspace 0
setp stepgen.1.dirhold 35000
setp stepgen.1.dirsetup 35000
setp stepgen.1.maxaccel [AXIS_1]STEPGEN_MAXACCEL
net ypos-cmd axis.1.motor-pos-cmd => stepgen.1.position-cmd
net ypos-fb stepgen.1.position-fb => axis.1.motor-pos-fb
net ystep <= stepgen.1.step
net ydir <= stepgen.1.dir
net yenable axis.1.amp-enable-out => stepgen.1.enable

setp stepgen.2.position-scale [AXIS_2]SCALE
setp stepgen.2.steplen 1
setp stepgen.2.stepspace 0
setp stepgen.2.dirhold 35000
setp stepgen.2.dirsetup 35000
setp stepgen.2.maxaccel [AXIS_2]STEPGEN_MAXACCEL
net zpos-cmd axis.2.motor-pos-cmd => stepgen.2.position-cmd
net zpos-fb stepgen.2.position-fb => axis.2.motor-pos-fb
net zstep <= stepgen.2.step
net zdir <= stepgen.2.dir
net zenable axis.2.amp-enable-out => stepgen.2.enable

net estop-out <= iocontrol.0.user-enable-out
net estop-out => iocontrol.0.emc-enable-in

loadusr -W hal_manualtoolchange
net tool-change iocontrol.0.tool-change => hal_manualtoolchange.change
net tool-changed iocontrol.0.tool-changed <= hal_manualtoolchange.changed
net tool-number iocontrol.0.tool-prep-number => hal_manualtoolchange.number
net tool-prepare-loopback iocontrol.0.tool-prepare => iocontrol.0.tool-prepared


# tratatata delta w krata
#vismach GUI stuff

#loadusr -W hexagui
#loadusr -W halui -ini puma.ini

#net j0 axis.0.joint-pos-fb hexagui.joint.0
#net j1 axis.1.joint-pos-fb hexagui.joint.1
#net j2 axis.2.joint-pos-fb hexagui.joint.2

#net x-fb halui.axis.0.pos-feedback hexagui.axis.0
#net y-fb halui.axis.1.pos-feedback hexagui.axis.1
#net z-fb halui.axis.2.pos-feedback hexagui.axis.2

#loadrt scale count=6



Tagi:

Awatar użytkownika

k-m-r1
ELITA FORUM (min. 1000)
ELITA FORUM (min. 1000)
Posty w temacie: 2
Posty: 1417
Rejestracja: 23 cze 2008, 10:38
Lokalizacja: OOL lub DW
Kontakt:

#2

Post napisał: k-m-r1 » 06 mar 2017, 20:16

Może To będzie pomocne

Kod: Zaznacz cały

###########################################################


[EMC]
MACHINE =    Robot Scara Politechnika Opole
#VERSION =               $Revision$
DEBUG = 0

[DISPLAY]
DISPLAY = axis
EDITOR = gedit 
POSITION_OFFSET = RELATIVE
POSITION_FEEDBACK = ACTUAL
#ARCDIVISION = 64
#GRIDS = 10mm 20mm 50mm 100mm

MAX_FEED_OVERRIDE = 2.0

PYVCP = scara.xml

DEFAULT_LINEAR_VELOCITY = 10
MIN_LINEAR_VELOCITY = 0
MAX_LINEAR_VELOCITY = 20
DEFAULT_ANGULAR_VELOCITY = 10
MIN_ANGULAR_VELOCITY = 0
MAX_ANGULAR_VELOCITY = 20
INTRO_GRAPHIC = linuxcnc.gif
INTRO_TIME = 1
PROGRAM_PREFIX = /home/robot/linuxcnc/nc_files
INCREMENTS = 100mm 20mm 5mm 1mm 

[FILTER]
#PROGRAM_EXTENSION = .png,.gif,.jpg Greyscale Depth Image
#PROGRAM_EXTENSION = .py Python Script
#png = image-to-gcode
#gif = image-to-gcode
#jpg = image-to-gcode
#py = python

[TASK]
TASK = milltask
CYCLE_TIME = 0.010

[RS274NGC]
PARAMETER_FILE = linuxcnc.var

[EMCMOT]
EMCMOT = motmod
COMM_TIMEOUT = 1.0
COMM_WAIT = 0.010
BASE_PERIOD = 50000
SERVO_PERIOD = 500000

[HAL]
HALFILE = ustawienia-scara.hal
HALFILE = custom.hal
POSTGUI_HALFILE = custom_postgui.hal

[TRAJ]
AXES = 2
COORDINATES = X Y
HOME  = 0 0
LINEAR_UNITS = mm
ANGULAR_UNITS = deg

CYCLE_TIME = 0.010
DEFAULT_VELOCITY = 10
MAX_VELOCITY = 160
MAX_LINEAR_VELOCITY = 200
DEFAUL_ACCELERATION = 11
MAX_ACCELERATION = 15

[EMCIO]
EMCIO = io
CYCLE_TIME = 0.100
TOOL_TABLE = tool.tbl

[AXIS_0]

TYPE = LINEAR
HOME = 63.2563
MAX_VELOCITY = 20			
# max predkoĹ&#8250;Ä&#8225;
MAX_ACCELERATION = 10		
STEPGEN_MAXACCEL = 12			
# powinno byÄ&#8225; okoĹ&#8218;o 120% maxa_ACCEL
SCALE = 17.77777777			
#SCALE = 8.88888888 dla 1/8 krok
FERROR = 10
MIN_FERROR = 10
MIN_LIMIT = -60.0
MAX_LIMIT = 150.0

HOME_OFFSET = -60.850000
HOME_SEARCH_VEL = -2.500000		
#Bazowanie w jednostkach maszyny, znak "-" to odwrotny kierunek bazowania
HOME_LATCH_VEL = 1.500000
HOME_SEQUENCE = 0 			
#BAZOWANIE OSI JAKO PIERWSZA NUMER 0
HOME_IGNORE_LIMITS = YES

[AXIS_1]

TYPE = LINEAR
HOME = -126.5126				
# Wartosc pozycji w ktorej ma ustawic sie os po wykonaniu bazowania
MAX_VELOCITY = 20
MAX_ACCELERATION = 10
STEPGEN_MAXACCEL = 12
SCALE = 17.77777777			
#SCALE = 8.88888888 dla 1/8 krok
FERROR = 10
MIN_FERROR = 10
MIN_LIMIT = -130.0
MAX_LIMIT = 130.0
HOME_OFFSET = -129.000000
# POZYCJA KRANCOBKI BAZUJACEJ WZGLEDEM PUNKTU 0.000mm
HOME_SEARCH_VEL = -2.500000		
#Bazowanie osi predkosc w jednostkach znak "-" to odwrotny kierunek
HOME_LATCH_VEL = 1.500000		
# Predkosc ponownego najazdu na krancowke 
HOME_SEQUENCE = 0 			
# BAZOWANIE OSI JAKO DRUGA NUMER 1, TRZECIA OS NUMER 2
HOME_IGNORE_LIMITS = YES

#[AXIS_2]
#TYPE = LINEAR
#HOME = 0.0
#MAX_VELOCITY = 3
#MAX_ACCELERATION = 33.0
#STEPGEN_MAXACCEL = 25.0
#SCALE = 2.0
#FERROR = 10
#MIN_FERROR = 10
#MIN_LIMIT = -150.0
#MAX_LIMIT = 100
#HOME_OFFSET = 0.0


[b]MACH3 cnc[/b]Tworzenie Makr do palników magazynków THC OHC inne[b]EKRANY dla firm producentów maszyn[/b] Budowa sprzedaż wypalarki plazma gaz obrotnice Elektrodrążarki Frezarki Tokarki Giętarki3D inne wg zlecenia 888 708 196 Tomek Komor [email protected]


Autor tematu
radek.c
Nowy użytkownik, używaj wyszukiwarki
Nowy użytkownik, używaj wyszukiwarki
Posty w temacie: 3
Posty: 5
Rejestracja: 27 lut 2017, 09:46
Lokalizacja: krk

#3

Post napisał: radek.c » 07 mar 2017, 12:38

Ty masz liniową deltę to trochę inaczej działa.

Awatar użytkownika

k-m-r1
ELITA FORUM (min. 1000)
ELITA FORUM (min. 1000)
Posty w temacie: 2
Posty: 1417
Rejestracja: 23 cze 2008, 10:38
Lokalizacja: OOL lub DW
Kontakt:

#4

Post napisał: k-m-r1 » 07 mar 2017, 19:28

ustaw i testy

Kod: Zaznacz cały

FERROR                  = 20.000000
MIN_FERROR              = 20.000000 

miałem lipnego kompa stary IBM z P4

Kod: Zaznacz cały

BASE_PERIOD = 50000
SERVO_PERIOD = 500000

dlaczego masz

Kod: Zaznacz cały

HOME                    = 0 0 90 
[b]MACH3 cnc[/b]Tworzenie Makr do palników magazynków THC OHC inne[b]EKRANY dla firm producentów maszyn[/b] Budowa sprzedaż wypalarki plazma gaz obrotnice Elektrodrążarki Frezarki Tokarki Giętarki3D inne wg zlecenia 888 708 196 Tomek Komor [email protected]


Autor tematu
radek.c
Nowy użytkownik, używaj wyszukiwarki
Nowy użytkownik, używaj wyszukiwarki
Posty w temacie: 3
Posty: 5
Rejestracja: 27 lut 2017, 09:46
Lokalizacja: krk

#5

Post napisał: radek.c » 08 mar 2017, 16:34

Dowiedziałem się, że na linuxie 2.8 jest gotowa kinematyka do rotary delta. Zaktualizowałem więc linuxa i biorę się za gotową kinematykę. W razie problemów będę pisał. Co do "home 0 0 90" zmieniłem na 0 0 0.

[ Dodano: 2017-03-09, 09:59 ]
W tej kinematyce, jeśli ustawię pozycję home na 0 0 0 to wywala
kinematicsinverse gave non-finite join location on joint 0

Kod: Zaznacz cały

loadrt [KINS]KINEMATICS
loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD num_joints=[KINS]JOINTS

loadusr -W my_machine_gui

# add motion controller functions to servo thread
addf motion-command-handler servo-thread
addf motion-controller servo-thread

# create HAL signals for position commands from motion module
# loop position commands back to motion module feedback
net J0pos joint.0.motor-pos-cmd => joint.0.motor-pos-fb
net J1pos joint.1.motor-pos-cmd => joint.1.motor-pos-fb
net J2pos joint.2.motor-pos-cmd => joint.2.motor-pos-fb

#net J3pos joint.3.motor-pos-cmd => joint.3.motor-pos-fb
#net J4pos joint.4.motor-pos-cmd => joint.4.motor-pos-fb
#net J5pos joint.5.motor-pos-cmd => joint.5.motor-pos-fb
#net J6pos joint.6.motor-pos-cmd => joint.6.motor-pos-fb
#net J7pos joint.7.motor-pos-cmd => joint.7.motor-pos-fb
#net J8pos joint.8.motor-pos-cmd => joint.8.motor-pos-fb

net J0cmd joint.0.pos-cmd => my_machine_gui.joint0
net J1cmd joint.1.pos-cmd => my_machine_gui.joint1
net J2cmd joint.2.pos-cmd => my_machine_gui.joint2

net pfr rotarydeltakins.platformradius => my_machine_gui.pfr
net tl rotarydeltakins.thighlength => my_machine_gui.tl
net sl rotarydeltakins.shinlength => my_machine_gui.sl
net fr rotarydeltakins.footradius => my_machine_gui.fr

sets pfr 485
sets tl 422
sets sl 640
sets fr 87

#setp deltakins.e 87
#setp deltakins.f 485
#setp deltakins.re 640
#setp deltakins.rf 422

# estop loopback
net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in

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

Kod: Zaznacz cały

# This config file was created 2017-03-07 17:04:28.782048 by the update_ini script
# The original config files may be found in the /home/student/linuxcnc/configs/deltaW/deltaW.old directory

# EMC controller parameters for a simulated hexapod of the minitetra type.

# General note: Comments can either be preceded with a # or ; - either is
# acceptable, although # is in keeping with most linux config files.

# Settings with a + at the front of the comment are likely needed to get 
# changed by the user.
# Settings with a - at the front are highly unneeded to be changed


######################################
# Megjegyzések a .hal-ban!           #
######################################



###############################################################################
# General section 
###############################################################################

# General section -------------------------------------------------------------
[EMC]


#- Version of this INI file
VERSION = 1.0

#+ Name of machine, for use with display, etc.
MACHINE =               DELTA-RAIL-sbt

#- Name of NML file to use, default is emc.nml
########  NML_FILE =              emc.nml

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

###############################################################################
# Sections for display options 
###############################################################################
[DISPLAY]

#+ Name of display program, e.g., xemc
 DISPLAY =              axis 
# DISPLAY =              usrmot
# DISPLAY =              mini
# DISPLAY = 		tkemc

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

#- Path to help file
HELP_FILE =             tkemc.txt

#OPEN_FILE = /home/jozsi/Munkaasztal/Gcode/Test-10/P3-m3m5.nc
#OPEN_FILE = /home/jozsi/Munkaasztal/Gcode/Test-8/50x50z-minus-10.nc
#OPEN_FILE = /home/jozsi/Munkaasztal/Gcode/Test-10/50x50-pj-z-minus10.nc
#OPEN_FILE = /home/jozsi/Munkaasztal/Gcode/Test-Rulers/kör100z10.nc
OPEN_FILE =/home/jozsi/Asztal/Gcode/Test-12/100x100.nc

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

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

#+ Highest value that will be allowed for feed override, 1.0 = 100%
MAX_FEED_OVERRIDE =     10.0

#+ Prefix to be used
#PROGRAM_PREFIX = ../../nc_files/
PROGRAM_PREFIX = /home/jozsi/Munkaasztal/Gcode

#- Introductory graphic
INTRO_GRAPHIC = emc2.gif
INTRO_TIME = 5

#PYVCP = laserpanel.xml
#PYVCP = custompanel.xml
#PYVCP = scara.xml
#PYVCP = puma.xml
#PYVCP = custompanel.xml

# Editor to be used with Axis
EDITOR = gedit

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


###############################################################################
# Task controller section 
###############################################################################

[RS274NGC]

#- File containing interpreter variables
#PARAMETER_FILE =        puma.var
#PARAMETER_FILE =        scara.var
PARAMETER_FILE = emc.var

###############################################################################
# Motion control section 
###############################################################################

[EMCMOT]

EMCMOT =              motmod
#SHMEM_KEY =            111
#- Timeout for comm to emcmot, in seconds
COMM_TIMEOUT =          1.0

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

#- Servo task period, in nanoseconds
SERVO_PERIOD =               1000000
#- Trajectory Planner task period, in nanoseconds - will be rounded to an
#   integer multiple of SERVO_PERIOD
TRAJ_PERIOD =                10000000

###############################################################################
# Hardware Abstraction Layer section
###############################################################################

[TASK]

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

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

###############################################################################
# Part program interpreter section 
###############################################################################

[HAL]

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

# list of hal config files to run through halcmd
# files are executed in the order in which they appear
HALFILE =                    puma_sim_6.hal
#HALFILE = joypad_v3.hal
HALFILE = custom.hal
#POSTGUI_HALFILE =            puma_postgui.hal
    POSTGUI_HALFILE = custom_postgui.hal
#POSTGUI_HALFILE =            scara_postgui.hal

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

#load halui to enable 
#HALUI =                      halui

###############################################################################
# Trajectory planner section
###############################################################################

[HALUI]
#No Content
[TRAJ]

#+ machine specific settings
AXES =                  3
# COORDINATES =         X Y Z 
COORDINATES =           X Y Z 
#HOME = 			140 80 0 
HOME = 			0 0 90
LINEAR_UNITS =          mm
ANGULAR_UNITS =         deg
CYCLE_TIME =            0.010
#DEFAULT_LINEAR_VELOCITY =      5.0
DEFAULT_LINEAR_VELOCITY =      5.0
#                                           MAX_VELOCITY =          80.0
MAX_LINEAR_VELOCITY =          80.0
DEFAULT_ACCELERATION =  50.0
MAX_LINEAR_ACCELERATION =      100.0
#DEFAULT_ACCELERATION =  10.0
#MAX_LINEAR_ACCELERATION =      30.0

###############################################################################
# Axes sections
###############################################################################

#+ First axis
[EMCIO]

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

#- cycle time, in seconds
CYCLE_TIME =                    0.100

#- tool table file
TOOL_TABLE =                    puma.tbl


[KINS]
KINEMATICS = rotarydeltakins
#This is a best-guess at the number of joints, it should be checked
JOINTS = 3

[AXIS_X]
MIN_LIMIT = -240.0
MAX_LIMIT = 240.0
MAX_VELOCITY = 80.0
MAX_ACCELERATION = 100.0

[JOINT_0]

TYPE = ANGULAR
#HOME = 230.000
HOME = 0.000
MAX_VELOCITY = 80.0
MAX_ACCELERATION = 100.0
#MAX_ACCELERATION = 150.0
#STEPGEN_MAXACCEL = 160.0
STEPGEN_MAXACCEL = 120.0
INPUT_SCALE =                   4000
OUTPUT_SCALE = 2.22
#OUTPUT_SCALE = 320.0
#COMP_FILE_TYPE = 0
#COMP_FILE = axis0.comp
FERROR = 20.0
MIN_FERROR = 5
HOME_OFFSET = 0.000
MIN_LIMIT = -360.0
MAX_LIMIT = 360.0
#HOME_OFFSET = 0.
HOME_SEQUENCE =                 0



#+ Second axis
[AXIS_Y]
MIN_LIMIT = -240.0
MAX_LIMIT = 240.0
MAX_VELOCITY = 80.0
MAX_ACCELERATION = 100.0

[JOINT_1]

TYPE = ANGULAR
HOME = 0.000
MAX_VELOCITY = 80.0
MAX_ACCELERATION = 100.0
STEPGEN_MAXACCEL = 120.0
INPUT_SCALE =                   4000
OUTPUT_SCALE = 2.22
#OUTPUT_SCALE = 320.0
#COMP_FILE_TYPE = 0
#COMP_FILE = axis0.comp
FERROR = 20.0
MIN_FERROR = 5
HOME_OFFSET = 0.000
MIN_LIMIT = -360.0
MAX_LIMIT = 360.0
#HOME_OFFSET = 0.0
HOME_SEQUENCE =                 0



#+ Third axis
[AXIS_Z]
MIN_LIMIT = -180.0
MAX_LIMIT = 180.0
MAX_VELOCITY = 80.0
MAX_ACCELERATION = 100.0

[JOINT_2]

TYPE = ANGULAR
HOME = 0.000
MAX_VELOCITY = 80.0
MAX_ACCELERATION = 100.0
STEPGEN_MAXACCEL = 120.0
INPUT_SCALE =                   4000
OUTPUT_SCALE = 2.22
#OUTPUT_SCALE = 320.0
#COMP_FILE_TYPE = 0
#COMP_FILE = axis0.comp
FERROR = 20.0
MIN_FERROR = 5
HOME_OFFSET = 0.000
MIN_LIMIT = -360.0
MAX_LIMIT = 360.0
#HOME_OFFSET = 0.0
HOME_SEQUENCE =                 0



#+ Fourth axis
#[AXIS_3]
#TYPE =                          ANGULAR
#HOME =                          0.000
#MAX_VELOCITY =                  6.0
#MAX_ACCELERATION =              30.0
#BACKLASH =                      0.000
#INPUT_SCALE =                   400
#OUTPUT_SCALE =                  1.000
#MIN_LIMIT =                     -360.0
#MAX_LIMIT =                     360.0
#FERROR =                        20.0
#MIN_FERROR =                    5.0
#HOME_OFFSET =                   0.0
#HOME_SEARCH_VEL =               0.0
#HOME_LATCH_VEL =                0.0
#HOME_USE_INDEX =                NO
#HOME_IGNORE_LIMITS =            NO
#HOME_SEQUENCE =                 0

#+ Fifth axis
#[AXIS_4]
#TYPE =                          ANGULAR
#HOME =                          0.000
#MAX_VELOCITY =                  6.0
#MAX_ACCELERATION =              30.0
#BACKLASH =                      0.000
#INPUT_SCALE =                   4000
#OUTPUT_SCALE =                  1.000
#MIN_LIMIT =                     -360.0
#MAX_LIMIT =                     360.0
#FERROR =                        2.000
#MIN_FERROR =                    0.200
#HOME_OFFSET =                   0.0
#HOME_SEARCH_VEL =               0.0
#HOME_LATCH_VEL =                0.0
#HOME_USE_INDEX =                NO
#HOME_IGNORE_LIMITS =            NO
#HOME_SEQUENCE =                 0

#+ Sixth axis
#[AXIS_5]
#TYPE =                          ANGULAR
#HOME =                          0.000
#MAX_VELOCITY =                  6.0
#MAX_ACCELERATION =              30.0
#BACKLASH =                      0.000
#INPUT_SCALE =                   4000 
#OUTPUT_SCALE =                  1.000
#MIN_LIMIT =                     -180.0
#MAX_LIMIT =                     180.0
#FERROR =                        2.000
#MIN_FERROR =                    0.200
#HOME_OFFSET =                   0.0
#HOME_SEARCH_VEL =               0.0
#HOME_LATCH_VEL =                0.0
#HOME_USE_INDEX =                NO
#HOME_IGNORE_LIMITS =            NO
#HOME_SEQUENCE =                 0


###############################################################################
# section for main IO controller parameters 
###############################################################################

ODPOWIEDZ Poprzedni tematNastępny temat

Wróć do „LinuxCNC (dawniej EMC2)”