For upgrading, we have:
More details are split into several child pages.
RTT 2.0 has unified events, commands and methods in the Operation interface.
This is how a function is added to the component interface:
#include <rtt/Operation.hpp>; using namespace RTT; class MyTask : public RTT::TaskContext { public: string getType() const { return "SpecialTypeB" } // ... MyTask(std::string name) : RTT::TaskContext(name), { // Add the a C++ method to the operation interface: addOperation( "getType", &MyTask::getType, this ) .doc("Read out the name of the system."); } // ... }; MyTask mytask("ATask");
The writer of the component has written a function 'getType()' which returns a string that other components may need. In order to add this operation to the Component's interface, you use the TaskContext's addOperation function. This is a short-hand notation for:
// Add the C++ method to the operation interface: provides()->addOperation( "getType", &MyTask::getType, this ) .doc("Read out the name of the system.");
Meaning that we add 'getType()' to the component's main interface (also called 'this' interface). addOperation takes a number of parameters: the first one is always the name, the second one a pointer to the function and the third one is the pointer to the object of that function, in our case, MyTask itself. In case the function is a C function, the third parameter may be omitted.
If you don't want to polute the component's this interface, put the operation in a sub-service:
// Add the C++ method objects to the operation interface: provides("type_interface") ->addOperation( "getType", &MyTask::getType, this ) .doc("Read out the name of the system.");
The code above dynamically created a new service object 'type_interface' to which one operation was added: 'getType()'. This is similar to creating an object oriented interface with one function in it.
Your code needs a few things before it can call a component's operation:
Combining these three givens, we must create an OperationCaller object that will manage our call to 'getType':
#include <rtt/OperationCaller.hpp> //... // In some other component: TaskContext* a_task_ptr = getPeer("ATask"); // create a OperationCaller<Signature> object 'getType': OperationCaller<string(void)> getType = a_task_ptr->getOperation("getType"); // lookup 'string getType(void)' // Call 'getType' of ATask: cout << getType() <<endl;
A lot of work for calling a function no ? The advantages you get are these:
var string result = ""; set result = ATask.getType();
// Add the C++ method to the operation interface: // Execute function in component's thread: provides("type_interface") ->addOperation( "getType", &MyTask::getType, this, OwnThread ) .doc("Read out the name of the system.");
So this causes that when getType() is called, it gets queued for execution in the ATask component, is executed by its ExecutionEngine, and when done, the caller will resume. The caller (ie the OperationCaller object) will not notice this change of execution path. It will wait for the getType function to complete and return the results.
// This first part is equal to the example above: #include <rtt/OperationCaller.hpp> //... // In some other component: TaskContext* a_task_ptr = getPeer("ATask"); // create a OperationCaller<Signature> object 'getType': OperationCaller<string(void)> getType = a_task_ptr->getOperation("getType"); // lookup 'string getType(void)' // Here it is different: // Send 'getType' to ATask: SendHandle<string(void)> sh = getType.send(); // Collect the return value 'some time later': sh.collect(); // blocks until getType() completes cout << sh.retn() <<endl; // prints the return value of getType().
Other variations on the use of SendHandle are possible, for example polling for the result or retrieving more than one result if the arguments are passed by reference. See the Component Builder's Manual for more details.
RTT 2.0 has a more powerful, simple and flexible system to exchange data between components.
Every instance of ReadDataPort and ReadBufferPort must be renamed to 'InputPort' and every instance of WriteDataPort and WriteBufferPort must be renamed to OutputPort. 'DataPort' and 'BufferPort' must be renamed according to their function.
The rtt2-converter tool will do this renaming for you, or at least, make its best guess.
InputPort and OutputPort have a read() and a write() function respectively:
using namespace RTT; double data; InputPort<double> in("name"); FlowStatus fs = in.read( data ); // was: Get( data ) or Pull( data ) in 1.x OutputPort<double> out("name"); out.write( data ); // was: Set( data ) or Push( data ) in 1.x
As you can see, Get() and Pull() are mapped to read(), Set() and Push() to write(). read() returns a FlowStatus object, which can be NoData, OldData, NewData. write() does not return a value (send and forget).
Writing to a not connected port is not an error. Reading from a not connected (or never written to) port returns NoData.
Your component can no longer see if a connection is buffered or not. It doesn't need to know. It can always inspect the return value of read() to see if a new data sample arrived or not. In case multiple data samples are ready to read in a buffer, read() will fetch each sample in order and each time return NewData, until the buffer is empty, in which case it returns the last data sample read with 'OldData'.
If data exchange is buffered or not is now fixed by 'Connection Policies', or 'RTT::ConnPolicy' objects. This allows you to be very flexible on how components are connected, since you only need to specify the policy at deployment time. It is possible to define a default policy for each input port, but it is not recommended to count on a certain default when building serious applications. See the 'RTT::ConnPolicy' API documentation for which policies are available and what the defaults are.
The DeploymentComponent has been extended such that it can create new-style connections. You only need to add sections to your XML files, you don't need to change existing ones. The sections to add have the form:
<!-- You can set per data flow connection policies --> <struct name="SensorValuesConnection" type="ConnPolicy"> <!-- Type is 'shared data' or buffered: DATA: 0 , BUFFER: 1 --> <simple name="type" type="short"><value>1</value></simple> <!-- buffer size is 12 --> <simple name="size" type="short"><value>12</value></simple> </struct> <!-- You can repeat this struct for each connection below ... -->
Where 'SensorValuesConnection' is a connection between data flow ports, like in the traditional 1.x way.
Consult the deployment component manual for all allowed ConnPolicy XML options.
std::vector<double> joints(10, 0.0); OutputPort<std::vector<double> > out("out"); out.setDataSample( joints ); // initialises all current and future connections to hold a vector of size 10. // modify joint values... add connections etc. out.write( joints ); // always hard real-time if joints.size() <= 10
As the example shows, a single call to setDataSample() is enough. This is not the same as write() ! A write() will deliver data to each connected InputPort, a setDataSample() will only initialize the connections, but no actual writing is done. Be warned that setDataSample() may clear all data already in a connection, so it is better to call it before any data is written to the OutputPort.
In case your data type is always hard real-time copyable, there is no need to call setDataSample. For example:
KDL::Frame f = ... ; // KDL::Frame never (de-)allocates memory during copy or construction. OutputPort< KDL::Frame > out("out"); out.write( f ); // always hard real-time
This page lists the renamings/relocations done on the RTT 2.0 branch (available through gitorious on http://www.gitorious.org/orocos-toolchain/rtt/commits/master) and also offers the conversion scripts to do the renaming.
A note about headers/namespaces: If a header is in rtt/extras, the namespace will be RTT::extras and vice versa. A header in rtt/ has namespace RTT. Note: the OS namespace has been renamed to lowercase os. The Corba namespace has been renamed to lowercase corba.
mv to-rtt-2.0.pl.txt to-rtt-2.0.pl chmod a+x to-rtt-2.0.pl ./to-rtt-2.0.pl $(find . -name "*.cpp" -o -name "*.hpp")
Minor manual fixes may be expected after running this script. Be sure to have your sources version controlled, such that you can first test what the script does before permanently changing files.
tar xjf rtt2-converter-1.1.tar.bz2 cd rtt2-converter-1.1 make ./rtt2-converter Component.hpp Component.cpp
The script takes preferably both header and implementation of your component, but will also accept a single file. It needs both class definition and implementation to make its best guesses on how to convert. If all your code is in a .hpp or .cpp file, you only need to specify that file. If nothing is to be done, the file will remain the same, so you may 'accidentally' feed non-Orocos files, or a file twice.
To run this on a large codebase, you can do something similar to:
# Calls : ./rtt2-converter Component.hpp Component.cpp for each file in orocos-app for i in $(find /home/user/src/orocos-app -name "*.cpp"); do ./rtt2-converter $(dirname $i)/$(basename $i cpp)hpp $i; done # Calls : ./rtt2-converter Component.cpp for each .cpp file in orocos-app for i in $(find /home/user/src/orocos-app -name "*.cpp"); do ./rtt2-converter $i; done # Calls : ./rtt2-converter Component.hpp for each .hpp file in orocos-app for i in $(find /home/user/src/orocos-app -name "*.hpp"); do ./rtt2-converter $i; done
RTT 1.0 | RTT 2.0 | Comments |
RTT::PeriodicActivity | RTT::extras::PeriodicActivity | Use of RTT::Activity is prefered |
RTT::Timer | RTT::os::Timer | |
RTT::SlaveActivity, SequentialActivity, SimulationThread, IRQActivity, FileDescriptorActivity, EventDrivenActivity, SimulationActivity, ConfigurationInterface, Configurator, TimerThread | RTT::extras::... | EventDrivenActivity has been removed. |
RTT::OS::SingleThread, RTT::OS::PeriodicThread | RTT::os::Thread | Can do periodic and non-periodic and switch at run-time. |
RTT::TimeService | RTT::os::TimeService | |
RTT::DataPort,BufferPort | RTT::InputPort,RTT::OutputPort | Buffered/unbuffered is decided upon connection time. Only input/output is hardcoded. |
RTT::types() | RTT::types::Types() | The function name collided with the namespace name |
RTT::Toolkit* | RTT::types::Typekit* | More logical name |
RTT::Command | RTT::Operation | Create an 'OwnThread' operation type |
RTT::Method | RTT::Operation | Create an 'ClientThread' operation type |
RTT::Event | RTT::internal::Signal | Events are replaced by OutputPort or Operation, the Signal class is a synchonous-only callback manager. |
commands()->getCommand<T>() | provides()->getOperation() | get a provided operation, no template argument required |
commands()->addCommand() | provides()->addOperation().doc("Description") | add a provided operation, document using .doc("doc").doc("a1","a1 doc")... |
methods()->getMethod<T>() | provides()->getOperation() | get a provided operation, no template argument required |
methods()->addMethod() | provides()->addOperation().doc("Description") | add a provided operation, document using .doc("doc").doc("a1","a1 doc")... |
attributes()->getAttribute<T>() | provides()->getAttribute() | get a provided attribute, no template argument required |
attributes()->addAttribute(&a) | provides()->addAttribute(a) | add a provided attribute, passed by reference, can now also add a normal member variable. |
properties()->getProperty<T>() | provides()->getProperty() | get a provided property, no template argument required |
properties()->addProperty(&p) | provides()->addProperty(p).doc("Description") | add a provided property, passed by reference, can now also add a normal member variable. |
events()->getEvent<T>() | ports()->getPort() OR provides()->getOperation<T>() | Event<T> was replaced by OutputPort<T> or Operation<T> |
ports()->addPort(&port, "Description") | ports()->addPort( port ).doc("Description") | Takes argument by reference and documents using .doc("text"). |
RTT 1.0 | RTT 2.0 | Comments |
scripting() | getProvider<Scripting>("scripting") | Returns a RTT::Scripting object. Also add #include <rtt/scripting/Scripting.hpp> |
RTT 1.0 | RTT 2.0 | Comments |
marshalling() | getProvider<Marshalling>("marshalling") | Returns a RTT::Marshalling object. Also add #include <rtt/marsh/Marshalling.hpp> |
RTT::Marshaller | RTT::marsh::MarshallingInterface | Normally not needed for normal users. |
RTT::Demarshaller | RTT::marsh::DemarshallingInterface | Normally not needed for normal users. |
RTT 1.0 | RTT 2.0 | Comments |
RTT::Corba::* | RTT::corba::C* | Each proxy class or idl interface starts with a 'C' to avoid confusion with the same named RTT C++ classes |
RTT::Corba::ControlTaskServer | RTT::corba::TaskContextServer | renamed for consistency. |
RTT::Corba::ControlTaskProxy | RTT::corba::TaskContextProxy | renamed for consistency. |
RTT::Corba::Method,Command | RTT::corba::COperationRepository,CSendHandle | No need to create these helper objects, call COperationRepository directly |
RTT::Corba::AttributeInterface,Expression,AssignableExpression | RTT::corba::CAttributeRepository | No need to create expression objects, query/use CAttributeRepository directly. |
Attachment | Size |
---|---|
class-dump.txt | 7.89 KB |
headers.txt | 10.17 KB |
to-rtt-2.0.pl.txt | 4.78 KB |
RTT 2.0 has dropped the support for the RTT::Command class. It has been replaced by the more powerful Methods vs Operations construct.
The rtt2-converter tool will automatically convert your Commands to Method/Operation pairs. Here's what happens:
// RTT 1.x code: class ATask: public TaskContext { bool prepareForUse(); bool prepareForUseCompleted() const; public: ATask(): TaskContext("ATask") { this->commands()->addCommand(RTT::command("prepareForUse",&ATask::prepareForUse,&ATask::prepareForUseCompleted,this), "prepares the robot for use"); } };
After:
// After rtt2-converter: RTT 2.x code: class ATask: public TaskContext { bool prepareForUse(); bool prepareForUseCompleted() const; public: ATask(): TaskContext("ATask") { this->addOperation("prepareForUse", &ATask::prepareForUse, this, RTT::OwnThread).doc("prepares the robot for use"); this->addOperation("prepareForUseDone", &ATask::prepareForUseCompleted, this, RTT::ClientThread).doc("Returns true when prepareForUse is done."); } };
What has happened is that the RTT 1.0 Command is split into two RTT 2.0 Operations: "prepareForUse" and "prepareForUseDone". The first will be executed in the component's thread ('OwnThread'), analogous to the RTT::Command semantics. The second function, prepareForUseDone, is executed in the callers thread ('ClientThread'), also analogous to the behaviour of the RTT::Command's completion condition.
The old behavior can be simulated at the callers side by these constructs:
Command<bool(void)> prepare = atask->commands()->getCommand<bool(void)>("prepareForUse"); prepare(); // sends the Command object. while (prepare.done() == false) sleep(1);
In RTT 2.0, the caller's code looks up the prepareForUse Operation and then 'sends' the request to the ATask Component. Optionally, the completion condition is looked up manually and polled for as well:
Method<bool(void)> prepare = atask->getOperation("prepareForUse"); Method<bool(void)> prepareDone = atask->getOperation("prepareForUseDone"); SendHandle h = prepare.send(); while ( !h.collectIfDone() && prepareDone() == false ) sleep(1);
The collectIfDone() and prepareDone() checks are now made explicit, while they were called implicitly in the RTT 1.x's prepare.done() function. Writing your code like this will case the exact same behaviour in RTT 2.0 as in RTT 1.x.
In case you don't care for the 'done' condition, the above code may just be simplified to:
Method<bool(void)> prepare = atask->getOperation("prepareForUse"); prepare.send();
In that case, you may ignore the SendHandle, and the object will cleanup itself at the appropriate time.
Scripting was very convenient for using commands. A typical RTT 1.x script would have looked like:
program foo { do atask.prepareForUse(); // ... rest of the code }
To have the same behaviour in RTT 2.x using Operations, you need to make the 'polling' explicit. Furthermore, you need to 'send' the method to indicate that you do not wish to block:
program foo { var SendHandle h; set h = atask.prepareForUse.send(); while (h.collectIfDone() == false && atask.prepareForUseDone() == false) yield; // ... rest of the code }
function prepare_command() { var SendHandle h; set h = atask.prepareForUse.send(); while (h.collectIfDone() == false && atask.prepareForUseDone() == false) yield; } program foo { call prepare_command(); // note: using 'call' // ... rest of the code }
export function prepare_command() // note: we must export the function { var SendHandle h; set h = atask.prepareForUse.send(); while (h.collectIfDone() == false && atask.prepareForUseDone() == false) yield; } program foo { var SendHandle h; set h = prepare_command(); // note: not using 'call' while (h.collectIfDone() == false) yield; // ... rest of the code }
program foo { prepare_command.call(); // (1) calls and blocks for result. prepare_command.send(); // (2) send() and forget. prepare_command.poll(); // (3) send() and poll with collectIfDone(). }
RTT 2.0 no longer supports the RTT::Event class. This page explains how to adapt your code for this.
Output ports differ from RTT::Event in that they can take only one value as an argument. If your 1.x Event contained multiple arguments, they need to be taken together in a new struct that you create yourself. Both sender and receiver must know and understand this struct.
For the simple case, when your Event only had one argument:
// RTT 1.x class MyTask: public TaskContext { RTT::Event<void(int)> samples_processed; MyTask() : TaskContext("task"), samples_processed("samples_processed") { events()->addEvent( &samples_processed ); } // ... your other code here... };
// RTT 2.x class MyTask: public TaskContext { RTT::OutputPort<int> samples_processed; MyTask() : TaskContext("task"), samples_processed("samples_processed") { ports()->addPort( samples_processed ); // note: RTT 2.x dropped the '&' } // ... your other code here... };
Note: the rtt2-converter tool does not do this replacement, see the Operation section below.
Components wishing to receive the number of samples processed, need to define an InputPort<int> and connect their input port to the output port above.
StateMachine SM { var int total = 0; initial state INIT { entry { } // Reads samples_processed and stores the result in 'total'. // Only if the port return 'NewData', this branch will be evaluated. transition samples_processed( total ) if (total > 0 ) select PROCESSING; } state PROCESSING { entry { /* processing code, use 'total' */ } } final state FINI {}
The transition from state INIT to state PROCESSING will only by taken if samples_processed.read( total ) == NewData and if total > 0. Note: When your TaskContext is periodically executing, the read( total ) statement will be re-tried and overwritten in case of OldData and NewData. Only if the connection of samples_processed is completely empty (never written to or reset), total will not be overwritten.
Operations are can take the same signature as RTT::Event. The difference is that only the component itself can attach callbacks to an Operation, by means of the signals() function.
For example:
// RTT 1.x class MyTask: public TaskContext { RTT::Event<void(int, double)> samples_processed; MyTask() : TaskContext("task"), samples_processed("samples_processed") { events()->addEvent( &samples_processed ); } // ... your other code here... };
// RTT 2.x class MyTask: public TaskContext { RTT::Operation<void(int,double)> samples_processed; MyTask() : TaskContext("task"), samples_processed("samples_processed") { provides()->addOperation( samples_processed ); // note: RTT 2.x dropped the '&' // Attaching a callback handler to the operation object: Handle h = samples_processed.signals( &MyTask::react_foo, this ); } // ... your other code here... void react_foo(int i, double d) { cout << i <<", " << d <<endl; } };
Note: the rtt2-converter tool only does this replacement automatically. Ie. it assumes all your Event objects were only used in the local component. See the RTT 2.0 Renaming table for this tool.
Since an Operation object is always local to the component, no other components can attach callbacks. If your Operation would return a value, the callback functions needs to return it too, but it will be ignored and not received by the caller.
The callback will be executed in the same thread as the operation's function (ie OwnThread vs ClientThread).
StateMachine SM { var int total = 0; initial state INIT { entry { } // Reacts to the samples_processed operation to be invoked // and stores the argument in total. If the Operations takes multiple // arguments, also here multiple arguments must be given. transition samples_processed( total ) if (total > 0 ) select PROCESSING; } state PROCESSING { entry { /* processing code, use 'total' */ } } final state FINI {}
The transition from state INIT to state PROCESSING will only by taken if samples_processed( total ) was called by another component (using a Method object, see Methods vs Operations and if the argument in that call > 0. Note: when samples_processed would return a value, your script can not influence that return value since the return value is determined by the function tied to the Operation, not by signal handlers.
NOTE: RTT 2.0.0-beta1 does not yet support the script syntax.