Streamlined Execution Flow API

It started with an idea on FOSDEM. It went on as a long mail (click link for full text and discussion) on the Orocos-dev mailing list.

Here's the summary:

  • RTT interoperates badly with other software, for example, any external process needs to go through a convoluted CORBA layer. There are also no tools that could ease the job (except the ctaskbrowser), for example some small shell commands that can query/change a component.
  • RTT has remaining usability issues. Sylvain already identified the short commings of data/buffer ports and proposed a solution. But any user wrestling with the Should I use an Event (syn/asyn)-Method-Command-DataPort'?' question only got the answer: Well, we got Events(syn/asyn)-Methods-Commands and DataPorts !'. It's not coherent. There are other frameworks doing a better job. We can do a far better job.
  • RTT has issues with its current distribution implementation: programs can be constructed as such that they cause mem leaks at the remote side, Events never got into the CORBA interface (there is a reason for that), and our data ports over CORBA are equally weak as the C++ implementation.
  • And then there are also the untaken opportunities to reduce RTT & component code size drastically and remove complex features.

The pages below analyse and propose new solutions. The pages are in chronological order, so later pages represent more recent views.

First analysis

I've seen people using the RTT for inter-thread communication in two major ways: or implement a function as a Method, or as a Command. Where the command was the thread-safe way to change the state of a component. The adventurous used Events as well, but I can't say they're a huge success (we got like only one 'thank you' email in its whole existence...). But anyway, Commands are complex for newbies, Events (syn/asyn) aren't better. So for all these people, here it comes: the RTT::Message object. Remember, Methods allow a peer component to _call_ a function foo(args) of the component interface. Messages will have the meaning of _sending_ another component a message to execute a function foo(args). Contrary to Methods, Messages are 'send and forget', they return void. The only guarantee you got is, that if the receiver was active, it processed it. For now, forget that Commands exist. We have two inter- component messaging primitives now: Messages and Methods. And each component declares: You can call these methods and send these messages. They are the 'Level 0' primitives of the RTT. Any transport should support these. Note that conveniently, the transport layer may implement messages with the same primitive as data ports. But we, users, don't care. We still have Data Ports to 'broadcast' our data streams and now we have Messages as well to send directly to component X.

Think about it. The RTT would be already usable if each component only had data ports and a Message/Method interface. Ask the AUTOSAR people, it's very close to what they have (and can live with).

There's one side effect of the Message: we will need a real-time memory allocator to reserve a piece of memory for each message sent, and free it when the message is processed. Welcome TLSF. In case such a thing is not possible wanted by the user, Messages can fall back to using pre-allocated memory, but at the cost of reduced functionality (similar to what Commands can do today). Also, we'll have a MessageProcessor, which replaces and is a slimmed down version of the CommandProcessor today.

So where does this leave Events? Events are of the last primitives I explain in courses because they are so complex. They don't need to be. Today you need to attach a C/C++ function to an event and optionally specify an EventProcessor. Depending on some this-or-thats the function is executed in this-or-the-other thread. Let's forget about that. In essence, an Event is a local thing that others like to know about: Something happened 'here', who wants to know? Events can be changed such that you can say: If event 'e' happens, then call this Method. And you can say: if event 'e' happens, send me this Message. You can subscribe as many callbacks as you want. Because of the lack of this mechanism, the current Event implementation has a huge foot print. There's a lot to win here.

Do you want to allow others to raise the event ? Easy: add it to the Message or Method interface, saying: send me this Message and I'll raise the event, or call this Method and you'll raise it, respectively. But if someone can raise it, is your component's choice. That's what the event interface should look like. It's a Level 1. A transport should do no more than allowing to connect Methods and Messages (which it already supports, Level 1) to Events. No more. Even our CORBA layer could do that.

The implementation of Event can benefit from a rt_malloc as well. Indirectly. Each raised Event which causes Messages to be sent out will use the Message's rt_malloc to store the event data by just sending the Message. In case you don't have/want an rt_malloc, you fall back to what events can roughly do today. But with lots of less code ( Goodbye RTT::ConnectionC, Goodbye RTT::EventProcessor ).

And now comes the climax: Sir Command. How does he fit in the picture? He'll remain in some form, but mainly as a 'Level 2' citizen. He'll be composed of Methods, Messages and Events and will be dressed out to be no more than a wrapper, keeping related classes together or even not that. Replacing a Command with a Message hardly changes anything in the C++ side. For scripts, Commands were damn useful, but we will come up with something satisfactory. I'm sure.

How does all this interface shuffling allows us to get 'towards a sustainable distributed component model'? That's because we're seriously lowering the requirements on the transport layer:

  • It only needs to implement the Level 0 primitives. How proxies and servers are built depends on the transport. You can do so manually (dlib like) or automatically (CORBA like)
  • It allows the transport to control memory better, share it between clients and clean it up at about any time.
  • The data flow changes Sylvain proposes strengthen our data flow model and I'm betting on it that it won't use CORBA as a transport. Who knows.

And we are at the same time lowering the learning curve for new users:

  • You can easily explain the basic primitives: Properties=>XML, DataPorts=>process data, Methods/Messages=>client/server requests. When they're familiar with these, they can start playing with Events (which build on top of Method/Messages and play a role in DataPorts as well). And finally, if they'll ever need, the Convoluted Command can encompass the most complex scenarios.
  • You can more easily connect with other middleware or external programs. People with other middleware will see the opportunities for 1-to-1 mappings or even implement it as a transport in the RTT.

Dissecting Command and Method: blocking/non-blocking vs synchronous/asynchronous

(Please feel free to edit/comment etc. This is a community document, not a personal document)

Notes on naming

The word service is used to name the offering of a C/C++ function for others to call. Today in Orocos Components offer services in the form of 'RTT::Method' or 'RTT::Command' objects. Both lead to the execution of a function, but in a different way. Also, despite the title, it is advised to refrain from using the terms synchronous/asynchronous, because they are relative terms and may cause confusion if the context is not clear.

An alternative naming is possible: the offering of a C/C++ function could be named 'operation' and the collection of a given set of operations in an interface could be called a 'service'. This definition would line up better with service oriented architectures like OSGi.

Purpose

This page collects the ideas around the new primitives that will replace/enhance Method and/or Command. Although Method is a clearly understood primitive by users, Command isn't because of its multi-threaded nature. It is too complex to setup/use and can lead to unsafe applications (segfaults) if used incorrectly. To get these primitives better, we re-look at what users want to do and how to map this to RTT primitives.

What users want to do

Users want to control which thread executes which function, and if they want to wait(block) on the result or not. This all in order to meet deadlines in real-time systems. In practice, this boils down to:

  • When calling services (ie functions) of other components, one may opt to wait until the service returns the result, or not and optionally collect the result later. This is often best decided at the caller side, because both cases will cause different client code for sending/receiving the results
  • When implementing services in a component, the component may decide that the caller's thread executes the function, or that it will execute the function in it's own thread. Clearly, this can only be decided at the receiver side, because both cases will cause a different implementation of the function to be executed. Especially with respect to thread-safety.

Dissecting the cases

When putting the above in a table, you get:
Calling a service (a function)
Wait? \ Thread? Caller Component
Yes (Method) (?)
No X (Command)

For reference, the current RTT 1.x primitives are shown. There are two remarkable spots: the X and the (?).

  • The X is a practically impossible situation. It would involve that the client thread does not wait, but its thread still executes the function. This could only be resolved if a 'third' thread executes the service on behalf of the caller. It is unclear at which priority this thread should execute, what it's lifetime and exclusivity is and so on.
  • The (?) marks a hole in the current RTT API. Users could only implement this behaviour by busy-waiting on the Command's done() function. However, that is disastrous in real-time systems, because of starvation or priority inversion issues that crop up with such techniques.

Another thing you should be aware of that in the current implementation, caller and component must agree on how the service is invoked. If the Component defines a Method, the caller must execute it in its own thread and wait for the result. There's no other way for the caller to deviate from this. In practice, this means that the component's interface dictates how the caller can use its services. This is consistent with how UML defines operations, but other frameworks, like ICE, allow any function part of the interface to be called blocking or non-blocking. Clearly, ICE has some kind of thread-pool behind the scenes that does the dispatching and collects the results on behalf of the caller.

Backwards compatibility - Or how it is now

Orocos users have written many components and the primary idea of RTT 2.0 is to solve issues these components still have due to defects in the current RTT 1.x design. Things that do work satisfactory should keep working without modification of the user's design.

Method

It is very likely that the RTT::Method primitive will remain to exist as it is today. Little problems have been reported and it is easy to understand. The only disadvantage is that it can not be called 'asynchronously'. For example: if a component defines a Method, but the caller does not have the resources to invoke it (due to a deadline), it needs to setup a separate thread to do the call on its behalf. This is error prone. Orocos users often solve this by defining a command and trying to get the result data back somehow (also error prone).

Command

Commands serve multiple purposes in today programming with Orocos.
  • First, they allow thread-safe execution of a piece of code in a component. Because the component thread executes the function, no locking or synchronization primitives are required.
  • Second, they allow a caller to dispatch work to another component, in case the caller does not have the time or resources to execute a function.
  • Third, they allow to track the status of the execution. The caller can poll to see if the function has been queued, executed, what it returned (a boolean) etc.
  • Fourth, they allow to track the status of the 'effect' of the command, past its execution. This is done by attaching a completion condition, which returns a bool and can indicate if the effect of the command has been completed or not. For example, if the command is to move to a position, the completion condition would return true if the position is reached, while the command function would have only programmed the interpolator to reach that position. Completion conditions are not that much used, and must be polled.

A simpler form of Command will be provided that does not contain the completion condition. It is too seldomly used.

It is to the proposals to show how to emulate the old behavior with the new primitives.

Proposals

Each proposal should try to solve these issues:

The ability to let caller and component choose which execution semantics they want when calling or offering a service (or motivate why a certain choice is limited):

  • The ability to wait for a service to be completed
  • The ability to invoke a service and not wait for the result
  • The ability to specify in the component implementation if a function is executed in the component's thread
  • The ability to specify in the component implementation if a function is executed in the caller's thread

And regarding easy use and backwards compatibility:

  • Show how old-time behavior can be emulated with the new proposal
  • Show which semantics changed
  • How these primitives will be used in the scripting languages and in C++

And finally:

  • Define proper names for each behavior.

Proposal 1: Method/Message

This is one of the earliest proposals. It proposes to keep Method as-is, remove Command and replace it with a new primitive: RTT::Message. The Message is a stripped Command. It has no completion condition and is send-and-forget. One can not track the status or retrieve arguments. It also uses a memory manager to allow to invoke the same Message object multiple times with different data.

Emulating a completion condition is done by defining the completion condition as a Method in the component interface and requiring that the sender of the Message checks that Method to evaluate progress. In scripting this becomes:

// Old:
  do comp.command("hello"); // waits (polls) here until complete returns true
 
// New: Makes explicit what above line does:
  do comp.message("hello"); // proceeds immediately
  while ( comp.message_complete("hello") == false ) // polling
     do nothing;

In C++, the equivalent is slightly different:

// Old:
  if ( command("hello") ) {
     //... user specific logic that checks command.done() 
  }
 
// New:
  if ( message("hello") ) { // send and forget, returns immediately
     // user specifc logic that checks message_complete("hello")
  }

Users have indicated that they also wanted to be able to specify in C++:

  message.wait("hello"); // send and block until executed.

It is not clear yet how the wait case can be implemented efficiently.

The user visible object names are:

  • RTT::Method to add a 'client thread' C/C++ function to the component interface or call one.
  • RTT::Message to add a 'component thread' C/C++ function to the component interface or call one.

This proposal solves:

  • A simpler replacement for Command
  • Acceptable emulation capacities of old user code
  • The invocation of multiple times the same message object in a row.

This proposal omits:

  • The choice of caller/component to choose independently
  • Solving case 'X' (see above)
  • How message.wait() can be implemented

Other notes:

  • It has been mentioned that 'Message' is not a good and too confusing name.

Proposal 2: Method/Service

This proposal focuses on separating the definition of a Service (component side) from the calling of a Method (caller side).

The idea is that components only define services, and assign properties to these services. The main properties to toggle are 'executed in my thread or callers thread, or even another thread'. But other properties could be added too. For example: a 'serialized' property which causes the locking of a (recursive!) mutex during the execution of the service. The user of the service can not and does not need to know how these properties are set. He only sees a list of services in the interface.

It is the caller that chooses how to invoke a given service: waiting for the result ('call') or not ('send'). If he doesn't want to wait, he has the option to collect the results later ('collect'). The default is blocking ('call'). Note that this waiting or not is completely independent of how the service was defined by the component, the framework will choose a different 'execution' implementation depending on the combination of the properties of service and caller.

This means that this proposal allows to have all four quadrants of the table above. This proposal does not detail yet how to implement case (X) though, which requires a 3rd thread to do the actual execution of the service (neither component nor caller wish to do execute the C function).

This would result in the following scripting code on caller side:

//Old:
  do comp.the_method("hello");
 
//New:
  do comp.the_service.call("hello"); // equivalent to the_method.
 
//Old:
  do comp.the_command("hello");
 
//New:
  do comp.the_service.send("hello"); // equivalent to the_command, but without completion condition.

This example shows two use cases for the same 'the_service' functionality. The first case emulates an RTT 1.x method. It is called and the caller waits until the function has been executed. You can not see here which thread effectively executes the call. Maybe it's 'comp's thread, in which case the caller's thread is blocking until it the function is executed. Maybe it's the caller's thread, in which case it is effectively executing the function. The caller doesn't care actually. The only thing that has effect is that it takes a certain amount of time to complete the call, *and* that if the call returns, the function has been effectively executed.

The second case is emulating an RTT 1.x command. The send returns immediately and there is no way in knowing when the function has been executed. The only guarantee you have is that the request arrived at the other side and bar crashes and infinite loops, will complete some time in the future.

A third example is shown below where another service is used with a 'send' which returns a result. The service takes two arguments: a string and a double. The double is the answer of the service, but is not yet available when the send is done. So the second argument is just ignored during the send. A handle 'h' is returned which identifies your send request. You can re-use this handle to collect the results. During collection, the first argument is now ignored, and the second argument is filled in with the result of the service. Collection may be blocking or not.

//New, with collecting results:
  var double ignored_result, result;
 
  set h = comp.other_service.send("hello", ignored_result);
 
  // some time later :
  comp.other_service.collect(h, "ignored", result); // blocking !
 
  // or poll for it:
  if ( comp.other_service.collect_if_done( h, "ignored", result ) == true ) then {
     // use result...
  }

In C++ the above examples are written as:

//New calling:
  the_service.call("hello", result); // also allowed: the_service("hello", result);
 
//New sending:
  the_service.send("hello", ignored_result);
 
//New sending with collecting results:
  h = other_service.send("hello", ignored_result);
 
  // some time later:
  other_service.collect(h, "ignored", result); // blocking !
 
  // or poll for it:
  if ( other_service.collect_if_done( h, "ignored", result ) == true ) {
     // use result...
  }

Completion condition emulation is done like in Proposal 1.

The definition of the service happens at the component's side. The component decides for each service if it is executed in his thread or the callers thread:

  // by default creates a service executed by caller, equivalent to defining a RTT 1.x Method  
  RTT::Service the_service("the_service", &foo_service );
 
  // sets the service to be executed by the component's thread, equivalent to Command
  the_service.setExecutor( this );
 
  //above in one line:
  RTT::Service the_service("the_service", &foo_service, this );

The user visible object names are:

  • RTT::Service to add a C/C++ function to the component interface (replaces use of Method/Command).
  • RTT::CallMethod or similar to call a service, please discuss a good/better name.
  • RTT::SendMethod or similar to send (and collect results from) a service, please discuss a good/better name.

This proposal solves:

  • Allows to specify threading parameters in the component independent of call/send semantics.
  • Removes user method/command dilemma.
  • Aligns better with 3rd party frameworks that also offer 'services'.

This proposal omits:

  • How collection semantics are exactly.
  • How to resolve a 'send' with a 'service executed in thread of caller' (case X). Should a send indicate which thread must do the send on its behalf ? Is the execution deferred in another point in time in the caller's thread ?

Your Proposal here

...

Provides vs Requires interfaces

Users can express the 'provides' interface of an Orocos Component. However, there is no easy way to express which other components a component requires. The notable exception is data flow ports, which have in-ports (requires) and out-ports (provides). It is however not possible to express this requires interface for the execution flow interface, thus for methods, commands/messages and events. This omission makes the component specification incomplete.

One of the first questions raised is if this must be expressed in C++ or during 'modelling'. That is, UML can express the requires dependency, so why should the C++ code also contain it in the form of code ? It should only contain it if you can't generate code from your UML model. Since this is not yet available for Orocos components, there is no other choice than expressing it in C++.

A requires interface specification should be optional and only be present for:

  • completing the component specification, allowing better review and understanding
  • automatically connecting component 'execution' interfaces, such that the manual lookup work which you need to write today can be omitted.

We apply this in code examples to various proposed primitives in the pages below.

New Command API

Commands are no longer a part of the TaskContext API. They are helper classes which replicate the old RTT 1.0 behaviour. In order to setup commands more easily, it is allowed to register them as a 'requires()' interface.

This is all very experimental.

/**
 * Provider of a Message with command-like semantics
 */
class TaskA    : public TaskContext
{
    Message<void(double)>   message;
    Method<bool(double)>    message_is_done;
    Event<void(double)>     done_event;
 
    void mesg(double arg1) {
        return;
    }
 
    bool is_done(double arg1) {
        return true;
    }
 
public:
 
    TaskA(std::string name)
        : TaskContext(name),
          message("Message",&TaskA::mesg, this),
          message_is_done("MessageIsDone",&TaskA::is_done, this),
          done_event("DoneEvent")
    {
        this->provides()->addMessage(&message, "The Message", "arg1", "Argument 1");
        this->provides()->addMethod(&method, "Is the Message done?", "arg1", "Argument 1");
        this->provides()->addEvent(&done_event, "Emited when the Message is done.", "arg1", "Argument 1");
    }
 
};
 
class TaskB   : public TaskContext
{
    // RTT 1.0 style command object
    Command<bool(double)>   command1;
    Command<bool(double)>   command2;
 
public:
 
    TaskB(std::string name)
        : TaskContext(name),
          command1("command1"),
          command2("command2")
    {
        // the commands are now created client side, you
        // can not add them to your 'provides' interface
        command1.useMessage("Message");
        command1.useCondition("MessageIsDone");
        command2.useMessage("Message");
        command2.useEvent("DoneEvent");
 
        // this allows automatic setup of the command.
        this->requires()->addCommand( &command1 );
        this->requires()->addCommand( &command2 );
    }
 
    bool configureHook() {
        // setup is done during deployment.
        return command1.ready() && command2.ready();
    }
 
    void updateHook() {
        // calls TaskA:
        if ( command1.ready() && command2.ready() )
            command1( 4.0 );
        if ( command1.done() && command2.ready() )
            command2( 1.0 );
    }
};
 
int ORO_main( int, char** )
{
    // Create your tasks
    TaskA ta("Provider");
    TaskB tb("Subscriber");
 
    connectPeers(ta, tb);
    // connects interfaces.
    connectInterfaces(ta, tb);
    return 0;
}

New Event API

The idea of the new Event API is that: 1. only the owner of the event can emit the event (unless the event is also added as a Method or Message) 2. Only methods or message objects can subscribe to events.

/**
 * Provider of Event
 */
class TaskA    : public TaskContext
{
    Event<void(string)>   event;
 
public:
 
    TaskA(std::string name)
        : TaskContext(name),
          event("Event")
    {
        this->provides()->addEvent(&event, "The Event", "arg1", "Argument 1");
        // OR:
        this->provides("FooInterface")->addEvent(&event, "The Event", "arg1", "Argument 1");
 
        // If you want the user to let him emit the event:
        this->provides()->addMethod(&event, "Emit The Event", "arg1", "Argument 1");
    }
 
    void updateHook() {
        event("hello world");
    }
};
 
/**
 * Subscribes a local Method and a Message to Event
 */
class TaskB   : public TaskContext
{
    Message<void(string)>   message;
    Method<void(string)>    method;
 
    // Message callback
    void mesg(double arg1) {
        return;
    }
 
    // Method callback
    int meth(double arg1) {
        return 0;
    }
 
public:
 
    TaskB(std::string name)
        : TaskContext(name),
          message("Message",&TaskB::mesg, this),
          method("Method",&TaskB::meth, this)
    {
        // optional:
        // this->provides()->addMessage(&message, "The Message", "arg1", "Argument 1");
        // this->provides()->addMethod(&method, "The Method", "arg1", "Argument 1");
 
        // subscribe to event:
        this->requires()->addCallback("Event", &message);
        this->requires()->addCallback("Event", &method);
 
        // OR:
        // this->provides("FooInterface")->addMessage(&message, "The Message", "arg1", "Argument 1");
        // this->provides("FooInterface")->addMethod(&method, "The Method", "arg1", "Argument 1");
 
        // subscribe to event:
        this->requires("FooInterface")->addCallback("Event", &message);
        this->requires("FooInterface")->addCallback("Event", &method);
    }
 
    bool configureHook() {
        // setup is done during deployment.
        return message.ready() && method.ready();
    }
 
    void updateHook() {
        // we only receive
    }
};
 
int ORO_main( int, char** )
{
    // Create your tasks
    TaskA ta("Provider");
    TaskB tb("Subscriber");
 
    connectPeers(ta, tb);
    // connects interfaces.
    connectInterfaces(ta, tb);
    return 0;
}

New Message API

This use case shows how one can use messages in the new API. The unchanged method is added for comparison. Note that I have also added the provides() and requires() mechanism such that the RTT 1.0 construction:

  method = this->getPeer("PeerX")->getMethod<int(double)>("Method");

is no longer required. The connection is made similar as data flow ports are connected.

/**
 * Provider
 */
class TaskA    : public TaskContext
{
    Message<void(double)>   message;
    Method<int(double)>     method;
 
    void mesg(double arg1) {
        return;
    }
 
    int meth(double arg1) {
        return 0;
    }
 
public:
 
    TaskA(std::string name)
        : TaskContext(name),
          message("Message",&TaskA::mesg, this),
          method("Method",&TaskA::meth, this)
    {
        this->provides()->addMessage(&message, "The Message", "arg1", "Argument 1");
        this->provides()->addMethod(&method, "The Method", "arg1", "Argument 1");
        // OR:
        this->provides("FooInterface")->addMessage(&message, "The Message", "arg1", "Argument 1");
        this->provides("FooInterface")->addMethod(&method, "The Method", "arg1", "Argument 1");
    }
 
};
 
class TaskB   : public TaskContext
{
    Message<void(double)>   message;
    Method<int(double)>     method;
 
public:
 
    TaskB(std::string name)
        : TaskContext(name),
          message("Message"),
          method("Method")
    {
        this->requires()->addMessage( &message );
        this->requires()->addMethod( &method );
        // OR:
        this->requires("FooInterface")->addMessage( &message );
        this->requires("FooInterface")->addMethod( &method );
    }
 
    bool configureHook() {
        // setup is done during deployment.
        return message.ready() && method.ready();
    }
 
    void updateHook() {
        // calls TaskA:
        method( 4.0 );
        // sends two messages:
        message( 1.0 );
        message( 2.0 );
    }
};
 
int ORO_main( int, char** )
{
    // Create your tasks
    TaskA ta("Provider");
    TaskB tb("Subscriber");
 
    connectPeers(ta, tb);
    // connects interfaces.
    connectInterfaces(ta, tb);
    return 0;
}

New Method, Operation, Service API

This page shows some use cases on how to use the newly proposed services classes in RTT 2.0.

WARNING: This page assumes the reader has familiarity with the current RTT 1.x API.

First, we introduce the new classes that would be added to the RTT:

#include <rtt/TaskContext.hpp>
#include <string>
 
using RTT::TaskContext;
using std::string;
 
/**************************************
 * PART I: New Orocos Classes
 */
 
/**
 * An operation is a function a component offers to do.
 */
template<class T>
class Operation {};
 
/**
 * A Service collects a number of operations.
 */
class ServiceProvider {
public:
    ServiceProvider(string name, TaskContext* owner);
};
 
/**
 * Is the invocation of an Operation.
 * Methods can be executed blocking or non blocking,
 * in the latter case the caller can retrieve the results
 * later on.
 */
template<class T>
class Method {};
 
/**
 * A ServiceRequester collects a number of methods
 */
class ServiceRequester {
public:
    ServiceRequester(string name, TaskContext* owner);
 
    bool ready();
};

What is important to notice here is the symmetry:

 (Operation, ServiceProvider) <-> (Method, ServiceRequester).
The left hand side is offering services, the right hand side is using the services.

First we define that we provide a service. The user starts from his own C++ class with virtual functions. This class is then implemented in a component. A helper class ties the interface to the RTT framework:

/**************************************
 * PART II: User code for PROVIDING a service
 */
 
/**
 * Example Service as abstract C++ interface (non-Orocos).
 */
class MyServiceInterface {
public:
    /**
     * Description.
     * @param name Name of thing to do.
     * @param value Value to use.
     */
    virtual int foo_function(std::string name, double value) = 0;
 
    /**
     * Description.
     * @param name Name of thing to do.
     * @param value Value to use.
     */
    virtual int bar_service(std::string name, double value) = 0;
};
 
/**
 * MyServiceInterface exported as Orocos interface.
 * This could be auto-generated from reading MyServiceInterface.
 *
 */
class MyService {
protected:
    /**
     * These definitions are not required in case of 'addOperation' below.
     */
    Operation<int(const std::string&,double)> operation1;
    Operation<int(const std::string&,double)> operation2;
 
    /**
     * Stores the operations we offer.
     */
    ServiceProvider provider;
public:
    MyService(TaskContext* owner, MyServiceInterface* service)
    : provider("MyService", owner),
      operation1("foo_function"), operation2("bar_service")
    {
                // operation1 ties to foo_function and is executed in caller's thread.
        operation1.calls(&MyServiceInterface::foo_function, service, Service::CallerThread);
        operation1.doc("Description", "name", "Name of thing to do.", "value", "Value to use.");
                provider.addOperation( operation1 );
 
        // OR: (does not need operation1 definition above)
        // Operation executed by caller's thread:
        provider.addOperation("foo_function", &MyServiceInterface::foo_function, service, Service::CallerThread)
                .doc("Description", "name", "Name of thing to do.", "value", "Value to use.");
 
        // Operation executed in component's thread:
        provider.addOperation("bar_service", &MyServiceInterface::bar_service, service, Service::OwnThread)
                .doc("Description", "name", "Name of thing to do.", "value", "Value to use.");
    }
};

Finally, any component is free to provide the service defined above. Note that it shouldn't be that hard to autogenerate most of the above code.

/**
 * A component that implements and provides a service.
 */
class MyComponent : public TaskContext, protected MyServiceInterface
{
    /**
     * The class defined above.
     */
    MyService serv;
public:
    /**
     * Just pass on TaskContext and MyServiceInterface pointers:
     */
    MyComponent() : TaskContext("MC"), serv(this,this)
    {
 
    }
 
protected:
    // Implements MyServiceInterface
    int foo_function(std::string name, double value)
    {
        //...
        return 0;
    }
    // Implements MyServiceInterface
    int bar_service(std::string name, double value)
    {
        //...
        return 0;
    }
};

The second part is about using this service. It creates a ServiceRequester object that stores all the methods it wants to be able to call.

Note that both ServiceRequester below and ServiceProvider above have the same name "MyService". This is how the deployment can link the interfaces together automatically.

/**************************************
 * PART II: User code for REQUIRING a service
 */
 
/**
 * We need something like this to define which services
 * our component requires.
 * This class is written explicitly, but it can also be done
 * automatically, as the example below shows.
 *
 * If possible, this class should be generated too.
 */
class MyServiceUser {
    ServiceRequester rservice;
public:
    Method<int(const string&, double)> foo_function;
    MyServiceUser( TaskContext*  owner )
    : rservice("MyService", owner), foo_function("foo_function")
      {
        rservice.requires(foo_function);
      }
};
 
/**
 * Uses the MyServiceUser helper class.
 */
class UserComponent2 : public TaskContext
{
    // also possible to (privately) inherit from this class.
    MyServiceUser mserv;
public:
    UserComponent2() : TaskContext("User2"), mserv(this)
    {
    }
 
    bool configureHook() {
        if ( ! mserv->ready() ) {
            // service not ready
            return false;
        }
    }
 
    void updateHook() {
        // blocking:
        mserv.foo_function.call("name", 3.14);
        // etc. see updateHook() below.
    }
};

The helper class can again be omitted, but the Method<> definitions must remain in place (in contrast, the Operation<> definitions for providing a service could be omitted).

The code below also demonstrates the different use cases for the Method object.

/**
 * A component that uses a service.
 * This component doesn't need MyServiceUser, it uses
 * the factory functions instead:
 */
class UserComponent : public TaskContext
{
    // A definition like this must always be present because
    // we need it for calling. We also must provide the function signature.
    Method<int(const string&, double)> foo_function;
public:
    UserComponent() : TaskContext("User"), foo_function("foo_function")
    {
        // creates this requirement automatically:
        this->requires("MyService")->add(&foo_function);
    }
 
    bool configureHook() {
        if ( !this->requires("MyService")->ready() ) {
            // service not ready
            return false;
        }
    }
 
    /**
     * Use the service
     */
    void updateHook() {
        // blocking:
        foo_function.call("name", 3.14);
        // short/equivalent to call:
        foo_function("name", 3.14);
 
        // non blocking:
        foo_function.send("name", 3.14);
 
        // blocking collect of return value of foo_function:
        int ret = foo_function.collect();
 
        // blocking collect of any arguments of foo_function:
        string ret1; double ret2;
        int ret = foo_function.collect(ret1, ret2);
 
        // non blocking collect:
        int returnval;
        if ( foo_function.collectIfDone(ret1,ret2,returnval) ) {
            // foo_function was done. Any argument that needed updating has
            // been updated.
        }
    }
};

Finally, we conclude with an example of requiring the same service multiple times, for example, for controlling two stereo-vision cameras.

/**
 * Multi-service case: use same service multiple times.
 * Example: stereo vision with two cameras.
 */
class UserComponent3 : public TaskContext
{
    // also possible to (privately) inherit from this class.
    MyVisionUser vision;
public:
    UserComponent3() : TaskContext("User2"), vision(this)
    {
        // requires a service exactly two times:
        this->requires(vision)["2"];
        // OR any number of times:
        // this->requires(vision)["*"];
        // OR range:
        // this->requires(vision)["0..2"];
    }
 
    bool configureHook() {
        if ( ! vision->ready() ) {
            // only true if both are ready.
            return false;
        }
 
    }
 
    void updateHook() {
        // blocking:
        vision[0].foo_function.call("name", 3.14);
        vision[1].foo_function.call("name", 3.14);
        // or iterate:
        for(int i=0; i != vision.interfaces(); ++i)
            vision[i].foo_function.call("name",3.14);
        // etc. see updateHook() above.
 
        /* Scripting equivalent:
         * for(int i=0; i != vision.interfaces(); ++i)
         *   do vision[i].foo_function.call("name",3.14);
         */
    }
};