Jump to content
OMRON Forums

r,theta machine tool kinematics


kmonroe023

Recommended Posts

I've been working on developing kinematics for a machine tool that utilizes r,theta tooling. Tool tip coordinates are in x,y and I need to convert those to r (radius) and theta values, which is pretty simple, its just rectangular to polar conversion. That seems to work well, where I'm running into problems is with the rollover. I've got the rollover working in the positive direction but I'm struggling with negative rollover values.

 

I know I'm missing something simple, and I'm wondering if you guys have some equations I could look at. I know you handle it the Pmac for axis defined as rotary axis so I'm assuming you have some algorithms to cleanly handle rollover.

 

Thanks,

Kmonroe

Link to comment
Share on other sites

  • Replies 14
  • Created
  • Last Reply

Top Posters In This Topic

Here's how I would handle it:

 

In the forward kinematics, establish both Theta within one cycle and which cycle you are in:

 

FullTheta = Motor2KinPos / MyMotor2ScaleFactor; // Could be outside 0 - 360 range

OldTheta = FullTheta % 360; // Location within 0 - 360 range, will be used by inv kin rollover

CycleTheta = FullTheta - OldTheta; // Multiple of 360, indicates cycle count

...

 

In the inverse kinematics, look for rollover by checking for angle change greater than +/-180

 

NewTheta = atan2d(AxisYKinPos, AxisXKinPos) + CycleTheta; // Tentative, wrong if there has been rollover

DeltaTheta = NewTheta - OldTheta; // Difference from last time (or from start)

if (DeltaTheta >= 180) { // Negative rollover?

NewTheta -= 360; // Correct for use this time

CycleTheta -= 360; // For use next time

}

if (DeltaTheta < -180) { // Positive rollover?

NewTheta += 360; // Correct for use this time

CycleTheta += 360; // For use next time

}

Motor2KinPos = NewTheta * MyMotor2ScaleFactor; // Use corrected result

OldTheta = NewTheta; // For use next time

...

 

I haven't had the time to test this, but I think it should work -- it shows the principle at any rate.

Link to comment
Share on other sites

I got a chance to test it today. I had to tweak the forward kinematics so it could start properly after it had rolled over. Here's the full routine:

 

global Motor1ScaleFactor = 1000.0;

global Motor1Offset = 0.0;

global Motor2ScaleFactor = 1000.0;

global Motor2Offset = 0.0;

 

csglobal OldTheta; // Saved for comparisons in next kinematics

csglobal CycleTheta; // Degrees of full cycles to handle rollover

csglobal FwdKinErr; // Flag to show failure

csglobal FullTheta;

 

open forward (1)

 

local Radius;

local Theta;

 

if (Coord[1].HomeComplete) {

if (KinVelEna) callsub 100; // Double pass for velocity-reporting use

KinAxisUsed = $C0; // Tell PMAC routine calculates X & Y positions

N100:

Radius = (KinPosMotor1 - Motor1Offset) / Motor1ScaleFactor;

FullTheta = (KinPosMotor2 - Motor2Offset) / Motor2ScaleFactor; // Could be outside +/-180 range

Theta = rem(FullTheta, 360); // Location within +/-180 range, will be used by inv kin rollover

CycleTheta = FullTheta - Theta; // Multiple of 360, indicates cycle count

KinPosAxisX = Radius * cosd(Theta);

KinPosAxisY = Radius * sind(Theta);

OldTheta = FullTheta;

FwdKinErr = 0;

}

else {

FwdKinErr = 1;

abort1;

}

close

 

Here's the full inverse kinematic routine:

 

undefine all

&1

#1->I

#2->I

 

csglobal MaxRadius = 250;

csglobal InvKinErr;

 

open inverse (1)

 

// Variables not needed outside of routine

local Radius; // Distance from center of rotation

local NewTheta; // Computed full angle including rollover

local DeltaTheta; // Change in computed angle since last kinematics call

 

Radius = sqrt(KinPosAxisX*KinPosAxisX + KinPosAxisY*KinPosAxisY);

if (Radius <= MaxRadius) {

NewTheta = atan2d(KinPosAxisY, KinPosAxisX) + CycleTheta; // Tentative, wrong if there has been rollover

DeltaTheta = NewTheta - OldTheta; // Difference from last time (or from start)

if (DeltaTheta >= 180) { // Negative rollover?

NewTheta -= 360; // Correct for use this time

CycleTheta -= 360; // For use next time

}

if (DeltaTheta < -180) { // Positive rollover?

NewTheta += 360; // Correct for use this time

CycleTheta += 360; // For use next time

}

KinPosMotor1 = Radius * Motor1ScaleFactor + Motor1Offset;

KinPosMotor2 = NewTheta * Motor2ScaleFactor + Motor2Offset; // Convert to motor units

OldTheta = NewTheta; // For use next time

InvKinErr = 0;

}

else {

InvKinErr = 1;

abort1;

}

Link to comment
Share on other sites

  • 3 years later...

Dear Sir,

 

I also doing same type of project .

I converted Cartesian to polar points but cant enable CCR its works for 0-180deg only above 180 prog stops/prog running bit goes to zero.

 

have you added this CCR mode in your project???

Let me know how to add this functionality ???

Link to comment
Share on other sites

To be clear -- to use cutter radius compensation, you must be programming in Cartesian coordinates.

 

If your mechanism is polar, you must use our kinematic subroutines to convert the offset Cartesian tool-tip trajectory to the polar actuators. This occurs at a later step in the processing.

Link to comment
Share on other sites

To be clear -- to use cutter radius compensation, you must be programming in Cartesian coordinates.

 

If your mechanism is polar, you must use our kinematic subroutines to convert the offset Cartesian tool-tip trajectory to the polar actuators. This occurs at a later step in the processing.

 

Means i have to add this cutter compensation value in term of counts in kinematics subroutine as a Motor1offset or Motor2offset value.

Link to comment
Share on other sites

No, that's not what I was trying to communicate. When you program the path in Cartesian coordinates (e.g. X & Y), and use cutter radius compensation, PMAC will automatically offset the Cartesian path properly by the radius and direction you specify.

 

Points on the already-offset path are then input to the inverse kinematic subroutine. The IK subroutine does NOT need to perform any offsetting, as this has already been done. It works the same way whether or not any offsets have been applied in Cartesian space.

Link to comment
Share on other sites

No, that's not what I was trying to communicate. When you program the path in Cartesian coordinates (e.g. X & Y), and use cutter radius compensation, PMAC will automatically offset the Cartesian path properly by the radius and direction you specify.

 

Points on the already-offset path are then input to the inverse kinematic subroutine. The IK subroutine does NOT need to perform any offsetting, as this has already been done. It works the same way whether or not any offsets have been applied in Cartesian space.

 

Thank you Sir,

 

I also did same thing , like taking care of CCR in (x,y)

 

But it update all points in 1st and 2nd quadrant coordinate file when CCR is on.

For example....

Step 1 : x 200 y 200 // (r=282.46 , theta =45)

Step 2: x -200 y 200 // (r=282.46 , theta =135)

Step 3: x -200 y -200 // (r=282.46 , theta =225)

Step 4: x 200 y -200 // (r=282.46 , theta =315)

 

If CCR is disable then it will update all the point and execute all program .

And when we put CCR it will execute upto step 2 as soon as step 3 starts it will immediately stop the program and give coord[1].Errorstatus=5.

Link to comment
Share on other sites

  • 1 year later...

Hi Curt

 

I have the same problem, i want to use 3d compensation. Can i use this with polar machine X C Z, or i have to use XYZ and kinematics ?.

 

I also do not know how to create a 3d tool model in disk format.

66mm diameter and 12 of corner Radius.

 

thank you

 

Paulo

 

The ErrorStatus value you report shows that you have an illegal "leadout" move (or don't have one at all) to end your cutter radius compensation sequence. Please contact our tech support group directly to learn how to do this properly.

453525029_3Dccomp2017-08-29_15-26-51.thumb.png.d7ca90db0b99be21289a458821ad6bce.png

Link to comment
Share on other sites

3D cutter radius compensation, as with 2D cutter radius compensation, must be programmed in XYZ Cartesian coordinates. If your mechanism does not have a 1-to-1 match of actuators to tool-tip coordinates, then you must use kinematic conversions.

 

You list a 33mm overall tool radius (66mm diameter) and a 12mm "corner radius". This does not correspond at all well with the drawings of your tool head. The "corner radius" looks much smaller with respect to the overall tool radius.

Link to comment
Share on other sites

Hi Curt

 

you are sure about this, i have tool diameter 66mm and 12mm is the insert diameter.

 

thank you

 

Paulo

 

3D cutter radius compensation, as with 2D cutter radius compensation, must be programmed in XYZ Cartesian coordinates. If your mechanism does not have a 1-to-1 match of actuators to tool-tip coordinates, then you must use kinematic conversions.

 

You list a 33mm overall tool radius (66mm diameter) and a 12mm "corner radius". This does not correspond at all well with the drawings of your tool head. The "corner radius" looks much smaller with respect to the overall tool radius.

Link to comment
Share on other sites

Looking at your drawing, the overall tool diameter is the distance along the line you have labeled XZ'. You describe this diameter as 66mm, so the tool radius from the axis of rotation to the outside of the tool is 33mm along this line.

 

The little circles (which I presume are the inserts) shown at the outside ends of this line have what our 3D compensation calls the cut radius. Using the same scaling that gives us 33mm tool radius, I measure on my screen a cut radius of only about 3 or 4mm. Of course, I am assuming your very nice drawing is accurately to scale.

Link to comment
Share on other sites

Guest
This topic is now closed to further replies.

×
×
  • Create New...