Motion control design pattern with Orocos

Hello,

I'm currently working on the implementation of Orocos in a motion
control system, whose motors are current-controlled. Thus, the
calculation of the real-time control laws will be made in Orocos. As I
know, the typical execution sequence is :

1. Read I/O
2. Calculate control law
3. Write I/O
4. Wait until next step

We would like to implement our device drivers with the Orocos Device
Interface to benefit from the IO Component. I see three solutions :

SOLUTION #1

The device interfaces are added to the IOComponent and then become
available as ports. The Controller component is connected to the IO
Component with these ports. However, the updateHook function of the
IOComponent does both read and write. So, the execution sequence would
be :

1. Read I/O
2. Write I/O
3. Calculate control law
4. Wait until next step

This solution is clean and required minor programming efforts.
However, this is not a good solution in the control point of vue,
because there will be a significant delay between the calculation and
the output of the result.

SOLUTION #2

We may have a MasterController component with the following updateHook :

1. Call the "custom" UpdateInputs() method of the IOComponent (Read I/O)
2. Call Controller.execute() (Calculate control law)
3. Call the "custom" UpdateOutputs()" method of the IOComponent (Write I/O)

This solution has two major advantages :
a) We still use the IOComponent, or a customized version of it;
b) The execution sequence is respected.

Although this solution addresses the major initial needs, it has some drawbacks:
a) The scripts of the MasterController will be executed before the Read I/O;
b) The MasterController updateHook will need to be customized each
time we add an axis/controller.

SOLUTION #3

This solution does not use the IOComponent. Each component (e.g. the
Controller) uses the Device Interface Naming Service to read/write
their specific I/O. Thus, the connections between components and I/O
are made in C++ code instead of ports inter-connections. In that way,
the Controller component may do something like this in his updateHook
:

1. Read Sensor via Naming Service (Read I/O)
2. Calculate control law
3. Write result to Drive via Naming Service (Write I/O)

However, this solution has drawbacks :
a) The connection of I/O via ports is better to me. It makes the
hardware/components inter-connections very clear.
b) If many components need the same I/O, the latter would be read many
times in the same "loop".

Currently, solution #2 seems the only way to completely solve the
problem. I'm looking for a better solution. So, anyone already faced
this problem with Orocos? Your suggestions/comments are very welcome!

Philippe

Motion control design pattern with Orocos

On Wednesday 11 February 2009 17:55:19 Philippe Hamelin wrote:
> Hello,
>
> I'm currently working on the implementation of Orocos in a motion
> control system, whose motors are current-controlled. Thus, the
> calculation of the real-time control laws will be made in Orocos. As I
> know, the typical execution sequence is :
>
> 1. Read I/O
> 2. Calculate control law
> 3. Write I/O
> 4. Wait until next step
>
> We would like to implement our device drivers with the Orocos Device
> Interface to benefit from the IO Component. I see three solutions :
>
> SOLUTION #1
>
> The device interfaces are added to the IOComponent and then become
> available as ports. The Controller component is connected to the IO
> Component with these ports. However, the updateHook function of the
> IOComponent does both read and write. So, the execution sequence would
> be :

What you clearly missed is the fact that you can have any number of
IOComponents. So just instantiate two, add 'read' drivers to one, and write
drivers to the other and you're set.

Speaking of patterns, we use (many) 'Adaptor' components in our applications
to get the data out or in. They are similar to IOComponents, but calling them
adaptor makes it for everyone clear what the component is supposed to do :
plug the data ports to real IO.
Reconfiguring the hardware (for example move from comedi to CAN) is then done
by only setting up a new adaptor.

Peter

motion control pattern

Hi Philippe,

Nice to read your analysis. I have been thinking about this as well.

Re SOLUTION 1:
This is what I use now, with a slight variation:
1 write
2 read
3 calculate
4 wait

This pattern indeed introduces some delay. However, the nice thing is that the delay is predictable and not time-varying. By choosing the period time short, we can simply minimize it, and then it is not much larger than worst case situations for SOLUTION 2.
It has been suggested (by Astrom and Wittenmark) that writing first has advantages, but I never really noticed it, so we might as well stick with reading first, then writing.

Re: SOLUTION 2
Ok, we need this if we do not want minimal period time. My conclusion has been that we could have a clean implementation of this by creating alternative ExecutionEngine behaviour. My idea is to replace the updateHook() call to the TaskContext by a sequence senseHook(), calculateHook(), actuateHook() or any other order, whatever you like. This could be done by introducing a userHookProcessor, as was discussed here: http://www.orocos.org/node/1050
I have not elaborated on this yet, but maybe together we can make something happen? What's your opinion on this?

Re: SOLUTION 3
Not my prefered way to go. I like sensor- and actuator info to be on ports, so that non-periodic tasks can access them without any worries.

Theo.

motion control pattern

On Thursday 12 February 2009 09:18:58 t [dot] j [dot] a [dot] devries [..] ... wrote:
> Hi Philippe,
>
> Nice to read your analysis. I have been thinking about this as well.
>
> Re SOLUTION 1:
> This is what I use now, with a slight variation:
> 1 write
> 2 read
> 3 calculate
> 4 wait
>
> This pattern indeed introduces some delay. However, the nice thing is that
> the delay is predictable and not time-varying. By choosing the period time
> short, we can simply minimize it, and then it is not much larger than worst
> case situations for SOLUTION 2. It has been suggested (by Astrom and
> Wittenmark) that writing first has advantages, but I never really noticed
> it, so we might as well stick with reading first, then writing.

Also this can be accomplished with two separate IO component instances.

>
> Re: SOLUTION 2
> Ok, we need this if we do not want minimal period time. My conclusion has
> been that we could have a clean implementation of this by creating
> alternative ExecutionEngine behaviour. My idea is to replace the
> updateHook() call to the TaskContext by a sequence senseHook(),
> calculateHook(), actuateHook() or any other order, whatever you like. This
> could be done by introducing a userHookProcessor, as was discussed here:
> http://www.orocos.org/node/1050 I have not elaborated on this yet, but
> maybe together we can make something happen? What's your opinion on this?

Not that if you want to do Simulink - like functionality, the sequence would
rather be:

senseHook() calculateHook(), updateHook(), actuateHook()

Where updating of the internal state space variables is done after the control
action is calculated.

Peter

motion control pattern

On Thu, 12 Feb 2009, t [dot] j [dot] a [dot] devries [..] ... wrote:

> Nice to read your analysis. I have been thinking about this as well.
>
> Re SOLUTION 1:
> This is what I use now, with a slight variation:
> 1 write
> 2 read
> 3 calculate
> 4 wait
>
> This pattern indeed introduces some delay. However, the nice thing is that the delay is predictable and not time-varying. By choosing the period time short, we can simply minimize it, and then it is not much larger than worst case situations for SOLUTION 2.
> It has been suggested (by Astrom and Wittenmark) that writing first has advantages, but I never really noticed it, so we might as well stick with reading first, then writing.

In a good control software implementation, the difference between both
policies should be irrelevant. I mean, if the sampling time is such that a
difference between both _is_ noticeable, that sampling time is too low! :-)

And writing first _seems_ to have the advantage that you apply your new
control setpoint closest to the optimal time, but one often forgets that
this new setpoint has been calculated an unspecified time ago :-)

> Re: SOLUTION 2
> Ok, we need this if we do not want minimal period time. My conclusion has
> been that we could have a clean implementation of this by creating
> alternative ExecutionEngine behaviour. My idea is to replace the
> updateHook() call to the TaskContext by a sequence senseHook(),
> calculateHook(), actuateHook() or any other order, whatever you like.
> This could be done by introducing a userHookProcessor, as was discussed
> here: http://www.orocos.org/node/1050

The TaskContext, as a _generic_ building block, should never get any stuff
that is specific to an particular application: your suggestion introduces
"periodic control policy" hooks into it, and that's not right :-)
What _is_ acceptable are application-specific implementations of
"updateHook()". But these will not be added into RTT, but into OCL.

> I have not elaborated on this yet, but maybe together we can make something happen? What's your opinion on this?
>
> Re: SOLUTION 3
> Not my prefered way to go. I like sensor- and actuator info to be on ports, so that non-periodic tasks can access them without any worries.

That's the _fundamental_ concern of component-based programming! :-)

Some possibly good news: our new contributor Markus agreed to give the OCL
part of Orocos some good refactoring attention, and to reduce it to the
bare minimum but with optimal documentation and motivation. (He will post
some comments "in the near future" :-)) And I see this motion control
pattern as an essential part of OCL!

Herman

motion control pattern

2009/2/12 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>:
> On Thu, 12 Feb 2009, t [dot] j [dot] a [dot] devries [..] ... wrote:
>
>> Nice to read your analysis. I have been thinking about this as well.
>>
>> Re SOLUTION 1:
>> This is what I use now, with a slight variation:
>> 1 write
>> 2 read
>> 3 calculate
>> 4 wait
>>
>> This pattern indeed introduces some delay. However, the nice thing is that the delay is predictable and not time-varying. By choosing the period time short, we can simply minimize it, and then it is not much larger than worst case situations for SOLUTION 2.
>> It has been suggested (by Astrom and Wittenmark) that writing first has advantages, but I never really noticed it, so we might as well stick with reading first, then writing.
>
> In a good control software implementation, the difference between both
> policies should be irrelevant. I mean, if the sampling time is such that a
> difference between both _is_ noticeable, that sampling time is too low! :-)
>

I do not fully agree on that.

a) In the worst case, this is like adding a unit delay in the control
loop. In control of linear motor for machining it has been shown in
many publications that this delay has an important role on the
reliability of the disturbance observers and on the dynamic stiffness
of the controller. If this delay is predictive, it can be taken into
account in the design of the discrete time controller. As against,
this inevitably degrades performance. So I admit that in 99% of cases,
the impact that this delay has on the system is negligible, but we can
not make a generality since this has an impact on the high-precision
control loop of my system.

b) One could increase the sampling frequency so that the unit delay
becomes negligible. However, depending on the type and the load of the
CPU, is not always possible. Again, I do not think we should make a
generality. Also, I'm not convinced that increasing the sampling
frequency for the sole purpose of minimizing this problem is a good
implementation.

> And writing first _seems_ to have the advantage that you apply your new
> control setpoint closest to the optimal time, but one often forgets that
> this new setpoint has been calculated an unspecified time ago :-)
>

I agree.

>> Re: SOLUTION 2
>> Ok, we need this if we do not want minimal period time. My conclusion has
>> been that we could have a clean implementation of this by creating
>> alternative ExecutionEngine behaviour. My idea is to replace the
>> updateHook() call to the TaskContext by a sequence senseHook(),
>> calculateHook(), actuateHook() or any other order, whatever you like.
>> This could be done by introducing a userHookProcessor, as was discussed
>> here: http://www.orocos.org/node/1050
>
> The TaskContext, as a _generic_ building block, should never get any stuff
> that is specific to an particular application: your suggestion introduces
> "periodic control policy" hooks into it, and that's not right :-)
> What _is_ acceptable are application-specific implementations of
> "updateHook()". But these will not be added into RTT, but into OCL.
>
>> I have not elaborated on this yet, but maybe together we can make something happen? What's your opinion on this?
>>

I agree with Herman that this application-specific implementation
should be part of OCL, not RTT.

>> Re: SOLUTION 3
>> Not my prefered way to go. I like sensor- and actuator info to be on ports, so that non-periodic tasks can access them without any worries.
>
> That's the _fundamental_ concern of component-based programming! :-)
>
> Some possibly good news: our new contributor Markus agreed to give the OCL
> part of Orocos some good refactoring attention, and to reduce it to the
> bare minimum but with optimal documentation and motivation. (He will post
> some comments "in the near future" :-)) And I see this motion control
> pattern as an essential part of OCL!

I also prefer to have I/O available as ports.

Upon reflection and in light of your comments, I think that the best
tradeoff would be (let's call it solution #4) :

SOLUTION #4

Make the device driver inherits from the OCL::IOComponent and make it
periodic at a multiple of the sample frequency of the controllers. In
this way, the time delay between "Calculation" and "Write" may be
minimized. The drawback of this method is that the IO will be updated
much more often than is needed, but at least the whole system will not
suffer from a global increase of all the sampling frequencies. This
method can also used to filter I/O at an higher frequency that the
"fundamental" sampling time.

Thank you all for you comments!

Philippe

motion control pattern

On Thu, 12 Feb 2009, Philippe Hamelin wrote:

> 2009/2/12 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>:
>> On Thu, 12 Feb 2009, t [dot] j [dot] a [dot] devries [..] ... wrote:
>>
>>> Nice to read your analysis. I have been thinking about this as well.
>>>
>>> Re SOLUTION 1:
>>> This is what I use now, with a slight variation:
>>> 1 write
>>> 2 read
>>> 3 calculate
>>> 4 wait
>>>
>>> This pattern indeed introduces some delay. However, the nice thing is that the delay is predictable and not time-varying. By choosing the period time short, we can simply minimize it, and then it is not much larger than worst case situations for SOLUTION 2.
>>> It has been suggested (by Astrom and Wittenmark) that writing first has advantages, but I never really noticed it, so we might as well stick with reading first, then writing.
>>
>> In a good control software implementation, the difference between both
>> policies should be irrelevant. I mean, if the sampling time is such that a
>> difference between both _is_ noticeable, that sampling time is too low! :-)
>>
>
> I do not fully agree on that.

Then you should rewrite all control theory textbook... :-)

> a) In the worst case, this is like adding a unit delay in the control
> loop. In control of linear motor for machining it has been shown in
> many publications that this delay has an important role on the
> reliability of the disturbance observers and on the dynamic stiffness
> of the controller. If this delay is predictive, it can be taken into
> account in the design of the discrete time controller.

If you really want to achieve this level of realtime response, you better
look for dedicated hardware, without any OS or multi-tasking, since the
jitter and latency in typical PC-based hardware is of the order of
magnitude of the differences you are talking about.

> As against,
> this inevitably degrades performance. So I admit that in 99% of cases,
> the impact that this delay has on the system is negligible, but we can
> not make a generality since this has an impact on the high-precision
> control loop of my system.

> b) One could increase the sampling frequency so that the unit delay
> becomes negligible. However, depending on the type and the load of the
> CPU, is not always possible. Again, I do not think we should make a
> generality. Also, I'm not convinced that increasing the sampling
> frequency for the sole purpose of minimizing this problem is a good
> implementation.

The _only_ alternative for a discretization of continuous-time control
theory that cannot assume that the discretization effects are negligible
wrt to the controlled plant dynamics is, as you mention, the approach in
which you can make (and use online!) an accurate dynamic model of your
plant's behaviour (_and_ of your control system's latencies...). And then
again, _if_ you can do it, you can equally well send out (or read in) the
IO together with timestamps from the realtime clock and adapt your control
output accordingly.

In addition, if you want to achieve such a control using Data Ports and
components, the overhead of using these (safe!) primitives is probably
much larger (thread scheduling, buffer overhead, ...) than the differences
you want to account for.

Anyway, paraphrasing Voltaire,
<http://en.wikipedia.org/wiki/Voltaire#cite_note-8>
"even if I disagree severely with what you say, I will defend to the death
your right to express them" in Orocos: Orocos will never try to impose any
control policy on its users! :-)

>> And writing first _seems_ to have the advantage that you apply your new
>> control setpoint closest to the optimal time, but one often forgets that
>> this new setpoint has been calculated an unspecified time ago :-)
>
> I agree.
>
>>> Re: SOLUTION 2
>>> Ok, we need this if we do not want minimal period time. My conclusion has
>>> been that we could have a clean implementation of this by creating
>>> alternative ExecutionEngine behaviour. My idea is to replace the
>>> updateHook() call to the TaskContext by a sequence senseHook(),
>>> calculateHook(), actuateHook() or any other order, whatever you like.
>>> This could be done by introducing a userHookProcessor, as was discussed
>>> here: http://www.orocos.org/node/1050
>>
>> The TaskContext, as a _generic_ building block, should never get any stuff
>> that is specific to an particular application: your suggestion introduces
>> "periodic control policy" hooks into it, and that's not right :-)
>> What _is_ acceptable are application-specific implementations of
>> "updateHook()". But these will not be added into RTT, but into OCL.
>>
>>> I have not elaborated on this yet, but maybe together we can make something happen? What's your opinion on this?
>>>
>
> I agree with Herman that this application-specific implementation
> should be part of OCL, not RTT.
>
>>> Re: SOLUTION 3
>>> Not my prefered way to go. I like sensor- and actuator info to be on ports, so that non-periodic tasks can access them without any worries.
>>
>> That's the _fundamental_ concern of component-based programming! :-)
>>
>> Some possibly good news: our new contributor Markus agreed to give the OCL
>> part of Orocos some good refactoring attention, and to reduce it to the
>> bare minimum but with optimal documentation and motivation. (He will post
>> some comments "in the near future" :-)) And I see this motion control
>> pattern as an essential part of OCL!
>
> I also prefer to have I/O available as ports.
>
> Upon reflection and in light of your comments, I think that the best
> tradeoff would be (let's call it solution #4) :
>
> SOLUTION #4
>
> Make the device driver inherits from the OCL::IOComponent and make it
> periodic at a multiple of the sample frequency of the controllers. In
> this way, the time delay between "Calculation" and "Write" may be
> minimized. The drawback of this method is that the IO will be updated
> much more often than is needed, but at least the whole system will not
> suffer from a global increase of all the sampling frequencies. This
> method can also used to filter I/O at an higher frequency that the
> "fundamental" sampling time.

In principle at least, Orocos has foreseen such cases: our design makes it
possible to "serialize" multiple activities in the same thread, so that you
can have the mentioned behaviour (different parts running at integer
multiples of the same frequency) without any scheduling overhead. However,
this is all manual work in the current version, but it is in our vision for
the toolchain support, _sometime_ in the future. In addition, if you
"deploy" your component-based design (using TaskContexts, Data Ports,
multiple activities, ...) on a centralized platform, this serialization
also allows to do away with all Data Port overheads, since one can be sure
about the order of access to the hardware.

> Thank you all for you comments!
Thank you for being critical, and for being stubborn enough to continue to
do so! :-)

Herman

>
> Philippe
>

motion control pattern

2009/2/12 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>:

> If you really want to achieve this level of realtime response, you better
> look for dedicated hardware, without any OS or multi-tasking, since the
> jitter and latency in typical PC-based hardware is of the order of
> magnitude of the differences you are talking about.

Of course this is the safiest way to do real time control. However, we
always try to do much with less. To this end, Orocos helps us to _Keep
It Simple_ by regrouping all the components on a Linux PC with simple
hardware. With respect to the _Keep It Simple_ philosophy, my only
goal to that is : How to make a proper use of Orocos which maximizes
it's potential real time control performance ?

> Anyway, paraphrasing Voltaire,
> <http://en.wikipedia.org/wiki/Voltaire#cite_note-8>
> "even if I disagree severely with what you say, I will defend to the death
> your right to express them" in Orocos: Orocos will never try to impose any
> control policy on its users! :-)
>

Well, why i'm not surprise to see a wikipedia reference here? :-)

>
> In principle at least, Orocos has foreseen such cases: our design makes it
> possible to "serialize" multiple activities in the same thread, so that you
> can have the mentioned behaviour (different parts running at integer
> multiples of the same frequency) without any scheduling overhead. However,
> this is all manual work in the current version, but it is in our vision for
> the toolchain support, _sometime_ in the future. In addition, if you
> "deploy" your component-based design (using TaskContexts, Data Ports,
> multiple activities, ...) on a centralized platform, this serialization
> also allows to do away with all Data Port overheads, since one can be sure
> about the order of access to the hardware.
>

Peter told me before that all PeriodicActivity that have the same
period are executed by the same thread. He also stated that the order
of execution is driven by the order of which the components are
started. However, this is not an _official_ behaviour. If I want to
make it safe, I have to use SlaveActivity. The current implementation
of the SlaveActivity in the deployer is not very clear to me. It would
be nice to have a way to force the order of execution of
PeriodicActivity via the deployer, regardless of the order in which
they were started.

See you soon on the next battlefield. :-)

Philippe

motion control pattern

On Thu, 12 Feb 2009, Philippe Hamelin wrote:

> 2009/2/12 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>:
>
>> If you really want to achieve this level of realtime response, you better
>> look for dedicated hardware, without any OS or multi-tasking, since the
>> jitter and latency in typical PC-based hardware is of the order of
>> magnitude of the differences you are talking about.
>
> Of course this is the safiest way to do real time control. However, we
> always try to do much with less. To this end, Orocos helps us to _Keep
> It Simple_ by regrouping all the components on a Linux PC with simple
> hardware. With respect to the _Keep It Simple_ philosophy, my only
> goal to that is : How to make a proper use of Orocos which maximizes
> it's potential real time control performance ?

If performance is your most important design requirement, forget about the
nice Orocos features. If reusability, instrumentability, reporting, safe
data flow, event-based functionality, ... are also important, please
continue this discussion, since different weights put on these different
requirements will possibly lead to different designs...

[...]
>> In principle at least, Orocos has foreseen such cases: our design makes it
>> possible to "serialize" multiple activities in the same thread, so that you
>> can have the mentioned behaviour (different parts running at integer
>> multiples of the same frequency) without any scheduling overhead. However,
>> this is all manual work in the current version, but it is in our vision for
>> the toolchain support, _sometime_ in the future. In addition, if you
>> "deploy" your component-based design (using TaskContexts, Data Ports,
>> multiple activities, ...) on a centralized platform, this serialization
>> also allows to do away with all Data Port overheads, since one can be sure
>> about the order of access to the hardware.
>
> Peter told me before that all PeriodicActivity that have the same
> period are executed by the same thread. He also stated that the order
> of execution is driven by the order of which the components are
> started. However, this is not an _official_ behaviour. If I want to
> make it safe, I have to use SlaveActivity.

Or use the state machine functionality. (This has some different use cases,
but behaviour determinism is one of them.)

> The current implementation
> of the SlaveActivity in the deployer is not very clear to me. It would
> be nice to have a way to force the order of execution of
> PeriodicActivity via the deployer, regardless of the order in which
> they were started.
Yes, this touches upon the abovementioned use of state machines, in
different components in the system: your Deployer's responsibilities stop
after deployment, and then a "Master Component" should take over, _if_ you
want all activities to act in a centrally synchronised way.

> See you soon on the next battlefield. :-)
Oops... Where could that be!?

Herman

motion control pattern

Wow man, I cannot keep up with you! My sample period seems to be much larger....

Regarding the issue of sampling: we have been involved in projects where the sample time was determined by sensors and communication, not by control hard- and software. Delay was definitely noticable, but we had no possibilities to change that. In these cases, we surely wanted to send out the new control as soon as possible. These cases were not 'standard' robotics, but still quite common I think. So there is a part of the world where this matters...

Then about the 'periodic control policy' (what a nice phrasing!) and the lack of generality of TaskContext that would follow from my proposal. Let me state clearly that like many others, I am very happy with what Orocos offers now, so indeed it must be general enough, right now. But in my opinion, the current implementation is "application-specific" anyway: it enforces a particular order of execution that may or may not be convenient. The whole reason for this thread is that in the case of the OP it is not convenient! And it is exactly the same as what I experience...
Also, each Processor contained in the ExecutionEngine can be modified without touching the ExecutionEngine, except for the user code part, i.e., updateHook(). It's not that large a problem, but I do not understand the reason behind this difference.
Anyway, providing solutions in OCL would be ok with me.

Which brings me to SOLUTION 4. Good idea, I think. The actuator part can work nicely in combination with a port that generates an event when new data has arrived and the sensor part can deliver better quality data. Hey, maybe we can then even lower the controller sample frequency...

Cheers, Theo.

motion control pattern

2009/2/12 <t [dot] j [dot] a [dot] devries [..] ...>:
> Wow man, I cannot keep up with you! My sample period seems to be much larger....

My control loops are usually running at 1 kHz. With solution #4, my
sensor/input would be refreshed at 2 kHz or more. It's not so marginal
to me, since I've seen an application of active vibration control
vibration at 10kHz with Linux/RTAI.

>
> Regarding the issue of sampling: we have been involved in projects where the sample time was determined by sensors and communication, not by control hard- and software. Delay was definitely noticable, but we had no possibilities to change that. In these cases, we surely wanted to send out the new control as soon as possible. These cases were not 'standard' robotics, but still quite common I think. So there is a part of the world where this matters...
>
> Then about the 'periodic control policy' (what a nice phrasing!) and the lack of generality of TaskContext that would follow from my proposal. Let me state clearly that like many others, I am very happy with what Orocos offers now, so indeed it must be general enough, right now. But in my opinion, the current implementation is "application-specific" anyway: it enforces a particular order of execution that may or may not be convenient. The whole reason for this thread is that in the case of the OP it is not convenient! And it is exactly the same as what I experience...
> Also, each Processor contained in the ExecutionEngine can be modified without touching the ExecutionEngine, except for the user code part, i.e., updateHook(). It's not that large a problem, but I do not understand the reason behind this difference.
> Anyway, providing solutions in OCL would be ok with me.
>
> Which brings me to SOLUTION 4. Good idea, I think. The actuator part can work nicely in combination with a port that generates an event when new data has arrived and the sensor part can deliver better quality data.

I didn't know that it was possible to fire an event on data port? Is
this documented? This wasn't supposed to be a 1.8 or 2.0 feature? This
could allow us to output data on demand (or ASAP?) with buffered port.

> Hey, maybe we can then even lower the controller sample frequency...
>

Of course. You'd be surprised how you can control systems with
relatively low sampling rates using appropriate discrete time design
tools.

Philippe