SCARA robot configuration

558 views
Skip to first unread message

sliptonic

unread,
Mar 15, 2015, 10:47:52 AM3/15/15
to machi...@googlegroups.com
I'm rebuilding an old IBM 7575 SCARA robot.  For control, I'm using a mesa 5i25/7i77 kit, an AMD based PC, and Machinekit.  I did the initial setup through pncconf.  Pncconf doesn't do machine configurations other than Cartesian trivial kinematics, so I used that to get the motors turning and then started adapting the config by hand.  My config so far.

At this time, I've got all four motors working pretty well.  Three of the joints (shoulder, elbow, and Z) have home and limit switches working.  the last joint, the wrist or "roll" is continuous and has only an index switch. The config loads with scarakins and the scaragui corresponds to the machine movement.   So far, so good.  

Now the problems I'm seeing. All of these, I can pretty much duplicate in the stock SCARA sim config: (configs/sim/axis/vismach/scara)

1) After homing, I can usually switch into world view if I have not jogged any axis. I've I've jogged, either before or after homing but before switching modes, I get an error that all joints must be homed before switching. Re-homing doesn't help.  Shutdown machinekit and restart.   

2) The wrist joint (C or joint 3 in my case) seems unaffected by the velocity and acceleration settings in the .ini file.  Regardless of how I set them, this axis moves very slow.  This duplicates in the simulation too.

3) If I get into world mode, I can jog in Cartesian space and things look good but there are no machine limits on the coordinated moves so the machine will try to exceed it's range and make all kinds of unpleasant sounds.  Similar behavior if you start try to job in forbidden ways in the sim configuration.

I've seen documentation in the linuxcnc wiki that make me believe I should be configuring separate [AXES_n] and [JOINT_n] sections but haven't had much luck yet.

What's the best example of a non-trivial kinematics configuration I can learn from?

The wrist joint also has me confused.  On my bot, it has its own motor but is also linked to the shoulder joint.  So if the shoulder is rotated, the wrist maintains its orientation.  Anyone know if that's a feature of this bot or typical of the SCARA platform?   

Claudio Lorini

unread,
Mar 15, 2015, 11:27:41 AM3/15/15
to machi...@googlegroups.com
just a suggestion,
 
are you sure of the sequence of the axis? 
afair should be XYZABCUVW <--> 012345678
where XYZ are linear ABC rotatoinal and UVW linear
in a setup with 4 linear and 2 rotational i have: 
XY<-->0,1 and Z<-->2 unused, 
A,B<-->3,4 C<-->5 unused 
UV<-->6,7 W<-->8 unused

maybe you can post your ini file?

C.

Il giorno domenica 15 marzo 2015 15:47:52 UTC+1, sliptonic ha scritto: 
... 
2) The wrist joint (C or joint 3 in my case) seems unaffected by the velocity and acceleration settings in the .ini file.  Regardless of how I set them, this axis moves very slow.  This duplicates in the simulation too.
...
 

sliptonic

unread,
Mar 15, 2015, 12:01:31 PM3/15/15
to machi...@googlegroups.com
Sorry.  My typo.  C  is JOINT_5

The link in my original post goes to my config in a github repo.  You can see the .ini and .hal files online.

Michael Haberler

unread,
Mar 16, 2015, 3:22:22 AM3/16/15
to Collette Brad, machi...@googlegroups.com

> Am 15.03.2015 um 15:47 schrieb sliptonic <shopint...@gmail.com>:
>
> I'm rebuilding an old IBM 7575 SCARA robot. For control, I'm using a mesa 5i25/7i77 kit, an AMD based PC, and Machinekit. I did the initial setup through pncconf. Pncconf doesn't do machine configurations other than Cartesian trivial kinematics, so I used that to get the motors turning and then started adapting the config by hand. My config so far.
>
> At this time, I've got all four motors working pretty well. Three of the joints (shoulder, elbow, and Z) have home and limit switches working. the last joint, the wrist or "roll" is continuous and has only an index switch. The config loads with scarakins and the scaragui corresponds to the machine movement. So far, so good.
>
> Now the problems I'm seeing. All of these, I can pretty much duplicate in the stock SCARA sim config: (configs/sim/axis/vismach/scara)
>
> 1) After homing, I can usually switch into world view if I have not jogged any axis. I've I've jogged, either before or after homing but before switching modes, I get an error that all joints must be homed before switching. Re-homing doesn't help. Shutdown machinekit and restart.

This smelled like a flag in the kinematics module needs work, unfortunately it isnt, but it must be 'around here' (or driven by this flag):
Have a look here:

https://github.com/machinekit/machinekit/blob/master/src/emc/motion/teleop-notes#L56-L61
https://github.com/machinekit/machinekit/blob/master/src/emc/kinematics/kinematics.h#L24-L42
https://github.com/machinekit/machinekit/blob/master/src/emc/kinematics/scarakins.c#L193

Any chance you reproduce the behavior with a scarakins sim config and an exact sequence of actions to follow? If you have that I would suggest you make it an issue in the github tracker

>
> 2) The wrist joint (C or joint 3 in my case) seems unaffected by the velocity and acceleration settings in the .ini file. Regardless of how I set them, this axis moves very slow. This duplicates in the simulation too.

unfortunately you'd be better off with the joints-axes branch which isnt merged yet, and needs a determined djihadi to get it ready for a merge, see https://github.com/machinekit/machinekit/issues/438 - also the next problem might be addressed with it

> 3) If I get into world mode, I can jog in Cartesian space and things look good but there are no machine limits on the coordinated moves so the machine will try to exceed it's range and make all kinds of unpleasant sounds. Similar behavior if you start try to job in forbidden ways in the sim configuration.

Out of curiosity: I think the jog-while-paused feature in mk motion does limits correctly on _jogs during pause_. Could you try to adapt this sim config to use your kins and see that it works (in sim mode maybe)? this would help point out what is missing.

- Michael

>
> I've seen documentation in the linuxcnc wiki that make me believe I should be configuring separate [AXES_n] and [JOINT_n] sections but haven't had much luck yet.

That is related to the
>
> What's the best example of a non-trivial kinematics configuration I can learn from?
>
> The wrist joint also has me confused. On my bot, it has its own motor but is also linked to the shoulder joint. So if the shoulder is rotated, the wrist maintains its orientation. Anyone know if that's a feature of this bot or typical of the SCARA platform?
>
> --
> website: http://www.machinekit.io blog: http://blog.machinekit.io github: https://github.com/machinekit
> ---
> You received this message because you are subscribed to the Google Groups "Machinekit" group.
> To unsubscribe from this group and stop receiving emails from it, send an email to machinekit+...@googlegroups.com.
> Visit this group at http://groups.google.com/group/machinekit.
> For more options, visit https://groups.google.com/d/optout.

sliptonic

unread,
Mar 22, 2015, 10:08:23 AM3/22/15
to machi...@googlegroups.com, shopint...@gmail.com


On Monday, March 16, 2015 at 2:22:22 AM UTC-5, Michael Haberler wrote:

Any chance you reproduce the behavior with a scarakins sim config and an exact sequence of actions to follow? If you have that I would suggest you make it an issue in the github tracker

Yes.  Posted issue in tracker.

 
> 2) The wrist joint (C or joint 3 in my case) seems unaffected by the velocity and acceleration settings in the .ini file.  Regardless of how I set them, this axis moves very slow.  This duplicates in the simulation too.

unfortunately you'd be better off with the joints-axes branch which isnt merged yet, and needs a determined djihadi to get it ready for a merge, see https://github.com/machinekit/machinekit/issues/438 - also the next problem might be addressed with it

I'm certainly not that djihadi but will be willing to test as things become available.  This machine is mostly for fun and learning so I have no time pressure.  I'm still curious about why joint 3 doesn't behave like other joints even in the sim config in joint mode.  I've cranked velocity and acceleration numbers through the roof but it still only moves at about 1/2 degree per second.  

 
> 3) If I get into world mode, I can jog in Cartesian space and things look good but there are no machine limits on the coordinated moves so the machine will try to exceed it's range and make all kinds of unpleasant sounds.  Similar behavior if you start try to job in forbidden ways in the sim configuration.

Out of curiosity: I think the jog-while-paused feature in mk motion does limits correctly on _jogs during pause_. Could you try to adapt this sim config to use your kins and see that it works (in sim mode maybe)? this would help point out what is missing.

I'll try porting my config.  I've been meaning to try this for my laser and mill configs anyway.   

sliptonic

unread,
Jun 7, 2015, 3:44:55 PM6/7/15
to machi...@googlegroups.com
An update on my progress.  I'm still playing with this robot when I can between other things.

It seems like most of the problems I'm seeing are related to how joint 3 (the axis which rotates the actuator around Z) moves.  It doesn't move fast enough so in world mode, it can't keep up with the other axes and causes a following error.
I was able to duplicate the problem using the unmodified scara sim config.  I just copied /usr/share/linuxcnc/examples/sample-configs/sim/axis/vismach/scara/ to my config directory and launched it.  With the jog speed slider maxed out, the joint 0 and joint 1 axes move naturally but joint 3 (which is AXES_5 in the config) is very slow.

When I watch this joint in halscope, it looks like the commanded velocity is limited but I don't understand why.  The joint is configured identically to the other two angular joints.

One way that the sim config differs from my real config is that in world mode, the C joint in the sim config moves at expected speed.  In my real config, I get following errors.

Daren Schwenke

unread,
Jun 8, 2015, 2:29:17 PM6/8/15
to machi...@googlegroups.com
I noticed something similar.
Even with identical configs for axis 4-8, I get radically different movement speeds, and immediate joint following errors in world mode. 
As I had the option, I tried both angular and linear.  It didn't seem to make a difference.  I had the running theory that my angular/linear setting was being ignored for some of them.
I ended up settling on velocity extrusion where I don't need an axis 4-8 to 'follow'.

Brad Collette

unread,
Jun 8, 2015, 3:42:15 PM6/8/15
to Daren Schwenke, machi...@googlegroups.com
Playing with it more today we noticed that if we inspected the value of axis.N.free-vel-lim in halconfig, we got different results for some axes than others. 
After jogging the other axes with the jog speed slider maxed out, the value would reflect the the MAX_VELOCITY value from the ini file but not joint 3 (AXIS_5).  That one is always = 1.  This is consistent with what halscope shows and seems to be about the real speed of the joint (ie about 1 degree per second).


--
You received this message because you are subscribed to a topic in the Google Groups "Machinekit" group.
To unsubscribe from this topic, visit https://groups.google.com/d/topic/machinekit/oNEWETICSE4/unsubscribe.
To unsubscribe from this group and all its topics, send an email to machinekit+...@googlegroups.com.



--
Brad Collette
573-427-7132


Cody Orlovsky

unread,
Dec 20, 2018, 2:55:06 PM12/20/18
to Machinekit
I know it's been over 3 years, but what was the solution you guys had to change the MAX_VELOCITY for joint 3?

Thanks

Brad Collette

unread,
Dec 21, 2018, 10:16:05 AM12/21/18
to Cody Orlovsky, Machinekit
It's been a long time so I don't remember the details but here's the solution to my problem:



For more options, visit https://groups.google.com/d/optout.


--
Brad Collette
573-427-7132


Reply all
Reply to author
Forward
0 new messages