Jump to content
OMRON Forums

User-written servo questions


steveneads

Recommended Posts

For a user-servo, the manual states:

 

"Power PMAC automatically computes the values of several commonly used quantities before

calling a user-written servo algorithm each cycle.

The following automatically computed elements are of particular use. All are “double” format

floating-point values.

Motor[x].DesPos Net desired position (trajectory, master, compensation)

Motor[x].DesVel Net desired velocity (DesPosnew – DesPosold)

Motor[x].ActPos Outer loop net actual position (measured, compensation, backlash)

Motor[x].ActPos2 Inner loop net actual position (measured, compensation)

Motor[x].PosError Following error (DesPos – ActPos)

Motor[x].ActVel Inner loop net actual velocity (ActPos2new – ActPos2old)"

 

When in the schedule of real-time tasks that happen relating to the servo do these values get calculated? I presume that it is just before that particular user-servo is called (ie after the previous motor's PID calculations are complete) - is this correct? I presume that it would also be after a compensation table is calculated, if this precedes this loop?

 

On a related matter, is it possible to have a user-servo that pre-processes some data for compensation or feedback purposes and then calls one of the standard servo PIDs? If so, would these automatic values be calculated incorrectly for the called PID? If this is a sensible strategy - is there any example code available?

 

Thanks.

Link to comment
Share on other sites

  • Replies 8
  • Created
  • Last Reply

Top Posters In This Topic

In each servo interrupt, the actions occur in the following order:

 

1. Encoder conversion table pre-processing of feedback and master data

 

2. Update raw actual positions (Motor[x].Pos, Pos2) for all active motors, from lowest to highest numbered. For each:

a. Read encoder conversion table results

b. Update buffers for filtered velocity calculations

 

3. Trajectory update for all active motors, from lowest to highest numbered. For each:

a. Master position following

b. Commanded move trajectory

c. Combine these into Motor[x].DesPos

 

4. Cam table and compensation table* updates for all active tables

 

5. Servo loop update for each active motor, from lowest to highest numbered. For each:

a. Add in cam, compensation, and backlash position corrections

b. Compute intermediate values as you refer to above

c. Call selected (built-in or custom) servo algorithm

d. Offset and clamp servo output as needed (CompDac, DacLimit, DacBias)

 

As to your second question, while I suppose it is theoretically possible to have your custom algorithm that was called in Step 5c (above) call a built-in algorithm, I don't believe this has been done before, and I can think of all sorts of ways this kind of recursion could blow up - let's just say that nothing was done to facilitate this in the design of the software...

 

What several users have done is to write a custom servo for Motor 0 that computes either modifications to the input (e.g. CompDesPos) or the output (e.g. CompDac) of one or more "real" servo algorithms. This is one of the reasons we do not by default assign real motors to Motor 0. A few users have also (or instead) activated a higher numbered motor to take the output of one or more standard servo algorithms and post-process the results.

 

*Can be delayed with non-zero value for Sys.CompMotor

Link to comment
Share on other sites

Hi Curt

 

I'm trying to understand the timing when adopting the strategy in one of your previous suggestions to me, namely, that it's possible to write a user servo to "poke" values into unused encoder conversion table entries to be used by subsequent higher numbered servos, or into the compensation registers of higher numbered servos themselves.

 

I have read in another thread a comment from you stating "Each servo cycle, Power PMAC computes these terms [PosError, ActVel etc] for all motors before it executes the servo loop for any motor." If this is the case, then presumably these terms will have been calculated before the user servo has written to its target registers and therefore there will be a 1 cycle delay before the new value is used. Is this right, or am I missing something? If there is a 1 cycle delay - then it seems to me that the numbering of the servos becomes irrelevant. This is rather at odds with your description of step 5 above - which suggests to me that the values are calculated for each loop in turn just before the loop calculations for that loop. Hence my confusion! Can you please clarify this?

 

Regarding suitable code for poking numbers into the encoder conversions table, this is what I've been doing...

 

//method to write directly to "unused" encoder conversion table entry[50]

lastAccel = pshm->EncTable[50].PrevEnc; //read current position

accelDiff = accel - lastAccel; //calculate new change in position ("accel" is my new value)

pshm->EncTable[50].DeltaPos = accelDiff; //write back to table

pshm->EncTable[50].PrevEnc = accel;

 

Is this what you would expect to do? (it seems to work).

 

Thanks

Steve

Link to comment
Share on other sites

What I have written immediately above is correct - I was going through the code as I wrote it. But for your purposes, I believe the difference between that and what I wrote before is not important, because all motors read the encoder table for raw position before any servo loops are closed.

 

If you were to use a user servo for Motor 0 for your custom processing, there would not be a servo cycle delay if you wrote the results to the target motor's compensation registers (CompPos, CompPos2, CompDac). However, there would be a cycle delay if you wrote to a conversion table entry.

 

Assuming you want to use input data newly available on the interrupt, you may want to do this in a user phase algorithm (probably for Motor 0) which executes immediately after the interrupt and before any servo calculations. In this case, if you set your servo clock equal to your phase clock, nothing new needs to be done. However, if your servo clock is divided down from your phase clock, you will only want to execute this on the servo clock.

 

To do this, your phase routine needs to read the level of the servo clock signal to see if it is low. The following code is necessary:

 

/***********************/

 

unsigned *pgio; = NULL;

 

# define GPIO_ADDR 0x4EF600B00llu

 

(MyPhase)

{

if(pgio == NULL) // So API function only called once

pgio = (unsigned *) ioremap_nocache(GPIO_ADDR , GPIO_LEN);

 

IntPins = *(pgio + 7);

 

if ((IntPins & 4) == 0)

{

// Tasks done on servo interrupt here

}

}

 

/***********************/

 

If you want to be able to support the new "465" CPU that is coming out soon as well, the single assignment statement for IntPins above is replaced by:

 

if (pshm->CPUType == CPU_APM86xxx)

IntPins = *((unsigned char *) piom + 3);

else

IntPins = *(pgio + 7);

 

Yes, I do think your method for poking into a conversion table entry is correct logically. Of course, PrevEnc is a signed 32-bit integer, and DeltaPos is a 64-bit floating-point value. (I suspect you must know this already, or it wouldn't be working for you. I wanted to make sure that others understood.)

Link to comment
Share on other sites

Thanks for this suggestion. It seems like a good idea to do the feedback pre-processing in the phase so that it's done before the encoder conversion table runs to avoid the 1 cycle delay.

 

I've had a go at implementing your suggested code to see how it works, but have failed to compile it successfully. The main issue has been the following error:

 

"C:\PowerPMAC Projects\PowerPmacExamples\PowerPmac1\C Language\Realtime Routines\\usrcode.c(45,0): Error : 'ioremap_nocache' was not declared in this scope"

 

I've spent some time trying to work out what to include to solve this - but have failed. Some more help is needed!

Link to comment
Share on other sites

Here's what is needed to do this:

 

/*****************************************/

#include "usrcode.h"

#include "../Include/pp_proj.h"

#ifdef __KERNEL__

#include

#include

#endif

extern struct SHM *pshm; // Pointer to shared memory

extern volatile unsigned *piom; // Pointer to I/O memory

extern void *pushm; // Pointer to user memory

unsigned *pgio = NULL; // global pointer so retained

 

void user_phase(struct MotorData *Mptr)

{

#ifdef __KERNEL__

if(pgio == NULL) // Not already assigned?

pgio = (unsigned *)ioremap_nocache(GPIO_ADDR,GPIO_LEN);

#endif

IntPins = *(pgio + 7);

 

if ((IntPins & 4) == 0) // This phase cycle also a servo cycle?

{

// Code to be executed once per servo cycle

}

}

/********************************************/

Link to comment
Share on other sites

On further reflection, it is probably going to be simpler if you do not try to access the hardware directly. I would suggest the following algorithm:

 

/****************************/

if (pshm->ServoCount == LastServoCount)

{

PauseCount++;

if (PauseCount == PhaseCycPerServoCyc)

{

// Do once-per-servo processing here

}

else // Servo count incremented after last scan

{

LastServoCount = pshm->ServoCount;

PauseCount = 1;

}

 

/************************************/

 

The user variables must be global so their values are retained from cycle to cycle.

 

PhaseCycPerServoCyc is constant for a given application (=4 in the default setup)

 

It is possible to rewrite this for slightly greater efficiency at the cost of clarity.

Link to comment
Share on other sites

  • 3 weeks later...

Hi Curt

I've been on other projects for the last couple of weeks - so I haven't had a chance to try your suggestion until today. I'm pretty sure that I got something like your suggestion working by using a flag set by user servo code to indicate when it has run, so that the next phase cycle pre-processing calculations can be run at the right time before the next servo cycle processing. I recorded the system time in the phase calculations and checked it again in the servo calculations and the result was around 1e-5 secs, so I believe that all calculations were therefore being done within the same servo-cycle.

Thanks for your help.

Steve

Link to comment
Share on other sites

Guest
This topic is now closed to further replies.

×
×
  • Create New...