Scara support ?
-
Hello,
I come to you for help if possible …
My configuration:
Firmware Name: RepRapFirmware for Duet WiFi
Firmware Electronics: Duet WiFi 1.0
Firmware Version: 1.19beta8 (2017-06-30)
WiFi Server Version: 1.19beta8
Web Interface Version: 1.16If i do a g28 z0
Position returns after homing
X400 y0 z398
Why x400 ???If i do
G1 S2 X10 ==> ok
G1 S2 X-10 ==> ok
G1 S2 y10 ==> ok
G1 S2 y-10 ==> okAfter all the movements X/Y do not correspond to anything moving …
Setting C0: 0: 0 is good or bad for my scara configuration?
M669 K4 P200 D200 A-90:90 B-135:135 C0:0:0 S200; ,???I can not use it ==> G92 X0 Y0
Return ==> Erreur: SyntaxError: JSON.parse: unexpected keyword at line 1 column 65 of the JSON data–-------------------------------------------------------
;My file homez.g
G91 ; use relative positioning
G1 S1 X700 Y700 Z700 F250 ; move all carriages up 700mm, stopping at the endstops
G90 ; back to absolute positioning–------------------------------------------------------
;My file config.g; Configuration file for Duet WiFi (firmware version 1.17)
; executed by the firmware on start-up; General preferences
;M111 S0 ; Debugging off
M111 S1 ; Debugging on
G21 ; Work in millimetres
G90 ; Send absolute coordinates…
M83 ; ...but relative extruder moves
M555 P2 ; Set firmware compatibility to look like Marlin
M208 X0 Y0 Z0 S1 ; Set axis minima
M208 X300 Y300 Z398 S0 ; Set axis maxima; Endstops
M574 X1 Y1 S0 ; Define active low and unused microswitches
M574 Z2 S0 ; Define active high microswitches; Drives - Axis and motor configuration
M569 P0 S0 ; Drive 0 (X) goes forwards
M569 P1 S1 ; Drive 1 (Y) goes forwards
M569 P2 S0 ; Drive 2 (Z) goes forwards
M569 P3 S0 ; Drive 3 (E0) goes forwards
M350 X16 Y16 Z16 E16 I1 ; Configure microstepping with interpolation
;Calcul Step/mm X/Y (Réduction 80/16) ==> 40016(80/16)/360=88,888888888888888888888888888889
;Calcul Step/mm Z (Réduction 51/1) ==> 2001651/2.0/20=4080
M92 X88.8888888888889 Y88.8888888888889 Z4080 E550 ; Set steps per mm
M566 X900 Y900 Z12 E120 ; Set maximum instantaneous speed changes (mm/min)
M203 X6000 Y6000 Z300 E2700 ; Set maximum speeds (mm/min)
M201 X500 Y500 Z250 E250 ; Set accelerations (mm/s^2)
M906 X1400 Y1400 Z1400 E1400 I60 ; Set motor currents (mA) and motor idle factor in per cent
M84 S30 ; Set idle timeout
M669 K4 P200 D200 A-90:90 B-135:135 C0:0:0 S200; set SCARA kinematics parameters [TODO what are bb and cc for the Helios?]; Heaters Buse & Bed
M143 S260 ; Set maximum heater temperature to 260C
M305 P0 T100000 B4725 C7.060000e-8 R4700 ; Set thermistor + ADC parameters for heater 0
M305 P1 T100000 B4725 C7.060000e-8 R4700 ; Set thermistor + ADC parameters for heater 1; Tools
M563 P0 D0 H1 ; Define tool 0
G10 P0 X0 Y0 Z0 ; Set tool 0 axis offsets
G10 P0 R0 S0 ; Set initial tool 0 active and standby temperatures to 0C; Network
M550 PScara ; Set machine name
M552 S1 ; Enable network
; Access point is configured manually via M587 by the user
M586 P0 S1 ; Enable HTTP
M586 P1 S0 ; Disable FTP
M586 P2 S0 ; Disable Telnet; Fans
M106 P0 S0.3 I0 F500 H-1 ; Set fan 0 value, PWM signal inversion and frequency. Thermostatic control is turned off
M106 P1 S1 I0 F500 H1 T45 ; Set fan 1 value, PWM signal inversion and frequency. Thermostatic control is turned on
M106 P2 S1 I0 F500 H1 T45 ; Set fan 2 value, PWM signal inversion and frequency. Thermostatic control is turned on
–------------------------------------------------------ -
As explained on the page I linked to:
aaa is the amount by which the X motor (whose primary function is to control the proximal arm) affects the angle between the distal arm and the X axis. For example, if movement of the proximal motor does not affect the proximal-to-distal joint angle, then an X motor movement that causes one degree of proximal arm movement also changes the angle between the distal arm and the X axis by one degree, and the crosstalk factor is 1.
the C parameter for your geometry should be 1:0:0. Caution: in a future firmware release I may change the meaning of the C parameter and you may need to use C0:0:0 instead.
-
Thank you for your prompt response
Modified ==> M669 K4 P200 D200 A-90:90 B-135:135 1:0:0 S200
The command "G92 X0 Y0" is apparently bugger ….
Return ==> Erreur: SyntaxError: JSON.parse: unexpected keyword at line 1 column 65 of the JSON dataAll gcode are inverted X/Y The arms move backwards
ok ==> Homing
ok ==> G1 S2 X10 should rotate the proximal arm 10 degrees anticlockwise
ok ==> G1 S2 X-10 should rotate the proximal arm 10 degrees clockwise.
ok ==> G1 S2 y10 should rotate the proximal arm 10 degrees anticlockwise
ok ==> G1 S2 y-10 should rotate the proximal arm 10 degrees clockwise. -
I think the problem is that X0 Y0 is not an accessible point on any SCARA printer, so the arm joint position calculation returns "nan" instead of a number, and that causes the JSON parsing error. Try extending both arms in the +X direction before you start or reset the Duet.
-
Same error on duet web control if change position
On Pronterface X+ RETURN/
[[language]] [ERROR] Traceback (most recent call last): File "printrun\printcore.pyc", line 241, in _readline File "printrun\pronterface.pyc", line 1713, in recvcb File "printrun\pronterface.pyc", line 1669, in update_pos ValueError: could not convert string to float: ```G92 X0 Y0 return no error on Pronterface but after cmd duet bugged not move …
-
Try placing the print head somewhere it can reach easily. For example, X300 Y0. Then send G92 with those coordinates.
If that doesn't work, I'll simulate your printer later today and see if I can reproduce the problem.
In the next beta firmware release, I'll add error handling for attempts to set unreachable positions with G92.
-
Hi
G92 X0 Y0 ==> ko
G92 X300 Y0 ==>okTest…
move manualy arm on x300 y0
send G92 x300 y0move with ptonterface button
x+ 100 ok (Approximately to the eye)
After +100 blocking no longer moves to x +on position x100 y300
test move y-100 (result move Approximately to the eye on y250 x10)
Y does not move correctly, Appears y move diagonallyon Pronterface all mouvement return:
[[language]] [ERROR] Traceback (most recent call last): File "printrun\printcore.pyc", line 241, in _readline File "printrun\pronterface.pyc", line 1713, in recvcb File "printrun\pronterface.pyc", line 1669, in update_pos ValueError: could not convert string to float:
–-------------------------------------------------
Edit Upgrade ....Just for info...
On Smoothieware i have modified
https://github.com/Smoothieware/Smoothieware/blob/edge/src/modules/robot/arm_solutions/MorganSCARASolution.cppComment:
//actuator_mm[BETA_STEPPER ] = to_degrees(SCARA_theta + SCARA_psi); // Morgan kinematics (dual arm)
Uncomment:
actuator_mm[BETA_STEPPER ] = to_degrees(SCARA_psi); // real scara
and removed ==> * this->morgan_scaling_x on:
SCARA_pos[X_AXIS] = (cartesian_mm[X_AXIS] - this->morgan_offset_x) * this->morgan_scaling_x; //Translate cartesian to tower centric SCARA X Y AND apply scaling factor from this offset.
SCARA_pos[Y_AXIS] = (cartesian_mm[Y_AXIS] * this->morgan_scaling_y - this->morgan_offset_y); // morgan_offset not to be confused with home offset. This makes the SCARA math work.After support real scara its ok
Impatient to test with Duet -
To operate a Scara kinematics it must specify to him where is its zero in the space before making a G92, no?
Example in Smoothie I have 2 parameters to say where is zero in space with compared to the main axis of the first armmorgan_offset_x 150 #my X offset
morgan_offset_y -68 #my Y offset
http://smoothieware.org/configuration-optionsI'm not good at math, but it seems to me that it lacks these parameters.
-
To operate a Scara kinematics it must specify to him where is its zero in the space before making a G92, no?
Example in Smoothie I have 2 parameters to say where is zero in space with compared to the main axis of the first armmorgan_offset_x 150 #my X offset
morgan_offset_y -68 #my Y offset
http://smoothieware.org/configuration-optionsI'm not good at math, but it seems to me that it lacks these parameters.
You may have a point. I don't have a SCARA printer yet, nor have I ever used one, so I don't know how they are normally set up. Where is X=0 Y=0 normally placed on a Scara printer?
-
No rule in my opinion…
You can definitely define X0 / Y0 on the axis of the main arm and G92 will define the offsets, right?
-
Thanks, but that's not the way G92 works in RRF, nor in other 3D printer firmwares AFAIK. G92 is used to tell the firmware where the print head is, from which it works out the motor positions - in this case the arm positions. In essence, using G92 is an alternative to homing.
So G92 X0 Y0 is telling the firmware that the print head reference point is coincident with the proximal arm joint - which is not possible.
If there is a need to tell the firmware that we wish to define (0,0) somewhere else - for example, in the centre of the printable area - then I can see two possibilities:
1. Allow X and Y bed origin offsets to be configured for SCARA printers, as Smoothieware appears to do;
2. Use the tool offset facilities provided by G10 and M206.
-
ok
When I tested smothie I used M206 X … Y ... to redefine the offsets x0 / y0 with respect to the position of homingExample in Smoothie we define the position x0 / y0 on the bed with respect to the axis to the main arm
Morgan_offset_x 150
Morgan_offset_y -68And after homing I measure the distances xo / y0 and I correct the offsets with M206 and they are put in memory for recalculation
I'm really not sure how to express myself correctly in English ... -
Without the homing currently you can add M206 to calculate the position x0 / y0 with respect to the axis of the first arm, No?
And after when the homing will be functional you will add the offsets … -
I've decided to add X and Y parameters to 1.19beta9 to allow the bed to be offset from the proximal joint. I will also change the way that the crosstalk factor works, which will have the effect of making C0:0:0 correct for your machine and C-1:0:0 correct for the Helios.
Until homing is implemented, I suggest you manually move the arms (slowly, to be kind to the electronics) so they are in line and the proximal joint is at the half way position. Then power on. The displayed coordinates should show Y=0 and X= just below the sum of the arm lengths. If you then send a G92 command with the same X and Y coordinates as the displayed ones, it will then consider that the machine has been homed.
We're planning to display a Helios at the TCT show in September, which means that I will get SCARA homing working before then.
-
Firmware 1.19beta9 is out, with added X and Y bed origin offsets and a fix for G92 X0 Y0.
-
Oup's…
I had not seen page 2 of the post
A big thank you for your responsiveness !
I test this afternoon at fablab -
Hello,
Again a big thank you for your responsiveness
My tests:The M669 command used (X150.0 Y-61.0):
M669 K4 P200 D200 A-175:175 B-175:175 1:0:0 S200 X150.0 Y-61.0; set SCARA kinematics parametersok
Test moves First arm of 20 ° it's ok?
G1 S2 X10 ;anticlockwise
G1 S2 X-10 ;clockwiseok
Test moves second arm of 20 ° it's ok?
G1 S2 Y10 ;anticlockwise
G1 S2 Y-10 ;clockwiseAll movements in Pronterface in debug mode return:
SENDING:G92 X0 Y0
[ERROR] Traceback (most recent call last):
File "printrun\printcore.pyc", line 241, in _readline
File "printrun\pronterface.pyc", line 1713, in recvcb
File "printrun\pronterface.pyc", line 1669, in update_pos
ValueError: could not convert string to float:Homing goes in the right direction x/y/z
I manually move the arms to position x0/y0
I power on with Pronterface I send command G92 X0 Y0I'm testing x/y placements everything works but upside down
When i do x + i get an x-
And when i do a y + i get a y-I reverse the engines in config.g and the displacements do anything?
I put the file config.g normal, and I reverse the connector of the engines,
Same results the movements do anythingIn short I did not succeed in reversing the meaning, how to do?
It's almost perfect we're not far -
In writing the firmware I assumed that the bed is to the right of the proximal joint, and the zero angle position of both arms is with them stretched out to the right so that they point towards the +X direction. Do you by any chance have your arm mounted the other way round?
-
hi
My Kinematics
for later End-stops (hall effect +on5v) are on X22.00 Y-35.00
-
Ok, so what i have assumed is +X is your +Y, and what I have assumed is +Y is your -X. Thinking about it, there are 4 possible orientations of the bed if we only consider the obvious ones, and I guess the firmware should allow any of them in a configuration option. Or maybe it should allow an arbitrary bed rotation angle.
For now, if you define the top left corner of the bed in your diagram as (0,0) and the axis directions as I have assumed them, then you should be able to print
Regarding homing, I was assuming there will be a limit switch at one end of the travel of each joint.