Operation and C++ exception

Hi.

I have a TaskContext embedding some functions from a C++ library.
I want to call the library functions through some operations provided by
the TaskContext. To avoid concurrent calls, all operations are executed
in the TaskContext thread (using RTT::OwnThread ).

Currently, if one of these methods throws an exception, the exception is
catched in os::Thread::step, and the thread exits. If the call is
blocking, the OperationCaller never returns. I need a way to unlock the
OperationCaller and to notify the exception to the calling thread.

By browsing the code, I think this can be done via the RStore, which can
catch the exception when exec() is called and throw another one when
isExecuted is called when the caller try to collect the result. The
called TaskContext can also be set to exception set if needed.

What do you think ? Will this mechanism work for remote calls through
corba ?

Thanks,

Operation and C++ exception

On Thu, 30 Jun 2011, Mathieu Gautier wrote:

> I have a TaskContext embedding some functions from a C++ library.
> I want to call the library functions through some operations provided by
> the TaskContext. To avoid concurrent calls, all operations are executed
> in the TaskContext thread (using RTT::OwnThread ).
>
> Currently, if one of these methods throws an exception, the exception is
> catched in os::Thread::step, and the thread exits. If the call is
> blocking, the OperationCaller never returns. I need a way to unlock the
> OperationCaller and to notify the exception to the calling thread.
>
> By browsing the code, I think this can be done via the RStore, which can
> catch the exception when exec() is called and throw another one when
> isExecuted is called when the caller try to collect the result. The
> called TaskContext can also be set to exception set if needed.
>
> What do you think ? Will this mechanism work for remote calls through
> corba ?

I hope you leave this line of thought as quickly as possible :-) Two
reasons:
- remote calls through CORBA (or any other middleware for that matter) are
the best way to screw up realtime determinism. If you want to do that,
there is no reason you should use RTT. Just do these things in another
framework and connect it to RTT if you need things in realtime. RTT has
good support to connect to other frameworks, such as ROS.
- exceptions (in C++ or anywhere else) are the second best way of screwing
realtime determinism, since it's the C++ runtime _implementation_ that
defines your behaviour, and that implementation's behaviour is opaque to
say the least.

Anyway, you're free to do what you like, but don't come back later
complaining about RTT not doing what you expect, if you use a combination
of C++ exceptions and CORBA method calls. I've seen big robotics projects
being killed that way...

> Thanks,
>
> Mathieu Gautier

Herman

Operation and C++ exception

On 06/30/2011 06:42 PM, Herman Bruyninckx wrote:
> - remote calls through CORBA (or any other middleware for that matter) are
> the best way to screw up realtime determinism. If you want to do that,
> there is no reason you should use RTT. Just do these things in another
> framework and connect it to RTT if you need things in realtime. RTT has
> good support to connect to other frameworks, such as ROS.
Why in hell are you always saying that ? RTT is a perfectly good general
purpose framework, that has features outside or realtimeness that stuff
like ROS do NOT have (proper component model, proper threading model,
explicit connection mechanism, multi-protocol dataflow support). So, why
should it be limited to the realtime "niche" ?

Finally, with the advent of the operations, one can call them without
screwing the realtime-ness of the component (only the caller is
non-realtime, not the callee).

> - exceptions (in C++ or anywhere else) are the second best way of screwing
> realtime determinism, since it's the C++ runtime _implementation_ that
> defines your behaviour, and that implementation's behaviour is opaque to
> say the least.
Not true. The C++ exception handling mechanism is very controlled by the
C++ specification. For instance, it cannot do any memory allocation (the
C++ exception objects can if they want to, as e.g. runtime_error).
Moreover, it is meant for *exceptional situations*. I.e. cases that the
normal execution (and realtime-ness properties) are guaranteed anyway
because *you are outside of the nominal execution flow*.

> Anyway, you're free to do what you like, but don't come back later
> complaining about RTT not doing what you expect, if you use a combination
> of C++ exceptions and CORBA method calls. I've seen big robotics projects
> being killed that way...
Operations are not CORBA method calls. Operations are RTT operations.
Period. Then, it so happens that you can call them from CORBA. I find
the poster question to be very sound: what is the behaviour of
exceptions w.r.t. operations in RTT ? Blocking the operation forever is
definitely not "a good behaviour"

Operation and C++ exception

>> - exceptions (in C++ or anywhere else) are the second best way of
>> screwing
>> realtime determinism, since it's the C++ runtime _implementation_ that
>> defines your behaviour, and that implementation's behaviour is opaque to
>> say the least.
> Not true. The C++ exception handling mechanism is very controlled by the
> C++ specification. For instance, it cannot do any memory allocation (the
> C++ exception objects can if they want to, as e.g. runtime_error).
> Moreover, it is meant for *exceptional situations*. I.e. cases that the
> normal execution (and realtime-ness properties) are guaranteed anyway
> because *you are outside of the nominal execution flow*.

It's precisely my use case. If one of my component happen to be outside
of "the nominal flow", I'd rather have a way to make this component and
the caller try to recover, than having part of the application freezing.

Besides, the operations than can throw exceptions are used to a
TaskContext before starting it.

Operation and C++ exception

On Friday 01 July 2011 10:53:09 Mathieu Gautier wrote:
> >> - exceptions (in C++ or anywhere else) are the second best way of
> >> screwing
> >> realtime determinism, since it's the C++ runtime _implementation_ that
> >> defines your behaviour, and that implementation's behaviour is opaque to
> >> say the least.
> >
> > Not true. The C++ exception handling mechanism is very controlled by the
> > C++ specification. For instance, it cannot do any memory allocation (the
> > C++ exception objects can if they want to, as e.g. runtime_error).
> > Moreover, it is meant for *exceptional situations*. I.e. cases that the
> > normal execution (and realtime-ness properties) are guaranteed anyway
> > because *you are outside of the nominal execution flow*.
>
> It's precisely my use case. If one of my component happen to be outside
> of "the nominal flow", I'd rather have a way to make this component and
> the caller try to recover, than having part of the application freezing.

Since C++ exceptions are a reality[1] when creating Orocos C++ components, I'm
in favour to catch any case in a deterministic way. We concluded before that
for every *Hook() function, a thrown exception will cause the component to
enter the Exception state. We could extend this to Operations and let the
operation caller fail if an exception is thrown, and let the component enter
the Exception state. I would consider throwing exceptions across component
boundaries as not supported, and any such attempt is an error.
I agree that the operationcaller must be unblocked in this case and report a
call failure. This should be done by throwing the failure during a call() and
returning it during a collect(). This must work transparantly over CORBA as
well of course.

Peter

>
> Besides, the operations than can throw exceptions are used to a
> TaskContext before starting it.

[1] both std C++ types and boost types throw exceptions for example. Due to
these types, it's even impossible to compile RTT with -fno-exceptions

Operation and C++ exception

Hi,

> Since C++ exceptions are a reality[1] when creating Orocos C++ components, I'm
> in favour to catch any case in a deterministic way. We concluded before that
> for every *Hook() function, a thrown exception will cause the component to
> enter the Exception state. We could extend this to Operations and let the
> operation caller fail if an exception is thrown, and let the component enter
> the Exception state. I would consider throwing exceptions across component
> boundaries as not supported, and any such attempt is an error.
> I agree that the operationcaller must be unblocked in this case and report a
> call failure. This should be done by throwing the failure during a call() and
> returning it during a collect(). This must work transparantly over CORBA as
> well of course.

I made a first attempt to implement this proposal (see attached patch).
I have only implemented exception propagation. I didn't modify the
component state yet.

Any exception thrown by an operation is catched in RStore when calling
exec. The string attached to the exception is kept by the RStore and a
flag "error" is set. An new std::runtime_error can be thrown by calling
checkError on the RStore if the error flag is set. The store string will
be passed to this new exception.

checkError is called in LocalOperationImpl::collectIfDone and in
FusedMCallDataSource::evaluate and get. This made call(), collect() and
collectIfDone() throw if the bound operation throw. I also have to catch
the exception in the OperationKeeper destructor, because
DataSource::evaluate is called. Since the OperationKeeper was designed
to avoid deadlocks, I ignore the catched exception.

I also implemented a CORBA version. I add a CCallError exception to
forward the exception through corba. CCallError store only a string.
std::runtime_error in thrown in CorbaOperationCaller is CCallError is
catched.

I still have some questions:

The biggest issue, imho, is how to made the component enter the
exception state. I think it's easy with the RTT::ClientThread flag, but
I'm not sure how to do it with RTT::OwnThread.

Is runtime_error the best suited exception to indicate an application
exception in a remote Operation?

How can we propagate the error status without using exceptions (as
suggested by Herman)?

How to implement the exception (or any other error mechanism)
propagation in other transports?

Operation and C++ exception

Hi Mathieu,

On Wed, Jul 6, 2011 at 2:41 PM, Mathieu Gautier <mathieu [dot] gautier [..] ...> wrote:
> Hi,
>
>> Since C++ exceptions are a reality[1] when creating Orocos C++ components,
>> I'm
>> in favour to catch any case in a deterministic way. We concluded before
>> that
>> for every *Hook() function, a thrown exception will cause the component to
>> enter the Exception state. We could extend this to Operations and let the
>> operation caller fail if an exception is thrown, and let the component
>> enter
>> the Exception state. I would consider throwing exceptions across component
>> boundaries as not supported, and any such attempt is an error.
>> I agree that the operationcaller must be unblocked in this case and report
>> a
>> call failure. This should be done by throwing the failure during a call()
>> and
>> returning it during a collect(). This must work transparantly over CORBA
>> as
>> well of course.
>
> I made a first attempt to implement this proposal (see attached patch). I
> have only implemented exception propagation. I didn't modify the component
> state yet.

Thanks for this excellent patch. This stuff is living in the hardest
parts of the operation handling, I'm glad you got it to work and added
extra unit tests.

>
> Any exception thrown by an operation is catched in RStore when calling exec.
> The string attached to the exception is kept by the RStore and a flag
> "error" is set. An new std::runtime_error can be thrown by calling
> checkError on the RStore if the error flag is set. The store string will be
> passed to this new exception.

Why do you catch only std::runtime_error ? What I would prefer is that
any exception (...) is caught. I would not allow to propagate a user
message in the exception, since this would imply that it's a valid
mechanism to report some error. Throwing a runtime_exception is fine
for me, but with a standard descriptive message...saying that the
operation could not be completed because the server code threw an
exception at some point.

>
> checkError is called in LocalOperationImpl::collectIfDone and in
> FusedMCallDataSource::evaluate and get. This made call(), collect() and
> collectIfDone() throw if the bound operation throw. I also have to catch the
> exception in the OperationKeeper destructor, because DataSource::evaluate is
> called. Since the OperationKeeper was designed to avoid deadlocks, I ignore
> the catched exception.

Ok. I'll need to re-look at this as well to see if it works out.

>
> I also implemented a CORBA version. I add a CCallError exception to forward
> the exception through corba. CCallError store only a string.
> std::runtime_error in thrown in CorbaOperationCaller is CCallError is
> catched.
>
> I still have some questions:
>
> The biggest issue, imho, is how to made the component enter the exception
> state. I think it's easy with the RTT::ClientThread flag, but I'm not sure
> how to do it with RTT::OwnThread.

I think calling engine->getTaskCore()->exception() when the exception
is caught is all it takes... The EE checks for the exception state at
well defined points (whenever it gets a chance). The only problem I
see is that exception() is protected. The EE is a friend, so the EE
could forward that with a new engine->exception() call...

>
> Is runtime_error the best suited exception to indicate an application
> exception in a remote Operation?

I don't mind throwing a runtime_error to the client code, but I would
catch all exceptions.

>
> How can we propagate the error status without using exceptions (as suggested
> by Herman)?

This can only be done by providing an extra argument to all functions,
containing the error state. We're not going to do that.

>
> How to implement the exception (or any other error mechanism) propagation in
> other transports?

Only corba supports operation calling, so the others don't need any
modification.

Peter

Operation and C++ exception

Hi,

I made a new patch with the suggested modifications

>
>>
>> I also implemented a CORBA version. I add a CCallError exception to forward
>> the exception through corba. CCallError store only a string.
>> std::runtime_error in thrown in CorbaOperationCaller is CCallError is
>> catched.
>>
>> I still have some questions:
>>
>> The biggest issue, imho, is how to made the component enter the exception
>> state. I think it's easy with the RTT::ClientThread flag, but I'm not sure
>> how to do it with RTT::OwnThread.
>
> I think calling engine->getTaskCore()->exception() when the exception
> is caught is all it takes... The EE checks for the exception state at
> well defined points (whenever it gets a chance). The only problem I
> see is that exception() is protected. The EE is a friend, so the EE
> could forward that with a new engine->exception() call...

I still have a issue. It's not currently possible to set the owner of
the operation in the exception state except if the operation was
registered with the OwnThread flag. Indeed, an OperationCaller can only
access the caller EE and the EE in which it must be called (myengine).

In order to set the owner component to the exception state, I think that
LocalOperationCaller must hold a handle to the component that provides
this operation or to the component's EE. Is this conclusion correct ?

Operation and C++ exception

Hi,

I finally had enough time to add the last functionalities to the patch.
ie, setting the task owning the operation in the exception state.

> In order to set the owner component to the exception state, I think that
> LocalOperationCaller must hold a handle to the component that provides
> this operation or to the component's EE. Is this conclusion correct ?

I add a handle on the taskcontext execution engine, if any, to the
LocalOperationCaller. It's done while calling addOperation on a Service.
If an exception is thrown, executeAndDispose calls reportError which
calls setExceptionState on the taskContext EE.

I add the corresponding tests.

Operation and C++ exception

Oops,

I forgot to attach the patch.

Operation and C++ exception

Hi,

>
> Why do you catch only std::runtime_error ? What I would prefer is that

It's was first attempt meant to discuss some points about the
implementation. I agree that all exception have to be caught.

> any exception (...) is caught. I would not allow to propagate a user
> message in the exception, since this would imply that it's a valid
> mechanism to report some error. Throwing a runtime_exception is fine
> for me, but with a standard descriptive message...saying that the
> operation could not be completed because the server code threw an
> exception at some point.

Ok, does the exception type have to be added to this message for common
exceptions ? Such as bad_alloc, logic_error, runtime_error, etc.

>> I still have some questions:
>>
>> The biggest issue, imho, is how to made the component enter the exception
>> state. I think it's easy with the RTT::ClientThread flag, but I'm not sure
>> how to do it with RTT::OwnThread.
>
> I think calling engine->getTaskCore()->exception() when the exception
> is caught is all it takes... The EE checks for the exception state at
> well defined points (whenever it gets a chance). The only problem I
> see is that exception() is protected. The EE is a friend, so the EE
> could forward that with a new engine->exception() call...

Ok, I'll try it.

Operation and C++ exception

On Wed, 6 Jul 2011, Peter Soetens wrote:

[...]
>> How can we propagate the error status without using exceptions (as suggested
>> by Herman)?
>
> This can only be done by providing an extra argument to all functions,
> containing the error state. We're not going to do that.

Why not...?

>> How to implement the exception (or any other error mechanism) propagation in
>> other transports?
>
> Only corba supports operation calling, so the others don't need any
> modification.

So, you have introduced a specific behaviour in the framework that is not
supportable over any communication middleware that developers decide to
use?

I have posed two questions above whose answers should be fully and clearly
documented and motivated in the official documentation, I think.

Herman

Operation and C++ exception

On Thu, Jul 7, 2011 at 7:17 AM, Herman Bruyninckx
<Herman [dot] Bruyninckx [..] ...> wrote:
> On Wed, 6 Jul 2011, Peter Soetens wrote:
>
> [...]
>>>
>>> How can we propagate the error status without using exceptions (as
>>> suggested
>>> by Herman)?
>>
>> This can only be done by providing an extra argument to all functions,
>> containing the error state. We're not going to do that.
>
> Why not...?

Only for practical reasons. The Operations are burdening the compiler
too much already, leading to too slow compilation times already,
adding extra functions (a complete parallel path) to these objects is
not an option.

>
>>> How to implement the exception (or any other error mechanism) propagation
>>> in
>>> other transports?
>>
>> Only corba supports operation calling, so the others don't need any
>> modification.
>
> So, you have introduced a specific behaviour in the framework that is not
> supportable over any communication middleware that developers decide to
> use?

Yes, and we are very aware of this. The message we send out is that
for coordination&operations, CORBA is to be used. For data flow, any
middleware may be used. Most middlewares (ROS, message queues, Yarp,
ZeroMQ,...) only provide streaming services[1]. CORBA comes from the
other end of perspective, and is bad in providing streaming services
(hence the many out-of-band streaming frameworks with CORBA) but is
very good at request/reply services, ie, mapping to RTT operations.

>
> I have posed two questions above whose answers should be fully and clearly
> documented and motivated in the official documentation, I think.

I agree.

Peter

[1] They do provide some request/reply features but we found them too
hard to integrate in our 'functional' operations paradigm.

Operation and C++ exception

On Thu, 7 Jul 2011, Peter Soetens wrote:

> On Thu, Jul 7, 2011 at 7:17 AM, Herman Bruyninckx
> <Herman [dot] Bruyninckx [..] ...> wrote:
>> On Wed, 6 Jul 2011, Peter Soetens wrote:
>>
>> [...]
>>>>
>>>> How can we propagate the error status without using exceptions (as
>>>> suggested
>>>> by Herman)?
>>>
>>> This can only be done by providing an extra argument to all functions,
>>> containing the error state. We're not going to do that.
>>
>> Why not...?
>
> Only for practical reasons. The Operations are burdening the compiler
> too much already, leading to too slow compilation times already,
> adding extra functions (a complete parallel path) to these objects is
> not an option.

I assume you have a clear message here, but I must confess I do not
understand it yet completely :-) But ok, I am reassured that there _is_
some sort of a motivation. It might be good to make it more visible.

>>>> How to implement the exception (or any other error mechanism) propagation
>>>> in
>>>> other transports?
>>>
>>> Only corba supports operation calling, so the others don't need any
>>> modification.
>>
>> So, you have introduced a specific behaviour in the framework that is not
>> supportable over any communication middleware that developers decide to
>> use?
>
> Yes, and we are very aware of this. The message we send out is that
> for coordination&operations, CORBA is to be used. For data flow, any
> middleware may be used.

I am not surprised to see "operations" mentioned as requiring a middleware
such as CORBA, but I am surprised to see "coordination" in the same
category: strictly speaking, Coordination requires only events, and events
only require "data flow-like" infrastructure.
I would expect "Configuration" to show up in the "Requires CORBA"
category, since configuration is a natural candidate for "operations".

> Most middlewares (ROS, message queues, Yarp,
> ZeroMQ,...) only provide streaming services[1]. CORBA comes from the
> other end of perspective, and is bad in providing streaming services
> (hence the many out-of-band streaming frameworks with CORBA) but is
> very good at request/reply services, ie, mapping to RTT operations.

Agreed! There seems to grow a useful "terminology pattern/categorization"
here:
- streaming, data flow
- request/reply services
Coincidentally, I suggested the same two categories earlier this week in an
internal design brainstorming session as the major two a framework such as
Orocos has to deal with. So, I suggest we adopt these two categories
(including the terminology) for all further discussions and documentation.
In my experience as the "top down guy" of Orocos (which is not really
different from my responsibility as the "harmonization Work Package leader
in the BRICS project), I am always looking for simple structures annex
terminology that helps to streamline and clarify documentation, tutorials
and design discussions, and I think we have just identified such a
structure...

>> I have posed two questions above whose answers should be fully and clearly
>> documented and motivated in the official documentation, I think.
>
> I agree.
>
> Peter
>
> [1] They do provide some request/reply features but we found them too
> hard to integrate in our 'functional' operations paradigm.

Is it possible to say in one sentence why exactly it was too hard? I
suspect that is because they do not provide "policy defining primitives" on
top of their "bare" data flow support... If that is the case, that's great
:-) In the sense that they then have succeeded in keeping their project
focused and lean, unlike CORBA...

Herman

Operation and C++ exception

On 07/07/11 17:48, Herman Bruyninckx wrote:
>> Most middlewares (ROS, message queues, Yarp,
>> ZeroMQ,...) only provide streaming services[1]. CORBA comes from the
>> other end of perspective, and is bad in providing streaming services
>> (hence the many out-of-band streaming frameworks with CORBA) but is
>> very good at request/reply services, ie, mapping to RTT operations.
>
> Agreed! There seems to grow a useful "terminology pattern/categorization"
> here:
> - streaming, data flow
> - request/reply services
> Coincidentally, I suggested the same two categories earlier this week in an
> internal design brainstorming session as the major two a framework such as
> Orocos has to deal with. So, I suggest we adopt these two categories
> (including the terminology) for all further discussions and documentation.
> In my experience as the "top down guy" of Orocos (which is not really
> different from my responsibility as the "harmonization Work Package leader
> in the BRICS project), I am always looking for simple structures annex
> terminology that helps to streamline and clarify documentation, tutorials
> and design discussions, and I think we have just identified such a
> structure...

OpenRTM uses exactly this categorisation with its port types. It
provides one port type for the request/reply services (the Service Port)
and one for data streams (called... wait for it... the Data Port).

This categorisation has been around in the software industry for quite
some time. Probably at least a decade. The OMG has two separate
standards, one in each category.

Geoff

Operation and C++ exception

On Thu, 7 Jul 2011, Geoffrey Biggs wrote:

> On 07/07/11 17:48, Herman Bruyninckx wrote:
>>> Most middlewares (ROS, message queues, Yarp,
>>> ZeroMQ,...) only provide streaming services[1]. CORBA comes from the
>>> other end of perspective, and is bad in providing streaming services
>>> (hence the many out-of-band streaming frameworks with CORBA) but is
>>> very good at request/reply services, ie, mapping to RTT operations.
>>
>> Agreed! There seems to grow a useful "terminology pattern/categorization"
>> here:
>> - streaming, data flow
>> - request/reply services
>> Coincidentally, I suggested the same two categories earlier this week in an
>> internal design brainstorming session as the major two a framework such as
>> Orocos has to deal with. So, I suggest we adopt these two categories
>> (including the terminology) for all further discussions and documentation.
>> In my experience as the "top down guy" of Orocos (which is not really
>> different from my responsibility as the "harmonization Work Package leader
>> in the BRICS project), I am always looking for simple structures annex
>> terminology that helps to streamline and clarify documentation, tutorials
>> and design discussions, and I think we have just identified such a
>> structure...
>
> OpenRTM uses exactly this categorisation with its port types. It
> provides one port type for the request/reply services (the Service Port)
> and one for data streams (called... wait for it... the Data Port).
>
> This categorisation has been around in the software industry for quite
> some time. Probably at least a decade. The OMG has two separate
> standards, one in each category.

Orocos has both of them too. So, there is no debate that this is not a
"Best Practice". But documentation can never be clear enough in guiding
newcomers sufficiently in the "right direction". :-)

> Geoff

Herman

Operation and C++ exception

2011/7/7 Herman Bruyninckx <Herman [dot] Bruyninckx [..] ...>:
> On Thu, 7 Jul 2011, Peter Soetens wrote:
>
>> On Thu, Jul 7, 2011 at 7:17 AM, Herman Bruyninckx
>> <Herman [dot] Bruyninckx [..] ...> wrote:
>>> On Wed, 6 Jul 2011, Peter Soetens wrote:
>>>
>>> [...]
>>>>>
>>>>> How can we propagate the error status without using exceptions (as
>>>>> suggested
>>>>> by Herman)?
>>>>
>>>> This can only be done by providing an extra argument to all functions,
>>>> containing the error state. We're not going to do that.
>>>
>>> Why not...?
>>
>> Only for practical reasons. The Operations are burdening the compiler
>> too much already, leading to too slow compilation times already,
>> adding extra functions (a complete parallel path) to these objects is
>> not an option.
>
> I assume you have a clear message here, but I must confess I do not
> understand it yet completely :-) But ok, I am reassured that there _is_
> some sort of a motivation. It might be good to make it more visible.
>
>>>>> How to implement the exception (or any other error mechanism) propagation
>>>>> in
>>>>> other transports?
>>>>
>>>> Only corba supports operation calling, so the others don't need any
>>>> modification.
>>>
>>> So, you have introduced a specific behaviour in the framework that is not
>>> supportable over any communication middleware that developers decide to
>>> use?
>>
>> Yes, and we are very aware of this. The message we send out is that
>> for coordination&operations, CORBA is to be used. For data flow, any
>> middleware may be used.
>
> I am not surprised to see "operations" mentioned as requiring a middleware
> such as CORBA, but I am surprised to see "coordination" in the same
> category: strictly speaking, Coordination requires only events, and events
> only require "data flow-like" infrastructure.
> I would expect "Configuration" to show up in the "Requires CORBA"
> category, since configuration is a natural candidate for "operations".
>
>> Most middlewares (ROS, message queues, Yarp,
>> ZeroMQ,...) only provide streaming services[1]. CORBA comes from the
>> other end of perspective, and is bad in providing streaming services
>> (hence the many out-of-band streaming frameworks with CORBA) but is
>> very good at request/reply services, ie, mapping to RTT operations.
>
> Agreed! There seems to grow a useful "terminology pattern/categorization"
> here:
> - streaming, data flow
> - request/reply services

I fully agree with this categorization, it is how we are implementing things.

We are using ZeroMQ for streaming and are about to start working on
request/reply for services. In my view, also request/reply is
supported very well in ZeroMQ. I have not looked in detail into CORBA,
maybe that is more convenient. But I think also ZeroMQ can come a long
way for services. Will share experiences in due time, but in the mean
time would like to understand what you mean with
>> found them too
>> hard to integrate in our 'functional' operations paradigm.
Can you maybe give a short example/pointer what is hard to integrate?

Cheers, Theo.

> Coincidentally, I suggested the same two categories earlier this week in an
> internal design brainstorming session as the major two a framework such as
> Orocos has to deal with. So, I suggest we adopt these two categories
> (including the terminology) for all further discussions and documentation.
> In my experience as the "top down guy" of Orocos (which is not really
> different from my responsibility as the "harmonization Work Package leader
> in the BRICS project), I am always looking for simple structures annex
> terminology that helps to streamline and clarify documentation, tutorials
> and design discussions, and I think we have just identified such a
> structure...
>
>
>>> I have posed two questions above whose answers should be fully and clearly
>>> documented and motivated in the official documentation, I think.
>>
>> I agree.
>>
>> Peter
>>
>> [1] They do provide some request/reply features but we found them too
>> hard to integrate in our 'functional' operations paradigm.
>
> Is it possible to say in one sentence why exactly it was too hard? I
> suspect that is because they do not provide "policy defining primitives" on
> top of their "bare" data flow support... If that is the case, that's great
> :-) In the sense that they then have succeeded in keeping their project
> focused and lean, unlike CORBA...
>
> Herman
> --
> Orocos-Dev mailing list
> Orocos-Dev [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-dev
>

Operation and C++ exception

On Thu, Jul 07, 2011 at 10:48:37AM +0200, Herman Bruyninckx wrote:
> On Thu, 7 Jul 2011, Peter Soetens wrote:
>
> > On Thu, Jul 7, 2011 at 7:17 AM, Herman Bruyninckx
> > <Herman [dot] Bruyninckx [..] ...> wrote:
> >> On Wed, 6 Jul 2011, Peter Soetens wrote:
> >>
> >> [...]
...
> >>>> How to implement the exception (or any other error mechanism) propagation
> >>>> in
> >>>> other transports?
> >>>
> >>> Only corba supports operation calling, so the others don't need any
> >>> modification.
> >>
> >> So, you have introduced a specific behaviour in the framework that is not
> >> supportable over any communication middleware that developers decide to
> >> use?
> >
> > Yes, and we are very aware of this. The message we send out is that
> > for coordination&operations, CORBA is to be used. For data flow, any
> > middleware may be used.
>
> I am not surprised to see "operations" mentioned as requiring a middleware
> such as CORBA, but I am surprised to see "coordination" in the same
> category: strictly speaking, Coordination requires only events, and events
> only require "data flow-like" infrastructure.

I would say Coordination _can_ be implemented by using only events,
but if it is practical and efficient under all circumstances is not
clear yet.

Markus

Operation and C++ exception

On 07/07/2011 10:56 AM, Markus Klotzbuecher wrote:
>> I am not surprised to see "operations" mentioned as requiring a middleware
>> such as CORBA, but I am surprised to see "coordination" in the same
>> category: strictly speaking, Coordination requires only events, and events
>> only require "data flow-like" infrastructure.
>
> I would say Coordination _can_ be implemented by using only events,
> but if it is practical and efficient under all circumstances is not
> clear yet.
I +1 Herman here. Allowing coordination of components using operations
is very dangerous. LAAS has that policy (using operation-like structures
only for configuration), and we continue that policy in rock. I have not
yet seen a big drawback for that.

Operation and C++ exception

On Tue, Jul 12, 2011 at 11:26:32AM +0200, Sylvain Joyeux wrote:
> On 07/07/2011 10:56 AM, Markus Klotzbuecher wrote:
> >> I am not surprised to see "operations" mentioned as requiring a middleware
> >> such as CORBA, but I am surprised to see "coordination" in the same
> >> category: strictly speaking, Coordination requires only events, and events
> >> only require "data flow-like" infrastructure.
> >
> > I would say Coordination _can_ be implemented by using only events,
> > but if it is practical and efficient under all circumstances is not
> > clear yet.
> I +1 Herman here. Allowing coordination of components using operations
> is very dangerous. LAAS has that policy (using operation-like structures
> only for configuration), and we continue that policy in rock. I have not
> yet seen a big drawback for that.

Thanks, thats good to know!
Markus

Operation and C++ exception

On Thu, 7 Jul 2011, Markus Klotzbuecher wrote:

> On Thu, Jul 07, 2011 at 10:48:37AM +0200, Herman Bruyninckx wrote:
>> On Thu, 7 Jul 2011, Peter Soetens wrote:
>>
>>> On Thu, Jul 7, 2011 at 7:17 AM, Herman Bruyninckx
>>> <Herman [dot] Bruyninckx [..] ...> wrote:
>>>> On Wed, 6 Jul 2011, Peter Soetens wrote:
>>>>
>>>> [...]
> ...
>>>>>> How to implement the exception (or any other error mechanism) propagation
>>>>>> in
>>>>>> other transports?
>>>>>
>>>>> Only corba supports operation calling, so the others don't need any
>>>>> modification.
>>>>
>>>> So, you have introduced a specific behaviour in the framework that is not
>>>> supportable over any communication middleware that developers decide to
>>>> use?
>>>
>>> Yes, and we are very aware of this. The message we send out is that
>>> for coordination&operations, CORBA is to be used. For data flow, any
>>> middleware may be used.
>>
>> I am not surprised to see "operations" mentioned as requiring a middleware
>> such as CORBA, but I am surprised to see "coordination" in the same
>> category: strictly speaking, Coordination requires only events, and events
>> only require "data flow-like" infrastructure.
>
> I would say Coordination _can_ be implemented by using only events,
> but if it is practical and efficient under all circumstances is not
> clear yet.

That definitely holds for an "operations-based" implementation too! :-)

I would turn things around: Coordination _has_ to be work with just events,
otherwise you are introducing come hidden coupling with other aspects of
the 5Cs...

I think it's high time to start discussing real Coordination use cases, so
that we can evaluate the "practicality and efficiency" (dis)claims more
concretely.

> Markus

Herman

Operation and C++ exception

On 07/01/2011 04:09 PM, Peter Soetens wrote:
> Since C++ exceptions are a reality[1] when creating Orocos C++ components, I'm
> in favour to catch any case in a deterministic way. We concluded before that
> for every *Hook() function, a thrown exception will cause the component to
> enter the Exception state. We could extend this to Operations and let the
> operation caller fail if an exception is thrown, and let the component enter
> the Exception state. I would consider throwing exceptions across component
> boundaries as not supported, and any such attempt is an error.
> I agree that the operationcaller must be unblocked in this case and report a
> call failure. This should be done by throwing the failure during a call() and
> returning it during a collect(). This must work transparantly over CORBA as
> well of course.
Sounds like a plan to me.

Sylvain

Operation and C++ exception

On Jul 1, 2011, at 10:31 , Sylvain Joyeux wrote:

> On 07/01/2011 04:09 PM, Peter Soetens wrote:
>> Since C++ exceptions are a reality[1] when creating Orocos C++ components, I'm
>> in favour to catch any case in a deterministic way. We concluded before that
>> for every *Hook() function, a thrown exception will cause the component to
>> enter the Exception state. We could extend this to Operations and let the
>> operation caller fail if an exception is thrown, and let the component enter
>> the Exception state. I would consider throwing exceptions across component
>> boundaries as not supported, and any such attempt is an error.
>> I agree that the operationcaller must be unblocked in this case and report a
>> call failure. This should be done by throwing the failure during a call() and
>> returning it during a collect(). This must work transparantly over CORBA as
>> well of course.
> Sounds like a plan to me.

+1

Operation and C++ exception

On Fri, 1 Jul 2011, S Roderick wrote:

> On Jul 1, 2011, at 10:31 , Sylvain Joyeux wrote:
>
>> On 07/01/2011 04:09 PM, Peter Soetens wrote:
>>> Since C++ exceptions are a reality[1] when creating Orocos C++ components, I'm
>>> in favour to catch any case in a deterministic way. We concluded before that
>>> for every *Hook() function, a thrown exception will cause the component to
>>> enter the Exception state. We could extend this to Operations and let the
>>> operation caller fail if an exception is thrown, and let the component enter
>>> the Exception state. I would consider throwing exceptions across component
>>> boundaries as not supported, and any such attempt is an error.
>>> I agree that the operationcaller must be unblocked in this case and report a
>>> call failure. This should be done by throwing the failure during a call() and
>>> returning it during a collect(). This must work transparantly over CORBA as
>>> well of course.
>> Sounds like a plan to me.
>
> +1

It's the only reasonable thing to do, but I would do exactly the same
without exceptions, and the latter case would be more clear and
transparant (because the cause of the exception and the action that the
programmer wants to see happen are _collocated_). I still believe that the
only reason for the introduction of exceptions was to allow programmers to
be less clear about when and how exactly they deal with problems, driven by
the use case that in many contexts one does not mind wiping a large class
of problems under the same carpet, and "outsourcing" the subsequent
cleaning of the mess to "somewhere, sometime and someone else", without
caring about who that someone is, where that somewhere lies, and when that
sometime will be.

I am not the C++ exception specialist, so I can be very wrong, and hence I
am also very open to get convincing arguments from you guys, that, in a
realtime context, we can also afford not to mind about the mentioned
"somewhere, sometime and someone else". I really hope you can come up with
such convincing arguments, for several reasons:
- if you don't, I will not give up my crusade against exceptions, and stay
on polluting this mailing list with my rants. And there are already
enough of those :-(
- if you do, it will not just be me who has learned something, and the
credibility of RTT as a realtime-aware framework can only profit from it
if we put these arguments clearly in the RTT documentation.
But not providing these convincing arguments puts a dark cloud above the
RTT skies. And don't blame me for having put it there...

Let me single out one sentence of Peter's reply: "I would consider throwing
exceptions across component boundaries as not supported, and any such
attempt is an error." My experience makes me wave a red flag here: you
_consider_ this as a problem, being _non-supported_, hence you implicitly
say immediately that (i) there is a problem, and (ii) there is nothing you
can do about _preventing_ this problem. So, the average RTT users see
exceptions being used, and hence infer that they can also use them in their
applications. I prefer not to stimulate users to make these inferences, but
rather to _force_ realtime-aware developers to clean up the mess[1], now,
immediately, transparantly, by not allowing exceptions, at all. Putting
warnings in the documentation about possibly dramatic usage of certain RTT
features should be considered as a last resort, not as an ad hoc, let alone
standard, policy of the project.

Herman

[1] Even if they are just the unfortunate ones that detect the mess caused
by others.

Operation and C++ exception

On Fri, 1 Jul 2011, Sylvain Joyeux wrote:

> On 06/30/2011 06:42 PM, Herman Bruyninckx wrote:
>> - remote calls through CORBA (or any other middleware for that matter) are
>> the best way to screw up realtime determinism. If you want to do that,
>> there is no reason you should use RTT. Just do these things in another
>> framework and connect it to RTT if you need things in realtime. RTT has
>> good support to connect to other frameworks, such as ROS.
> Why in hell are you always saying that ? RTT is a perfectly good general
> purpose framework, that has features outside or realtimeness that stuff
> like ROS do NOT have (proper component model, proper threading model,
> explicit connection mechanism, multi-protocol dataflow support). So, why
> should it be limited to the realtime "niche" ?

It should not. And while I am happy that you defend RTT in this
enthusiastic way, one should not give users the impression that it is the
best solution for everything. My message is the following: Orocos wants to
be the best in realtime, and (over time) the best in clean component model
and corresponding toolchain support, but it does not pretend to be the "one
size fits all" framework. In practice, that means that it is often much
easier for some people to use a 'ready made' piece of _functionality_ that
is wrapped in a component offered by another framework, instead of spending
time in "porting" that thing to RTT, even though the latter has arguably a
much better "component model" support. Of course, I _like_ people to do
that effort, but I don't _expect_ then to do so if that is not efficient
for them in the short or medium term.

> Finally, with the advent of the operations, one can call them without
> screwing the realtime-ness of the component (only the caller is
> non-realtime, not the callee).

An operation _does_ cost something, inevitably, so it _can_ screw up _your_
specific realtime-ness. While the mentioned cost is deterministic
and can be minor, it is not zero, and it is not even O(1), certainly not
when multiple operations are applied and the "status callback" feature is
being used; and this is (in my humble opinion) what normal users of this
feature are going to do most of the time.
Going into a bit more technical detail (see
<http://www.orocos.org/stable/documentation/rtt/v2.x/doc-xml/orocos-components-manual.html#task-operations>
for the relevant documentation, thanks Peter!):
without the "callback", the operation boils down to the "stored procedure"
concept of databases
<http://en.wikipedia.org/wiki/Stored_procedure>
and that is a _very_ nice feature to have. But using it in the correct way
requires insight in the consequences of the "OwnThread" vs "ClientThread"
choices. This is advanced material, that (as experience shows) goes beyond
what can be expected from the typical "ROS user" or "CORBA user" (no insult
intended! Replace "ROS" and "CORBA" with any "easy" middleware project that
you like).

This is information that developers should be aware of. The situation that
I want to avoid is that some developers come back to us with a complaint
like: "He guys, you told us RTT was realtime safe, but look what
performance figures I have in my application...!". :-) And that's why I
keep on saying that RTT has very nice features, but they should be used
with care.

>> - exceptions (in C++ or anywhere else) are the second best way of screwing
>> realtime determinism, since it's the C++ runtime _implementation_ that
>> defines your behaviour, and that implementation's behaviour is opaque to
>> say the least.
> Not true. The C++ exception handling mechanism is very controlled by the
> C++ specification. For instance, it cannot do any memory allocation (the
> C++ exception objects can if they want to, as e.g. runtime_error).
> Moreover, it is meant for *exceptional situations*. I.e. cases that the
> normal execution (and realtime-ness properties) are guaranteed anyway
> because *you are outside of the nominal execution flow*.

If you want to do hard realtime, _you_ should control the "exceptional
situations" _explicitly_, and not rely on an opaque runtime. Not doing
memory allocation is not enough to garantee determinism; and the
determinism is, after all, defined by the _implementation_ of the
specification, and not by the specification itself. That's why I am not in
favour of exceptions.

>> Anyway, you're free to do what you like, but don't come back later
>> complaining about RTT not doing what you expect, if you use a combination
>> of C++ exceptions and CORBA method calls. I've seen big robotics projects
>> being killed that way...
> Operations are not CORBA method calls.

No, but the original poster _was_ refering explicitly to doing method calls
over CORBA, that's why I mention this here. And he _could_ use operations
without realising the above-mentioned "non-obvious, hidden costs", that's
why I refered to them.

> Operations are RTT operations.
> Period. Then, it so happens that you can call them from CORBA. I find
> the poster question to be very sound: what is the behaviour of
> exceptions w.r.t. operations in RTT ?

I do not find this a clear question at all. But that's probably due to my
lack of precise understanding of the English term "w.r.t."...

> Blocking the operation forever is definitely not "a good behaviour"

> Sylvain Joyeux
> Space& Security Robotics

Thanks for bringing up some very useful remarks.

Herman

> !!! Achtung, neue Telefonnummer!!!
>
> Standort Bremen:
> DFKI GmbH
> Robotics Innovation Center
> Robert-Hooke-Straße 5
> 28359 Bremen, Germany
>
> Phone: +49 (0)421 178-454136
> Fax: +49 (0)421 218-454150
> E-Mail: robotik [..] ...
>
> Weitere Informationen: http://www.dfki.de/robotik
> -----------------------------------------------------------------------
> Deutsches Forschungszentrum fuer Kuenstliche Intelligenz GmbH
> Firmensitz: Trippstadter Straße 122, D-67663 Kaiserslautern
> Geschaeftsfuehrung: Prof. Dr. Dr. h.c. mult. Wolfgang Wahlster
> (Vorsitzender) Dr. Walter Olthoff
> Vorsitzender des Aufsichtsrats: Prof. Dr. h.c. Hans A. Aukes
> Amtsgericht Kaiserslautern, HRB 2313
> Sitz der Gesellschaft: Kaiserslautern (HRB 2313)
> USt-Id.Nr.: DE 148646973
> Steuernummer: 19/673/0060/3
> -----------------------------------------------------------------------
>
>

--
K.U.Leuven, Mechanical Eng., Mechatronics & Robotics Research Group
<http://people.mech.kuleuven.be/~bruyninc> Tel: +32 16 328056
EURON Coordinator (European Robotics Research Network) <http://www.euron.org>
Open Realtime Control Services <http://www.orocos.org>
Associate Editor JOSER <http://www.joser.org>, IJRR <http://www.ijrr.org>

Re: Operation and C++ exception

bruyninc wrote:
and the determinism is, after all, defined by the _implementation_ of the specification, and not by the specification itself.

It's curious because i just had a training on SCADE with a trainer from Esterel. He said this quite differently.

He uses as an example the "random" function. It is predictable but non determinist (for a given set of inputs, if we use random, we can't expect a given output). So a designer that specify a system that should give some output with some input, can't introduce a random function in his design.

So i suppose our trainer would have said "the determinism is defined by the specification, then by the implementation". But i suppose that it is what every model driven advocate would have said :)

Operation and C++ exception

On Fri, 1 Jul 2011, paul [dot] chavent [..] ... wrote:

>

bruyninc wrote:

> and the
> determinism is, after all, defined by the _implementation_ of the
> specification, and not by the specification itself.

>
> It's curious because i just had a training on SCADE with a trainer from
> Esterel. He said this quite differently.
>
If you bring in the Esterel context, I have to add some terms to my claim:
it should then read as follows:
" and the time determinism is, after all, defined by the _implementation_
of the specification, and not by the specification itself."

The thread was not refering to the _logical_ determinism, which is another matter.

> He uses as an example the "random" function. It is predictable but non
> determinist (for a given set of inputs, if we use random, we can't expect
> a given output). So a designer that specify a system that should give
> some output with some input, can't introduce a random function in his
> design.
>
> So i suppose our trainer would have said "the determinism is defined by
> the specification, then by the implementation". But i suppose that it is
> what every model driven advocate would have said :)

No: he was fully correct, but his and mine "determinism" have to be
interpreted as having a hidden, context-determined adjective: "logical",
respectively "time". :-) The "model" takes care of the meaning and the
logic, the "implementation" takes care of the efficiency and execution
predictability.

Herman

Operation and C++ exception

On 06/30/2011 06:42 PM, Herman Bruyninckx wrote:
> - remote calls through CORBA (or any other middleware for that matter) are
> the best way to screw up realtime determinism. If you want to do that,
> there is no reason you should use RTT. Just do these things in another
> framework and connect it to RTT if you need things in realtime. RTT has
> good support to connect to other frameworks, such as ROS.

I'm not sure that it's true for remote calls in "ClientThread". There are no reasons for killing realtime in this case (at least the "realtime of the server").

Operation and C++ exception

On Thu, 30 Jun 2011, Paul Chavent wrote:

> On 06/30/2011 06:42 PM, Herman Bruyninckx wrote:
>> - remote calls through CORBA (or any other middleware for that matter) are
>> the best way to screw up realtime determinism. If you want to do that,
>> there is no reason you should use RTT. Just do these things in another
>> framework and connect it to RTT if you need things in realtime. RTT has
>> good support to connect to other frameworks, such as ROS.
>
> I'm not sure that it's true for remote calls in "ClientThread". There are
> no reasons for killing realtime in this case (at least the "realtime of
> the server").

I don't know this latter concept ("realtime of the server")... Realtime is
a system property, and not that of one single component.

Herman

Re: Operation and C++ exception

bruyninc wrote:
On Thu, 30 Jun 2011, Paul Chavent wrote:

I don't know this latter concept ("realtime of the server")... Realtime is a system property, and not that of one single component.

Herman

This concept means that we can have a system that is realtime, and that we can have an other system that watch this realtime system without disturbing it (a gui that display some values for example). That's what i call a server/client, but my terminology isn't the one of a robotician...

Moreover, you say that rtt is absolutely realtime, but i'am not sure that a system where some function calls can be inserted before the updateHook is easy to be proven to be periodic.

Paul.

Operation and C++ exception

On Fri, 1 Jul 2011, paul [dot] chavent [..] ... wrote:

>

bruyninc wrote:
On Thu, 30 Jun 2011, Paul Chavent wrote:
>
>
> I don't know this latter concept ("realtime of the server")... Realtime is
> a system property, and not that of one single component.
>
> Herman
>

>
>
> This concept means that we can have a system that is realtime, and that
> we can have an other system that watch this realtime system without
> disturbing it (a gui that display some values for example). That's what i
> call a server/client, but my terminology isn't the one of a robotician...

It is :-) And I understand what you mean. But this is exactly my worry: how
can you guarantee the realtime behaviour of your component if part of it is
engaging in possibly blocking interactions with another component that is
not interested in realtime? This _has_ to happen in a separate component
(that is allowed to wait) and that only has deterministic, asynchronous
interaction with the realtime component.

> Moreover, you say that rtt is absolutely realtime,

I am saying that it is a _framework_ that _allows_ hard realtime behaviour,
_if_ the application developers know what they are doing.

> but i'am not sure that a system where some function calls can be inserted
> before the updateHook is easy to be proven to be periodic.

I am very sure that it _cannot_ be _proven_ :-) That's what I say all the
time: it's not because one uses a realtime _capable_ framework that one
gets a realtime _system_, just like that... And the exceptions and
sychronous method calls that you brought up in your original post are two
of the major "realtime screw-ups" that I know. Hence my reactions.

> Paul.

Herman

Re: Operation and C++ exception

bruyninc wrote:
how can you guarantee the realtime behaviour of your component if part of it is engaging in possibly blocking interactions with another component that is not interested in realtime? This _has_ to happen in a separate component (that is allowed to wait) and that only has deterministic, asynchronous interaction with the realtime component.

Yes ! When Peter talk us about the transport during a training course i was very interesting by this aspect.

It seems that for a ClientThread operation, the code is executed on the server but in a separate thread dedicated to handle the transport. So if the developper take care to write a function that not affect the realtime of the called object (for example, only read an integer), that's win ! This is very useful to not have to handle those communication aspects.

The same thing apply to ports. The fact that the flow don't need to be continuous is very useful. I like the "pull" option of connection policy.

There are a lot of ways to kill the realtime, but there are a lot of options to try too :)...