Jump to content
OMRON Forums

"mixed" kinematic


teremock

Recommended Posts

Hello

 

I define following CS1:

undefine all

&1

#1->x

#2->y

#3->i

#4->i

 

Then I declare necessary kinematic for motors #3 and #4 only:

open forward (1)      // Put Coordinate System number inside "(cs)"
  if (KinVelEna > 0) callsub 100;	// Double pass for velocity or error calcs
  KinAxisUsed = KinEnaAxisZ;
N100: 
  KinPosAxisZ = (KinPosMotor3 + KinPosMotor4) / 2000 * 360;
close

open inverse (1)      // Put Coordinate System number inside "(cs)"
KinPosMotor3 = KinPosAxisZ * 2000;	
KinPosMotor4 = (KinPosAxisZ - 100) * 2000;
if (KinVelEna > 0) {			// True for unsegmented PVT only
	KinVelMotor3 = KinVelAxisZ * 2000;
	KinVelMotor4 = KinVelAxisZ * 2000;
}
close

 

I expect that DT will move X,Y as default built-in kinematic and move Z by my declared logic.

 

But DT ck3e shows Z axis only:

&1p

Z0

 

Axes X and Y are invisible.

Is possible to use default kinematic together with custom kinematic in one CS?

 

If I add logic for X and Y into inverse() and forward() than all works fine

&1p

X0 Y0 Z0

 

Roman

Link to comment
Share on other sites

  • Replies 9
  • Created
  • Last Reply

Top Posters In This Topic

Unfortunately, for a given coordinate system, either all axes need to use kinematics or none of them can; they can't be mixed. That said, the "solution" is to point their Axis Definitions to I, then add

 

KinPosAxisX = KinPosMotor1

KinPosAxisY = KinPosMotor2

 

to your forward kinematics and then

 

KinPosMotor1 = KinPosAxisX

KinPosMotor2 = KinPosAxisY

 

to your inverse (and similarly set KinVelMotorn and KinAxisUsed to reflect all motors). Because the basis of a coordinate system--and kinematics itself--is that the motors are all "intermingled" and working together, PMAC wants to just look in one spot for all relevant motors.

Link to comment
Share on other sites

Alex, thank you for quick reply.

 

I understand, and You confirm, that I need to map all used in CS motors to axes and vice verse.

But problem that in our solution CS configuration can be changed at any time over SSH commands.

 

And I need to detect actual CS configuration in inverse() and forward() code at runtime.

 

I try following code:

 

LOCAL mot;
local ax;
LOCAL ratio;
mot = 1;
while(mot <= Sys.MaxMotors)
{
	ax = 0;
	do
	{
		ratio = Motor[mot].CoordSf[ax];
		ax++;
	}while(ax <33 && ratio != 0);

	if(ratio != 0)
	{
		KinPosAxis(ax) = KinPosMotor(mot) / ratio;
	}
	mot++;
}

 

But the compiler shows the following error for line:

ratio = Motor[mot].CoordSf[ax];
...\Forward1.kin(23,1) : Error : ( error #31)  invalid data :   L322 = Motor[L320].CoordSf[L321]

 

It seems like compiler does not like AX variable and it wants a constant value in index of CoordSf[...]

How can I use variable in index of CoordSf[...] ?

 

Sorry if this issue too easy - I'm newbie in DT ck3e.

Thank you

 

Roman

Link to comment
Share on other sites

I'd like to actually ask a different question--why does your system need to support changing coordinate system configuration via SSH? If it's a matter of stretching/rotating and adjusting the scale factor for an axis, transformation matrices are the recommended way of implementing that. Typically, we do not really recommend varying coordinate system definitions "on the fly".
Link to comment
Share on other sites

Hello Alex

Maybe "on fly" is not the correct word.

but our equipment allows to have different configurations of manipulator axes. Some time it is XY only, some time customer adds rotation and angle axes XYZAC.

All servo drivers are EtherCAT. If they are detached physically, Ether CAT shows error.

Our desktop app starts and initializes ck3e with necessary actual axes to motor params.

Also, we need to set necessary ratios that can differ in differ configuration of hardware.

Therefore, when app starts, it sends:

&1
#1->123.33X
#2->33.21Y
...

... and so on for other manipulator config and start

 

(to change that parameters every time over ck3e firmaware from PowerPMAC IDE is not suitable for customer)

 

And if app sets ratios over that commands, kinematic routines code needs to know current values of ratios for correct mapping axes to motors at runtime.

 

So, I understand that access to CoordSf[...] values over variable index is not possible?

 

Roman

Link to comment
Share on other sites

A few different things:

 

1) From the "kinematics" you listed, you don't actually need kinematics. You could just do:

 

&1

#1->X

#2->Y

#3->2000Z

#4->2000Z - 2000

 

2) I am not certain, but the "p" command might have only been returning the position for Z because you had set "KinAxisUsed = KinEnaAxisZ". Had you set "KinAxisUsed = $1C0", it might have returned X, Y, and Z.

 

3) Similar to #2...you technically can use both axis definition statements and kinematics, but you will still need to include all axes in the forward kinematic buffer. Because you still need to put it there, we strongly recommend either using all axes in the kinematic buffers or none just to keep it straight forward.

 

4) To your actual question, where are you running that code? In the terminal window, for instance, I could set or query Motor[x].CoordSf with local variables for both x and i, which makes me think there is something else going on. From the syntax, I am assuming that is some sort of C code, though I am not sure where exactly you are running it.

1746823486_CoordSfwithVariables.png.7f8890132f3f7fc608544ed107b0fcbb.png

Link to comment
Share on other sites

Alex, thank you for detailed reply.

 

Let me a bit explain:

1) I show Z kinematic code as sample only. In real case it will be 2 or 3DOF arm. Therefore, I need to use the *.kin scripts.

2) Yes, I know about a bit mask for used axes. In real code, I use:

...
KinAxisUsed = KinEnaAxisZ + KinEnaAxisX + KinEnaAxisY;
...

 

3) Hmmm ... I will think and check ...

 

4) I try to implement forward1.kin script from PMAC Script Language\Kinematic Routines\Forward1.kin

Please note that it is the short sample only. In real code, the MOT and AX variables are indexes in loops.

I show this sample only to show compiler error for you.

 

open forward (1)      // Put Coordinate System number inside "(cs)"
LOCAL mot;
local ax;
LOCAL ratio;
ax = 1;
mot = 1;
ratio = Motor[mot].CoordSf[ax];
close

 

I click Download All Programs and see the following error:

 

...
Total Project download time = 3.344 seconds.
Total Project build and download time = 3.344 seconds.
There were errors during the download process and the download process has stopped.
The following errors were found:
   1 Error(s)

C:\job\.....\PMAC Script Language\Kinematic Routines\Forward1.kin(18,1) : Error : ( error #31)  invalid data :   L322 = Motor[L320].CoordSf[L321]

 

Maybe I need to somehow change the local declaration of AX variable?

 

version of PPMAC v4.5.1.3

 

Roman

Link to comment
Share on other sites

Just so that it doesn't look like we're ignoring this, I'm still trying to figure it out. It looks like the problem is specifically having a variable index for CoordSf, though it was allowed in the terminal. I'm consulting with our firmware team to try to understand why it's blocked.

 

...that said, though, if you are using kinematics, I wouldn't generally recommend using Motor[x].CoordSf. It's really intended as a read-only parameter being set by standard/linear axis definitions, which aren't recommended to be used with kinematics anyways. I was initially going to suggest you define all axes with correlations to all motors, then use an axis transformation to "clear" the motor and axis interactions that are not being used (plus appropriately scale the axes being used), but this wouldn't really work for kinematics.

 

Are there set "configurations"--customers will either have , , , etc.? If so, then the easiest way to do this may just be to implement all of them and use a SWITCH statement in the kinematics--now the user would just toggle potentially a single variable via ssh, and then when they go to run their motion program, it will utilize whatever configuration is indicated by the correct case. This could even be done piecewise, so the "base" kinematics are always used, and then use a SWITCH based on options the end user might have to implement kinematics for those, too.

Link to comment
Share on other sites

I do still believe that a different method may be better, but for now, if you use an L Variable directly, you should be able to loop across Motor[x].CoordSf.

 

Internally, LOCAL declarations associate the names you create with a pre-existing "L Variable"--that's why in the error message, it says L322 instead of "ratio", L320 instead of "mot", and L321 instead of "ax". If you replace "ax" specifically with "L150", it should work.

 

You can use other L Variable numbers if you prefer. The key seems to be it must be less than 223.

 

It is not ideal, but similarly, you likely could even write "#define ax L150" instead of "local ax", and then you could use "ax" exactly as you intend successfully. If you do this, I would not include the semicolon on the end of the line; #define is a direct string replacement, so if you say "#define ax L150;" that may replace every instance of "ax" with "L150;", thereby breaking many other lines.

Link to comment
Share on other sites

Hello Alex

 

It seems I resolved the issue.

I moved "error" code into *.plc script.

And same code works perfect in PLC script.

PLC code reads and copies the necessary axes ratios into GLOBAL arrays.

After that, I can access to that GLOBAL arrays in kinematic scripts *.kin

 

It is strange that compiler logic is different for *.plc and *.kin files.

 

Thank you.

 

Roman

Link to comment
Share on other sites

Guest
This topic is now closed to further replies.

×
×
  • Create New...