Hi,
The problem is that your CalcJointT would most probably generate an error, because it needs that the confdata of the robtarget Offs(PointP,10,20,30) be correct. In your case, it might work because the offset is not that big, but if you have for example CalcJointT(RelTool(PointP,10,20,30 \Rz:= 180), it would most certainly generate an error.
Also, by the way, if you already have the jointtaget, there is no use in converting it to a robtarget. You can just use MoveAbsJ.
The way I circumvent the CalJointT restrictions is using error handling. But this is way too complicated and time consuming. I basically get all possible jointtargets corresponding to a desired end-effector pose. Then I need to find the one that is closest to my current position. Here’s the code:
MODULE MainModule
VAR iodev jtfile;
VAR robtarget r;
VAR jointtarget tryconf;
VAR bool notfound := TRUE;
VAR bool goodconf := TRUE;
VAR num cf1 := -2;
VAR num cf4 := -2;
VAR num cf6 := -2;
VAR num idx;
VAR jointtarget j{8};
PROC Main()
Open “U:”\File:=“jointtargets.txt”,jtfile\Write;
idx := 1;
! robtarget for which I need all possible confdata
r := CalcRobT([[100,40,-89,150,-40,-70], [9E9,9E9,9E9,9E9,9E9,9E9] ], tool0);
Write jtfile, “Position (x,y,z) : " + NumToStr(r.trans.x,3) + " mm, " \NoNewLine;
Write jtfile, NumToStr(r.trans.y,3) + " mm, " + NumToStr(r.trans.z,3) + " mm”;
Write jtfile, “Orientation (az, ay, ax) : " + NumToStr(EulerZYX(\Z, r.rot),3) +” deg, " \NoNewLine;
Write jtfile, NumToStr(EulerZYX(\Y, r.rot),3) + " deg, " + NumToStr(EulerZYX(\X, r.rot),3) + " deg";
Write jtfile,“”;
notfound := TRUE;
goodconf := TRUE;
FOR cfx FROM 0 TO 7 DO !looking for all solutions of the inverse kinematics
notfound := TRUE;
WHILE notfound AND cf1 <= 1 DO
WHILE notfound AND cf4 <= 1 DO
WHILE notfound AND cf6 <= 1 DO
tryconf := CalcJointT([r.trans,r.rot,[cf1,cf4,cf6,cfx],[9E9,9E9,9E9,9E9,9E9,9E9]],tool0);
IF goodconf AND tryconf.robax.rax_1 <= 180
AND tryconf.robax.rax_4 >= -180 AND tryconf.robax.rax_4 < 180
AND tryconf.robax.rax_6 >= -180 AND tryconf.robax.rax_6 < 180 THEN
j{idx} := tryconf;
Write jtfile,“j{” + NumToStr(idx,0) + “} := [[” \NoNewLine;
Write jtfile,NumToStr(tryconf.robax.rax_1,3) + “,” \NoNewLine;
Write jtfile,NumToStr(tryconf.robax.rax_2,3) + “,” \NoNewLine;
Write jtfile,NumToStr(tryconf.robax.rax_3,3) + “,” \NoNewLine;
Write jtfile,NumToStr(tryconf.robax.rax_4,3) + “,” \NoNewLine;
Write jtfile,NumToStr(tryconf.robax.rax_5,3) + “,” \NoNewLine;
Write jtfile,NumToStr(tryconf.robax.rax_6,3) + “],” \NoNewLine;
Write jtfile,“[9E9,9E9,9E9,9E9,9E9,9E9]];”;
idx := idx + 1;
notfound := FALSE; !des qu’on trouve une solution, on passe au prochain cfx
ENDIF
goodconf := TRUE;
cf6 := cf6 + 1;
ENDWHILE
cf6 := -2;
cf4 := cf4 + 1;
ENDWHILE
cf4 := -2;
cf1 := cf1 + 1;
ENDWHILE
cf1 := -2;
ENDFOR
Close jtfile;
ERROR
!When the confdata in CalcJointT is not good, RAPID generates the error number 1074 (ERR_ROBLIMIT)
IF ERRNO = ERR_ROBLIMIT THEN
goodconf := FALSE;
TryNext;
ENDIF
ENDPROC
ENDMODULE