Absolute Accuracy ignored by Coordinated MultiMove?

TLDR: I think Coordinated Multimove is using non AbsAcc data for creating wobj uframe of the wobj attached to robot 1. Can I force MultiMove to use AbsAcc data?

I have two IRB2400s running RobotWare 5.16 with Absolute Accuracy and Coordinated Multimove. Absolute Accuracy is on for both bots. The rev counts are good, motors and resolvers untouched with original calibration. I have pins attached to each robot which have accurately set TCPs. I’ve used these pins to set up the base frame of robot 2 to match robot 1.

I can bring the pins tip to tip and relative wobj0 they both read the same position in multiple locations. In theory, the wobj should read [0,0,0] in this situation, but it’s off and off inconsistently - at different positions it will be off in different directions and in different amounts, [1.1,-2,0.4], etc.

However, when I switch absolute accuracy off and perform the same test the wobj reads [0,0,0] at all positions, though I have to bring the pins slightly off from tip to tip to get the robots reading that they are in the same position in space relative wobj0, as things are not as accurate. This indicates to me that MultiMove is not using Absolute Accuracy.

Have I missed some configuration setting or something?

Hallo. They recommend AbsAcc when working with Multimove Coordinated, so I suppose AbsAcc should be on all the time.

AbsAcc is improving the kinematic model of a robot by re-defining the DH parameter and also elastic distortions and gear ratio are measured.

AbsAcc is not active with MoveAbs. So when defining your wobj, check the points by moving in MoveJ/L and you will probably see a difference with AbsAcc on/off.

matti

I don’t think I was clear in my original post. Let me show my experiment.
T_ROB1:

PERS tasks task_list{2} := [[“T_ROB1”], [“T_ROB2”]];
VAR syncident sync1;
VAR syncident sync2;
PERS tooldata tPin_Rob1:=[TRUE,[[-0.367956,0.130794,64.0582],[1,0,0,0]],[0.1,[0,0,2],[1,0,0,0],0,0,0]];
PERS wobjdata wobjPin_Rob2:= [FALSE, FALSE, "ROB_2", [[0,0,0],[1,0,0,0]],[[-0.15426,0.134004,69.2849],[1,0,0,0]]];

PERS robtarget LineStart_1:=[[1000,0,500],[0.707107,0.707107,0,0],[-2,-1,1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];

PROC Report()
    VAR robtarget curpos;
    curpos:=CRobT(\TaskName:="T_ROB1"\Tool:=tPin_Rob1\WObj:=wobj0);
    TPWrite "R1 Pin, wobj0: [" + NumToStr(curpos.trans.x,1) + ", " + NumToStr(curpos.trans.y,1) + ", " + NumToStr(curpos.trans.z,1) +"]" ;
ENDPROC

PROC MotionTest_1()
    TPErase;
    ConfL\Off;
    WaitSyncTask sync1, task_list;
    MoveL LineStart_1, v300, fine, tPin_Rob1;
	waittime .5;
	Report;
	Stop;
    WaitSyncTask sync2, task_list;
    MoveL Offs(LineStart_1,-400,0,0), v300, fine, tPin_Rob1;
	waittime .5;
	Report;
	Stop;
ENDPROC

T_ROB2:

PERS tasks task_list{2} := [["T_ROB1"], ["T_ROB2"]];
VAR syncident sync1;
VAR syncident sync2;

PERS tooldata tPin_Rob2:=[TRUE,[[-0.15426,0.134004,69.2849],[1,0,0,0]],[0.1,[0,0,2],[1,0,0,0],0,0,0]];
PERS wobjdata wobjPin_Rob1 := [FALSE, FALSE, "ROB_1", [[0,0,0],[1,0,0,0]],[[-0.367956,0.130794,64.0582],[1,0,0,0]]];

PERS robtarget LineStart_2:=[[1000,0,500],[0.707107,-0.707107,0,0],[-2,-1,1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];

PROC Report()
    VAR robtarget curpos;
    curpos:=CRobT(\TaskName:="T_ROB2"\Tool:=tPin_Rob2\WObj:=wobj0);
    TPWrite "R2 Pin, wobj0: [" + NumToStr(curpos.trans.x,1) + ", " + NumToStr(curpos.trans.y,1) + ", " + NumToStr(curpos.trans.z,1) +"]" ;
    curpos:=CRobT(\TaskName:="T_ROB2"\Tool:=tPin_Rob2\WObj:=wobjPin_Rob1);
    TPWrite "R2 Pin, wobjPin_Rob1: [" + NumToStr(curpos.trans.x,1) + ", " + NumToStr(curpos.trans.y,1) + ", " + NumToStr(curpos.trans.z,1) +"]" ;
ENDPROC


PROC MotionTest_2()
    ConfL\Off;
    WaitSyncTask sync1, task_list;
	MoveL LineStart_2, v300, fine, tPin_Rob2;
	waittime .5;
	Report;
	Stop;
    WaitSyncTask sync2, task_list;
    MoveL Offs(LineStart_2,-400,0,0), v300, fine, tPin_Rob2;
	waittime .5;
	Report;
	Stop;
ENDPROC

Here is what the TPWrites display when I run the experiment with Absolute Accuracy off:
R1 Pin, wobj0: [1000.0, 0.0, 500.0]
R2 Pin, wobj0: [1000.0, 0.0, 500.0]
R2 Pin, wobjPin_Rob1: [0.0, 0.0, 0.0]
R1 Pin, wobj0: [600.0, 0.0, 500.0]
R2 Pin, wobj0: [600.0, 0.0, 500.0]
R2 Pin, wobjPin_Rob1: [0.0, 0.0, 0.0]

When I view the Online Monitor in robot studio with AbsAcc off the two TCPs are shown perfectly touching.

Now when I run with Absolute Accuracy on:
R1 Pin, wobj0: [1000.0, 0.0, 500.0]
R2 Pin, wobj0: [1000.0, 0.0, 500.0]
R2 Pin, wobjPin_Rob1: [-0.3, -2.8, -0.4]
R1 Pin, wobj0: [600.0, 0.0, 500.0]
R2 Pin, wobj0: [600.0, 0.0, 500.0]
R2 Pin, wobjPin_Rob1: [-0.1, -3.3, -0.6]

Online Monitor in RobotStudio, AbsAcc on, TCPs not touching:

There is clearly some kind of communication issue here with Absolute Accuracy and Coordinated MultiMove.

Hallo.

It is quite a sophisticated test.

How is the behaviour when executing in the real cell?

I think in RSO there is no AbsAcc, because the robot model is the ideal one.

If your MOC contains a section AXIS_CALIBRATION_JOINT (because downloaded from the real controller), AbsAcc on will take that corrections into account and show the changes done by AbsAcc ( in comparison to the ideal robot model).

In the real cell it might be the other way round, so a deviation is shown without AbsAcc.

A deviation might occur in the real cell with AbsAcc on as well, due to the base frame of the robots.

In fact, we have some applications with 2 robots in one gantry with MultiMove and AbsAcc and finely measured base frames (3D coordinate measuring) and never get the tooltips at the same point.

We can come close as 3-4 mm, but not better.

matti

In the real cell when I run my test with absolute accuracy on the tips of my pins stay within about 0.3mm. When I turn off absolute accuracy they are within about 2mm. When I try to have one robot stay on a mobile wobj controlled by the other I get similar divergence to when AbsAcc is disabled.

My guess is there is some kind of internal miscalculation for the uframe of the mobile wobj when the robot “holding” the mobile wobj has AbsAcc on. When I disable AbsAcc for just the robot holding the mobile wobj the positions in the mobile wobj read [0,0,0], just like when both robots have AbsAcc disabled.