Scara kinematics configuration issue

More
03 Jul 2016 19:30 #76947 by sliptonic
I'm continuing to configure my IBM 7575 scara robot. I have it working well in joint mode including homing. I still have some issues in world mode including a basic question:

The C axis (joint 5) is the rotation around the Z of the manipulator. My limited understanding of scarakins is that C is calculated and the motor drives the axis to keep the axis correctly aligned relative to the world coordinate system unless C motion is commanded. However, this ibm robot has the motor for the C axis in the pillar. It's connected to the manipulator through a set of belts that run through the shoulder and elbow joints. As a result, the C axis keeps its alignment mechanically when either the shoulder or elbow is moved.

In other words, even with the power off, I can swing the shoulder/elbow/both joints throughout the range of motion and the C orientation doesn't change relative to the world.

But using the standard scarakins, I have all sorts of problems in world mode. I can't jog without getting immediate following errors.

Since this is the first scara robot I've ever played with up close, I really don't know what 'normal' is. Is this a standard configuration for a scara bot? What would I have to change in scarakins to make it behave correctly for this machine?

Please Log in or Create an account to join the conversation.

More
04 Jul 2016 07:53 #76956 by bkt
I think it is better you show your ini file and talk about your hardware (mesa card parallel port or other) .... any how I seem to see that the standard Scara kinematics is not made for high speeds .... so it is better if low-speed games , or if you increase the value of ferror ....

regards
giorgio

Please Log in or Create an account to join the conversation.

More
04 Jul 2016 16:51 - 04 Jul 2016 16:52 #76975 by sliptonic
The hardware is a 5i25+7i77 combo. The ini file is attached. The servos are capable of extremely high (scary) speed and the max acceleration and velocity are well below what they're able to do.

Moving each joint separately, I can go very fast without following errors but moving in world mode I get the errors even moving absurdly slow.

The very high error/ferror numbers for joint5 are part of debug attempts and had no effect. So I think the corrected motion of the C axis is affecting the shoulder (theta 0) and elbow (theta 1) joints.


File Attachment:

File Name: gypsy.ini
File Size:5 KB
Attachments:
Last edit: 04 Jul 2016 16:52 by sliptonic. Reason: file attachment

Please Log in or Create an account to join the conversation.

More
04 Jul 2016 18:14 #76986 by andypugh
A following error occurs when the axis.N.motor-position-cmd does not match the axis.N.motor-position-fb.

It might help to halscope those two pins to see what is going on.

With an f-error of 60,000 it ought to be impossible to trigger a following error. Maybe LinuxCNC is confused about which axis has the f-error problem?

Please Log in or Create an account to join the conversation.

More
04 Jul 2016 22:57 #77000 by sliptonic
Following this procedure, the error is extremely repeatable.

I home in joint mode. All axis move perfectly (and fast).
Switch to World mode.
Slide the jog speed to a crawl.
begin jogging in X (or Y) direction.
Both motors turn at very slow speed. I can pause and reverse direction and repeat all day without error.
However, if I continue jogging in the same direction, I hit the point were the error happens every time. It's a different point if I'm jogging in X rather than Y but it's always the same. It's as though the error is accumulating.

Watching the two pins mentioned in halwatch, the fb and cmd are reading almost exactly the same value for all joints. right up to the point the error occurs.

Jogging ONLY the C axis causes both the other two joints to move. The reported XY position in Axis flutters during the move but then settles back to where it was even though the position has changed.

The only thing I can think is that the mechanical linkage of the C joint through the motors is at odds with the scarakins config. I've looked through scarakins.c but I don't understand it enough to hack out the C correction.

Please Log in or Create an account to join the conversation.

More
04 Jul 2016 23:26 #77002 by andypugh

Watching the two pins mentioned in halwatch, the fb and cmd are reading almost exactly the same value for all joints. right up to the point the error occurs.

What is the difference between the values at that point (look at all joints)

Jogging ONLY the C axis causes both the other two joints to move. The reported XY position in Axis flutters during the move but then settles back to where it was even though the position has changed.


I think what this basically comes down to is that your robot isn't a SCARA geometry.

You can see in the code that joint3->A3->X and Y position calculations:
int kinematicsForward(const double * joint,
                      EmcPose * world,
                      const KINEMATICS_FORWARD_FLAGS * fflags,
                      KINEMATICS_INVERSE_FLAGS * iflags)
{
    double a0, a1, a3;
    double x, y, z, c;

/* convert joint angles to radians for sin() and cos() */

    a0 = joint[0] * ( PM_PI / 180 );
    a1 = joint[1] * ( PM_PI / 180 );
    a3 = joint[3] * ( PM_PI / 180 );
/* convert angles into world coords */

    a1 = a1 + a0;
    a3 = a3 + a1;

    x = D2*cos(a0) + D4*cos(a1) + D6*cos(a3);
    y = D2*sin(a0) + D4*sin(a1) + D6*sin(a3);
    z = D1 + D3 - joint[2] - D5;
    c = a3;
	
    *iflags = 0;
    if (joint[1] < 90)
	*iflags = 1;
	
    world->tran.x = x;
    world->tran.y = y;
    world->tran.z = z;
    world->c = c * 180 / PM_PI;
	
    world->a = joint[4];
    world->b = joint[5];
	
    return (0);
}

You may need to work out the trigonometry for your particular robot. It shouldn't be particularly complicated.

Please Log in or Create an account to join the conversation.

More
05 Jul 2016 07:46 #77012 by bkt
any how ... I think your angular velocity is too hight to test first time your scara .... as suggested me andypugh in the past for my scara I set 40°/sec angular velocity for to control the behavior of the kinematic .... at higher speeds is quite difficult because of the setting of the servo drives .

regards
Giorgio

Please Log in or Create an account to join the conversation.

More
14 Jul 2016 08:10 #77431 by bkt

I think what this basically comes down to is that your robot isn't a SCARA geometry.


robot is IBM 7575 ... why these world?

regards
Giorgio

Please Log in or Create an account to join the conversation.

Time to create page: 0.094 seconds
Powered by Kunena Forum