Difference between revisions of "AXY:Element Coordination/One Dimensional Tracking Algorithm"
(→State: Full Synchronization follow the master) |
|||
(40 intermediate revisions by 2 users not shown) | |||
Line 13: | Line 13: | ||
* Check if master velocity or acceleration exceeds max master frame's values if yes return an error | * Check if master velocity or acceleration exceeds max master frame's values if yes return an error | ||
− | * ''track ← master'' | + | * '''track ← master''' ''copying all derivatives'' |
* ''reset:'' '''flopstime = flops = 0''' | * ''reset:'' '''flopstime = flops = 0''' | ||
Line 21: | Line 21: | ||
<table style="float:right" border = "1"> | <table style="float:right" border = "1"> | ||
<tr><td> | <tr><td> | ||
− | Scaled value of [[ | + | Scaled value of [[MC-Basic:movingFrame.ACCELERATIONMAXTRAN|AccMaxTran]] (or [[MC-Basic:movingFrame.ACCELERATIONMAXROT|AccMaxRot]]) is used of checking of acceleration limit. |
</td></tr> | </td></tr> | ||
<tr><td> | <tr><td> | ||
− | Scaled value of [[ | + | Scaled value of [[MC-Basic:movingFrame.VELOCITYMAXTRANS|VelMaxTran]] (or [[MC-Basic:movingFrame.VELOCITYMAXROT|VelMaxRot]]) is used of checking of velocity limit. |
</td></tr> | </td></tr> | ||
</table> | </table> | ||
Line 38: | Line 38: | ||
<table style="float:right" border = "1"> | <table style="float:right" border = "1"> | ||
<tr><td> | <tr><td> | ||
− | <math>{sync_{jrk}}</math> defined as a scaled value [[ | + | <math>{sync_{jrk}}</math> defined as a scaled value [[MC-Basic:robot.JERKSYNCTRAN|SyncJerkTran]] or [[MC-Basic:robot.JERKSYNCROT|SyncJerkRot]] |
</td></tr> | </td></tr> | ||
<tr><td> | <tr><td> | ||
− | <math>{sync_{acc}}</math> defined as a scaled value [[ | + | <math>{sync_{acc}}</math> defined as a scaled value [[MC-Basic:robot.ACCELERATIONSYNCTRAN|SyncAcclerationTran]] or [[MC-Basic:robot.ACCELERATIONSYNCROT|SyncAcclerationRot]] |
</td></tr> | </td></tr> | ||
</table> | </table> | ||
Line 51: | Line 51: | ||
to get from that (higher) velocity to conveyers - therefore the multiplication by 2''<br> | to get from that (higher) velocity to conveyers - therefore the multiplication by 2''<br> | ||
+ | <br> | ||
<math>time_{toreach} = \sqrt{\frac {K*|{vel_{diff}}|} {sync_{jrk}} } + \sqrt{\frac{4*|{pos_{diff}}|}{sync_{acc}}}</math><br> | <math>time_{toreach} = \sqrt{\frac {K*|{vel_{diff}}|} {sync_{jrk}} } + \sqrt{\frac{4*|{pos_{diff}}|}{sync_{acc}}}</math><br> | ||
+ | <br> | ||
+ | |||
+ | ''where'' <math> K = \begin{cases} 4, & \mbox{if }vel_{diff} > 0 \\2, & \mbox{if }vel_{diff} \le 0 \end{cases}</math> <br> | ||
− | |||
<table style="float:right" border = "1"> | <table style="float:right" border = "1"> | ||
<tr><td> | <tr><td> | ||
− | DampingFactor - user defined by: [[ | + | DampingFactor - user defined by: [[MC-Basic:movingFrame.DAMPINGFACTOR|MF.DAMPINGFACTOR]] |
</td></tr> | </td></tr> | ||
</table> | </table> | ||
− | '' | + | ''Additionally we multiply by a prediction factor - to decrease acc/jerk<br> |
(rounding to integer number of samples):'' | (rounding to integer number of samples):'' | ||
Line 71: | Line 74: | ||
=== Prediction of the Rendezvous-Point === | === Prediction of the Rendezvous-Point === | ||
''The predicted position of the rendezvous (minus T, if it will happen in this sample!)''<br> | ''The predicted position of the rendezvous (minus T, if it will happen in this sample!)''<br> | ||
− | + | <math>pred_{pos}</math>: ''position prediction assuming constant acceleration''<br> | |
− | + | <math>pred_{diff}</math>: ''Predicted position difference''<br> | |
− | + | <math>pred_{vel}</math>: '' velocity prediction''<br> | |
− | < | + | |
− | t = ( | + | |
− | + | <math>t = (time_{toreach}-T)</math><br> | |
− | + | <math>pred_{pos} = master_{pos} + t*master_{vel} + t^2*master_{acc}/2</math><br> | |
− | + | <math>pred_{diff} = pred_{pos} - track_{pos}</math><br> | |
− | </ | + | <math>pred_{vel} = master_{vel} + t*master_{acc}</math><br> |
− | '' acceleration will be zero'' | + | |
− | < | + | |
− | + | ||
+ | '' Assuming the acceleration will be zero:''<br> | ||
+ | <math>pred_{acc} = 0</math><br> | ||
+ | |||
'' Polynomial coefficients of 5-degree polynom connecting the current p,v,a to the randevous p,v,a''<br> | '' Polynomial coefficients of 5-degree polynom connecting the current p,v,a to the randevous p,v,a''<br> | ||
Line 94: | Line 100: | ||
=== Next SamplePosition === | === Next SamplePosition === | ||
''The position at the next sample will be:''<br> | ''The position at the next sample will be:''<br> | ||
− | dp = | + | ''Initial increment (full displacement): ''<math>dp = a5*T^5 + a4*T^4 + a3*T^3 + 0.5*track_{acc}*T^2 + track_{vel}*T</math><br> |
+ | |||
+ | '' The accleration and jerk increments could be computed in this way also.''<br> | ||
+ | '' But they are computed as average values for the time of sample duration, this approach doeas fit more to ''<br> | ||
+ | '' the tools we are using to test this feature, as they all compute acceleration & jerk by numeric differentiation''<br> | ||
+ | '' inside one sample.''<br> | ||
+ | '' The side effect of all this is that we can have a change in jerk/acc sign inside one sample and the average value we are using ''<br> | ||
+ | '' ddp,dddp could have an opposite sign, so we are seeing effects like jerk or acceleration is limited from a "wrong side" i.e. instead''<br> | ||
+ | '' using jmax -jmax is used. There is not much we can do against it, using exact jerk/acc values (from polynom) returns than wrong average values ''<br> | ||
+ | '' we observe as jerk/acc exceed over theri max values. So the average value approach is not perfect but gives results within the given limits.''<br> | ||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | '' Initial setting of predicted time and the filter limit flag ( if the filter did work - this flag will be on)'' | + | '' Initial setting of predicted time and the filter limit flag (if the filter did work - this flag will be on)'' |
<pre> | <pre> | ||
− | |||
limit = false | limit = false | ||
state.satVel = false | state.satVel = false | ||
Line 122: | Line 124: | ||
<table style="float:right" border = "1"> | <table style="float:right" border = "1"> | ||
<tr><td> | <tr><td> | ||
− | sync_vel defined as a scaled value [[ | + | sync_vel defined as a scaled value [[MC-Basic:robot.VELOCITYSYNCTRAN|VelSyncTran]] or [[MC-Basic:robot.VELOCITYSYNCROT|VelSyncRot]] |
</td></tr> | </td></tr> | ||
<tr><td> | <tr><td> | ||
− | sync_acc defined as a scaled value [[ | + | sync_acc defined as a scaled value [[MC-Basic:robot.ACCELERATIONSYNCTRAN|AccSyncTran]] or [[MC-Basic:robot.ACCELERATIONSYNCROT|AccSyncRot]] |
</td></tr> | </td></tr> | ||
<tr><td> | <tr><td> | ||
− | sync_jrk defined as a scaled value [[ | + | sync_jrk defined as a scaled value [[MC-Basic:robot.JERKSYNCTRAN|JrkSyncTran]] or [[MC-Basic:robot.JERKSYNCROT|JrkSyncRot]] |
</td></tr> | </td></tr> | ||
<tr><td> | <tr><td> | ||
Line 136: | Line 138: | ||
</table> | </table> | ||
− | + | ||
− | < | + | <math> dp = \begin{cases} sync_{velT} , & \mbox{if } dp > sync_{velT} \\ limit = true \\ -sync_{velT}, & \mbox{if }dp < -sync_{velT} \\ limit = true\end{cases}</math> |
− | dp = | ||
− | limit | ||
− | |||
− | |||
− | |||
− | |||
− | limit | ||
− | </ | ||
==== Setting Initial velocity delta==== | ==== Setting Initial velocity delta==== | ||
− | ddp = dp - | + | <math>ddp = dp - dp_0</math> <br> |
− | + | ||
− | < | + | <math> ddp = \begin{cases} sync_{accT2} , & \mbox{if } ddp > sync_{accT2} \\ dp = sync_{accT2} + dp_0 \\limit = true \\ -sync_{accT2}, |
− | + | & \mbox{if }ddp < -sync_{accT2} \\dp = -sync_{accT2} + dp_0 \\ limit = true\end{cases}</math> | |
− | ddp = | ||
− | limit | ||
− | |||
− | |||
− | |||
− | dp | ||
− | |||
− | limit | ||
− | </ | ||
==== Setting Initial acceleration delta==== | ==== Setting Initial acceleration delta==== | ||
− | dddp = ddp - | + | <math>dddp = ddp - ddp_0</math><br> |
+ | |||
+ | |||
− | if | + | <math> dddp = \begin{cases} sync_{jrkT3} , & \mbox{if } dddp > sync_{jrkT3} \\ ddp = sync_{jrkT3} + ddp_0 \\dp = ddp + dp_{0}\\limit = true \\ -sync_{jrkT3}, |
− | + | & \mbox{if }dddp < -sync_{jrkT3} \\ddp = -sync_{jrkT3} + ddp_0 \\dp = ddp + dp_{0} \\ limit = true\end{cases}</math> | |
− | ddp = | ||
− | dp = ddp + | ||
− | limit | ||
− | |||
− | |||
− | |||
− | ddp = - | ||
− | dp = ddp + | ||
− | limit | ||
− | </ | ||
==== New position is: ==== | ==== New position is: ==== | ||
− | + | <math>track_{pos} = track_{pos} + dp</math> | |
==== If the filter was activated then: ==== | ==== If the filter was activated then: ==== | ||
− | '' if the velocity,accleration or jerk is limited then the velocity computed using polynomials does'' | + | '' if the velocity,accleration or jerk is limited ('''limit = true''') then the velocity computed using polynomials does''<br> |
− | + | <math> track_{vel} = dp/T </math><br> | |
− | + | <math> track_{acc} = ddp/T^2</math><br> | |
− | < | + | |
− | + | <br> | |
− | |||
− | < | ||
− | |||
'' Velocity & Accleration will be computed exactly not using dp and ddp, it has been shown that this'' | '' Velocity & Accleration will be computed exactly not using dp and ddp, it has been shown that this'' | ||
− | '' approach is much better - means more stable'' | + | '' approach is much better - means more stable''<br> |
− | < | + | |
− | + | <math> track_{vel} = 5*a5*T^4 + 4*a4)*T^3 + 3*a3*T^2 + track_{acc}*T + track_{vel}</math><br> | |
− | + | <math> track_{acc} = 20*a5*T^3 + 12*a4*T^2 + 6*a3*T + track_{acc}</math><br> | |
− | </ | ||
====keep the old values for next sample==== | ====keep the old values for next sample==== | ||
+ | <pre> | ||
ddp0 = ddp; | ddp0 = ddp; | ||
dp0 = dp; | dp0 = dp; | ||
+ | </pre> | ||
====System is synchronized if NEW delta's are under certesian thresholds:==== | ====System is synchronized if NEW delta's are under certesian thresholds:==== | ||
− | + | <math>dv_0 = dv</math>; - ''keep the previous dv''<br> | |
− | dv = | + | <math>dv = master_{vel} - track_{vel}</math><br> |
+ | |||
+ | |||
+ | <table style="float:right" border = "1"> | ||
+ | <tr><td> | ||
+ | syncGain defined by the user with: [[MC-Basic:movingFrame.FILTERFACTOR|MF.FilterFactor]] | ||
+ | </td></tr> | ||
+ | </table> | ||
+ | |||
+ | |||
+ | |||
+ | ===== Successful tracking completion ===== | ||
− | + | '''<u>if((fabs(dv) <= syncGain * sync_accT) && (fabs(master_pos - track_pos) <= syncGain * sync_accT2))</u> ''' <br> | |
− | if((fabs(dv) <= syncGain * sync_accT) && (fabs(master_pos - track_pos) <= syncGain * sync_accT2)) | + | '' Synchronization'' <br> |
'' Take the middle for an additional smoothing:'' | '' Take the middle for an additional smoothing:'' | ||
<pre> | <pre> | ||
Line 213: | Line 199: | ||
track_vel = 0.5*(track_vel + master_vel); | track_vel = 0.5*(track_vel + master_vel); | ||
ResetFilter(); // Reset the filter | ResetFilter(); // Reset the filter | ||
+ | state.tracking = MOT_MASTER_SYNC; // System synchronized<br> | ||
</pre> | </pre> | ||
− | ''' | + | '''else if( dv0*dv < 0)'''<br> |
− | else if( dv0*dv < 0) | ||
'' Check against over-oscillation ''<br> | '' Check against over-oscillation ''<br> | ||
<pre> | <pre> | ||
Line 223: | Line 209: | ||
</pre> | </pre> | ||
− | ==== Over-Oscillation Check ==== | + | ===== Over-Oscillation Check ===== |
<table style="float:right" border = "1"> | <table style="float:right" border = "1"> | ||
<tr><td> | <tr><td> | ||
− | maxFlops defined by the user with: [[ | + | maxFlops defined by the user with: [[MC-Basic:movingFrame.MAXFLOPS|MF.MaxFlops]] |
</td></tr> | </td></tr> | ||
</table> | </table> | ||
− | if (flops > maxFlops && (flopstime > maxFlopsTime && fabs(dv) > syncGain * sync_accT2))<br> | + | '''<u>if (flops > maxFlops && (flopstime > maxFlopsTime && fabs(dv) > syncGain * sync_accT2))</u>'''<br> |
<pre> | <pre> | ||
state.tracking = MOT_MASTER_OSC; // OScilationss | state.tracking = MOT_MASTER_OSC; // OScilationss | ||
</pre> | </pre> | ||
− | else | + | '''else''' |
<pre> | <pre> | ||
flopstime++; | flopstime++; | ||
Line 255: | Line 241: | ||
− | [[Category | + | [[Category:Motion:MovingFrame]] |
Latest revision as of 09:18, 22 May 2014
Contents
- 1 One Dimensional Tracking Algorithm
- 1.1 State: Full Synchronization follow the master
- 1.2 State: Tracking process
- 1.2.1 Initial Setup and testing
- 1.2.2 Time-to-Reach initial estimation
- 1.2.3 Prediction of the Rendezvous-Point
- 1.2.4 Next SamplePosition
- 1.2.5 Velocity, Acceleration and Jerk Filter
- 1.3 State: Stopping (de-synchronization process)
One Dimensional Tracking Algorithm
This algorithm is used always in simple axis based MF tracking:
The algorithm consist of a state machine with the following states:
- Tracking process
- Full Synchronization follow the master
- Stopping (de-synchronization process)
State: Full Synchronization follow the master
- Check if master velocity or acceleration exceeds max master frame's values if yes return an error
- track ← master copying all derivatives
- reset: flopstime = flops = 0
State: Tracking process
Initial Setup and testing
Scaled value of AccMaxTran (or AccMaxRot) is used of checking of acceleration limit. |
Scaled value of VelMaxTran (or VelMaxRot) is used of checking of velocity limit. |
- Check if master velocity or acceleration exceeds max master frame's values if yes return an error
- Compute differences:
pure delta-position
pure delta-velocity
Time-to-Reach initial estimation
defined as a scaled value SyncJerkTran or SyncJerkRot |
defined as a scaled value SyncAcclerationTran or SyncAcclerationRot |
This is an estimation of time needed to reach the target. It is not an exact formula
if the velocity difference is positive, it means the robot velocity is lower then conveyors
therefore we need more time once to get to a higher velocity then the conveyers and once
to get from that (higher) velocity to conveyers - therefore the multiplication by 2
where
DampingFactor - user defined by: MF.DAMPINGFACTOR |
Additionally we multiply by a prediction factor - to decrease acc/jerk
(rounding to integer number of samples):
time_to_reach *= DampingFactor time_to_reach = T*int(time_to_reach/T+1)
Prediction of the Rendezvous-Point
The predicted position of the rendezvous (minus T, if it will happen in this sample!)
: position prediction assuming constant acceleration
: Predicted position difference
: velocity prediction
Assuming the acceleration will be zero:
Polynomial coefficients of 5-degree polynom connecting the current p,v,a to the randevous p,v,a
- not used, directly written into code
- not used, directly written into code
- not used, directly written into code
Next SamplePosition
The position at the next sample will be:
Initial increment (full displacement):
The accleration and jerk increments could be computed in this way also.
But they are computed as average values for the time of sample duration, this approach doeas fit more to
the tools we are using to test this feature, as they all compute acceleration & jerk by numeric differentiation
inside one sample.
The side effect of all this is that we can have a change in jerk/acc sign inside one sample and the average value we are using
ddp,dddp could have an opposite sign, so we are seeing effects like jerk or acceleration is limited from a "wrong side" i.e. instead
using jmax -jmax is used. There is not much we can do against it, using exact jerk/acc values (from polynom) returns than wrong average values
we observe as jerk/acc exceed over theri max values. So the average value approach is not perfect but gives results within the given limits.
Initial setting of predicted time and the filter limit flag (if the filter did work - this flag will be on)
limit = false state.satVel = false state.satAcc = false state.satJrk = false
Velocity, Acceleration and Jerk Filter
sync_vel defined as a scaled value VelSyncTran or VelSyncRot |
sync_acc defined as a scaled value AccSyncTran or AccSyncRot |
sync_jrk defined as a scaled value JrkSyncTran or JrkSyncRot |
T is sampling time |
Setting Initial velocity delta
Setting Initial acceleration delta
New position is:
If the filter was activated then:
if the velocity,accleration or jerk is limited (limit = true) then the velocity computed using polynomials does
Velocity & Accleration will be computed exactly not using dp and ddp, it has been shown that this
approach is much better - means more stable
keep the old values for next sample
ddp0 = ddp; dp0 = dp;
System is synchronized if NEW delta's are under certesian thresholds:
; - keep the previous dv
syncGain defined by the user with: MF.FilterFactor |
Successful tracking completion
if((fabs(dv) <= syncGain * sync_accT) && (fabs(master_pos - track_pos) <= syncGain * sync_accT2))
Synchronization
Take the middle for an additional smoothing:
track_pos = 0.5*(track_pos + master_pos); track_vel = 0.5*(track_vel + master_vel); ResetFilter(); // Reset the filter state.tracking = MOT_MASTER_SYNC; // System synchronized<br>
else if( dv0*dv < 0)
Check against over-oscillation
if (flops == -1) flops = 0; // ignore the first sample else flops++; flopstime = 0;
Over-Oscillation Check
maxFlops defined by the user with: MF.MaxFlops |
if (flops > maxFlops && (flopstime > maxFlopsTime && fabs(dv) > syncGain * sync_accT2))
state.tracking = MOT_MASTER_OSC; // OScilationss
else
flopstime++;
State: Stopping (de-synchronization process)
flopstime = flops = 0;
- De-Syncing profile, follow the given profile, ignore the real source
desync.Profile(); track_pos = track_pos_0+master_direction*desync.path.curr_pos; track_vel = master_direction*desync.path.vel; track_acc = master_direction*desync.path.acc; if(desync.path.Status.stop) // if stopped,change the state to OFF SetState(MOT_MASTER_OFF);