MIRA
Comparison of MIRA and ROS


Significant differences are shown below in Usability and Performance:

General


General concepts

MIRAROS

Platform independence

  • full Unix/Linux support (Compiler: GCC, LLVM CLang)
  • partial Windows support (highly experimental)
  • Mac OSX support in preparation

  • full Unix/Linux support
  • partial Windows support (highly experimental)
  • no Mac OSX support

Language independence

  • C++0x
  • support for Python
  • adapters for Octave/MATLAB
  • support for Java and other languages in preparation

  • C++, Python, Lisp, Java
  • adapters for Octave/MATLAB

Software Components

  • a feature-rich software base for commonly used tasks
  • a „framework“ that provides all functions of a middlware
  • full featured and fully extendable gui (rich client platform) and visualization library
  • growing community repositories that provide algorithms, drivers, etc.

  • a minimalistic software core that provides a middleware
  • huge number of community repositories that provide robotic algorithms, drivers, etc.

Modularity

  • user applications are divided into self-contained modules (Units) that
    perform the actual tasks and computations and use the communication mechanisms to exchange data with each other

  • ROS also divides the user application into modules (Nodes/Nodelets) that use the communication mechanisms for data exchange

Communication

Both provide mechanisms to transport data and messages between software modules within the same process or between different distributed processes. Moreover, both allow Remote Procedure Calls (RPC) between the modules to realize „request-reply“ interactions.

Inter-Process Communication

Uses „Channels“ to exchange data. Channels between different processes are exchanged and synchronized via TCP.

ROS also uses TPC or UDP to exchange messages between nodes in different processes.

Intra-Process Communication

  • modules that are located within the same process automatically shares the data within the same memory and allows efficient zero copy passing of data
  • takes care of protecting the data from concurrent access
  • the underlying communication is fully transparent to the software modules, allowing to decide at configuration time or even runtime where to place different software modules

  • Intra-Process communication was integrated in a later version of ROS, hence it does not integrate seamlessly into the existing communication concepts
  • users have to write special „Nodelets“ instead of „Nodes“
  • Nodes cannot be placed into the same process at configuration time without changes in the code (see Usability)

History of data

  • natively supported by the channel concept, i.e. each channel provides a history of all values that were stored
  • allows to access data from the past (e.g. for synchronizing different data streams)
  • allows the transport of audio streams (audio frames) and can guarantee that no frames are missed
  • allows interpolation of data from channels

  • requires filters to provide a history of data and to do data synchronization (resulting in additional copying and performance penalties)
  • cannot handle audio streams (no guarantee, that no audio frames is mussed)

Datatypes that can be transported

  • fundamental data types (int, float, ...)
  • containers (STL, boost)
  • arbitrary, complex user-defined datatypes
  • pointers
  • polymorphic types

  • fundamental data types (int, float, ...)
  • containers (STL, boost)
  • simple user-defined datatypes only
  • no pointers and no polymorphic types

Migration of software modules

  • allows software-modules to move dynamically at runtime from one process to another or even from one machine to another (e.g. depending on the network and cpu loads)

  • not possible


Reliability, Safety and Security

MIRAROS

Fault tolerance

  • fully decentralized
  • if a single component fails or a computer node is no longer reachable, the rest of the computation network keeps operational

  • uses a centralized approach with a so called "ros master"
  • introduces a "single point of failure"
  • if the ros master stops working or is no longer reachable due to insufficient network coverage, large parts of the computation network will fail
  • is a critical vulnerability for an autonomous robotic system, especially in multi-robot scenarios

Networking Security

  • built-in security mechanisms to protect the MIRA network from external threats
  • allows to use different authentication methods when connecting MIRA software components (frameworks) on different computers via a network connection:
    1. no authentication
    2. weak authentication using a shared pass phrase
    3. strong authentication using RSA keys
  • when two frameworks connect to each other, one framework acts as server while the other one is a client: the connection is established in one direction only that allows to keep the client side fully protected by a firewall

"ROS requires bidirectional networking between all computers attached to the network and does not have security built in" [ROS Wiki].

  • a VPN must be establish to maintain security
  • in real-world applications this can be difficult to arrange with existing network policies (e.g. in some companies)
  • also results in additional networking overhead (computational requirements and latency)
  • due to the required bidirectional connection between the connected nodes, the firewall settings of all nodes must be less strict and poses an additional security threat

Software quality

  • strict code reviews for core framework and other major components
  • elaborated software tests using automated unit testing during nightly builds
  • analysis of code coverage in software tests

  • usually the documentation is reviewed only (no code review), even for the important core components
  • automated unit testing

Prevention of programming errors

  • provides strong type safety for all transport mechanism
  • programming errors when mixing incompatible types will be reported by the compiler

  • topics are typed, but there are no explicit type checks
  • cannot detect when incompatible types are mixed in the transport mechanism, which will result in undefined and unexpected behaviour (see Usability)

Benchmarks

Compared to ROS, MIRA has a significantly lower latency and hence better performance for data exchange and RPC calls:

Usability

Afterwards we compare the usability of MIRA and ROS by examining the implementation steps that are needed to accomplish typical tasks that need to be done when working with both frameworks:


Serialization of data

First we want to create a very simple user-defined structure that should later be transported between different software modules. Therefore, our user-defined structure must be serializable.

MIRAROS
  1. In MIRA you need to add a "reflect" template method to all structs that you want to serialize. In this method you describe the members of the structure.
    struct MyData
    {
    int myIntMember;
    std::vector<float> myFloatVector;
    <template typename Reflector>
    void reflect(Reflector& r)
    {
    r.property("myIntMember",myIntMember,"int member");
    r.member("myFloatVector",myFloatVector,"float vector");
    }
    };

You can simply use your struct like any other normal C++ struct

MyData myData;
myData.myIntMember = 1234;

Thats it, with 6 additional lines of code, objects of "MyData" can now:

  • be transported in channels between modules via intraprocess and interprocess transports
  • be used as parameters and return values for RPC calls
  • can be stored to "tape" files, in order to playback the data later
  • be used as parameters for our software modules, those parameters can be read from xml config files
  • can be used as properties in property editors to change the values of the "myIntMember" dynamically at runtime, e.g. to tune your algorithms LIVE!

  1. In ROS you need to describe your structure in a special metalanguage. Hence, we need to create a new file containing this description:
    File: MyData.msg
    ----------------
    int myIntMember
    float[] myFloatVector
  2. A metacompiler will then create a C++ header from this description which will finally contain our simple user defined struct. Therefore, we need to add the following lines to the CMakeLists.txt:
    File: CMakeLists.txt
    --------------------
    # generates code from message descriptions
    rosbuild_genmsg()
  3. Include the generated header:
    #include <MyPackage/MyData.h>

Now you can finally use your struct:

MyPackage::MyData myData;
myData.myIntMember = 123;

Compared to MIRA there are a couple of things more to do. However, objects of your created message struct can now

  • be transported in channels between modules via intraprocess and interprocess transports
  • be used as parameters and return values for RPC calls
  • can be stored to "bag" files, in order to playback the data later

But note that they:

  • CAN NOT be used as parameters for software modules that can be loaded from XML configuration files
  • CAN NOT be used as properties in property editors to change the values of the members live at runtime to tune algorithms.

For these features you would need to find and use yet another mechanism for serialization that is suitable for these purposes. This will obviously introduce more coding overhead, etc.


Writing a publisher module for inter-process communication

Now, we want to create a module that posts an object of our user-defined structure to other modules in other processes (e.g. TCP) every 100 milliseconds.

MIRAROS
  1. In MIRA software modules are usually represented as Units. Hence, we first need to create a Unit. To simplify this task we use the MIRAWizard, that will create the necessary source file and a configuration file. All we need to do is to add five code lines in the initialize() and process() methods as indicated by the bold lines:

#include <fw/Unit.h>

namespace myns {
class MyPublisher : public Unit
{
MIRA_OBJECT(MyPublisher)
public:
    MyPublisher() : Unit(Duration::milliseconds(100)) {}

    virtual void initialize() 
    {
        // tell the framework, that we will publish a 
        // channel with the name MyChannel
        myChannel = publish<MyData>("MyChannel");
    }

    virtual void process(const Timer& timer)
    {
        // obtain a write accessor to our channel
        auto data = myChannel.write();
        
        // fill in the data
        data->myIntMember=12;
        data->myFloatVector.push_back(3.2f);
        
        // data will we written, when 'data' gets out of scope
    }

private:
    Channel<MyData> myChannel;     
};
}
MIRA_CLASS_SERIALIZATION(myns::MyPublisher, mira::Unit );

  1. We additionally need a configuration file that is used launching our Unit or the whole application. Fortunately, the wizard already created one for us and in this example we do not need to do any changes and can leave the file as it is:
File: start.xml
---------------
<root>
<unit id="MyPublisher" class="myns::MyPublisher"/>
</root>
  1. Finally, we can start the unit from the console by typing
    > mira start.xml

  1. In ROS modules are represented as Nodes. Therefore, we first create a Node. Since there is no wizard that can create code for us, we need to write all of the following code or copy it from an exisiting template:
#include <ros/ros.h>
#include <MyPackage/MyData.h>
int main(int argc, char **argv)
{
// initialize ros and create a node handle
ros::init(argc, argv, "MyPublisher");
ros::NodeHandle n;
// we will publish a channel with the name MyChannel
ros::Publisher pub = n.advertise<MyPackage::MyData>(
"MyChannel", 10);
// specify our cycle time
ros::Rate r(10);
// create an instance of the data
MyPackage::MyData msg;
while (n.ok())
{
// fill in the data
msg.myIntMember=12;
msg.myFloatVector.push_back(3.2f);
// write the data
pub.publish(msg);
// let ros process our events
ros::spinOnce();
r.sleep();
}
return 0;
}
  1. In ROS we also need a configuration or "launch" file for starting our Node or the whole application consiting of several nodes. Again, we need to write the file on our own or we can copy it from an example:
File: start.launch
------------------
<launch>
<node name="MyPublisher" pkg="mypackage" type="MyPublisher" />
</launch>
  1. Finally, we can start the Node from the console by typing
    > roslaunch start.launch


Using the publisher module for communication within the same process

Now, we want to use the module that we have created above together with a second module (e.g. "MySubscriber") within the SAME process. Communication within the same process usually is up to several magnitudes faster than inter-process communication.

MIRAROS
  1. In MIRA we can place Units wherever we want to. We can place several of them into the same process or we can distribute them over different processes. If units reside within the same process, MIRA and its channel concept automatically takes care of concurrent data access, so the Units do not need to worry about that. Hence, we can simply extend our configuration file as follows:
    File: start.xml
    ---------------
    <root>
    <unit id="MyPublisher" class="myns::MyPublisher"/>
    <unit id="MySubscriber" class="myns::MySubscriber"/>
    </root>

And we are done!

  1. In ROS each node can only live within its own process. This leads to a significant communication overhead when large data is transfered. To overcome this limitation Nodelets were introduced in the "C Turtle" release. However, since those nodelets were not part of the initial concepts, they do not integreate seamlessly. Hence, we cannot simply use our above Node to run it in the same thread with our Subscriber node, instead, we have to rewrite our node to create a nodelet. Note, that nodelets use shared pointers to pass data between different modules. ROS does not take care of concurrent accesses to this data and the Nodelets are responsible for this on their own!
#include <pluginlib/class_list_macros.h>
#include <nodelet/nodelet.h>
#include <ros/ros.h>
#include <MyPackage/MyData.h>
#include <boost/thread.hpp>
#include <boost/bind.hpp>
namespace myns {
class MyPublisher : public nodelet::Nodelet
{
public:
~BenchmarkPublisher()
{
thread.interrupt();
thread.join();
}
virtual void onInit()
{
// we will publish a channel with the name MyChannel
ros::NodeHandle& nh = getNodeHandle();
pub = nh.advertise<MyPackage::MyData>("MyChannel", 10);
// we need to create our own thread
thread = boost::thread(boost::bind(&MyPublisher::process,
this));
}
void process()
{
// specify our cycle time
ros::Rate r(10);
while (!boost::this_thread::interruption_requested())
{
// create an instance of the data (Nodelets can
// only work with shared pointers)
// we always need to create a new message to
// handle concurrent access, since the subscriber
// could still read the data in the shared pointer
MyPackage::MyData::Ptr msg(new MyPackage::MyData);
// fill in the data
msg->myIntMember=12;
msg->myFloatVector.push_back(3.2f);
// write the data
pub.publish(msg);
r.sleep();
}
}
ros::Publisher pub;
boost::thread thread;
};
}
PLUGINLIB_DECLARE_CLASS(myns, MyPublisher,
myns::BenchmarkPublisher, nodelet::Nodelet);
  1. This code has to be compiled into a library (similar to a Unit in MIRA). Unlinke MIRA, the ROS nodelet management additionally needs another XML file, that describes the content of the library, which has to be created manually:
File: MyNodelet.xml
-------------------
<library path="lib/libMyNodelet">
<class name="myns/MyPublisher" type="myns::MyPublisher"
base_class_type="nodelet::Nodelet">
<description>
Some Description
</description>
</class>
</library>
  1. We now have to add this XML file to the manifest of our package - another XML configuration file. (Hopefully, you will not get lost in all those XML files ;) )
File: manifest.xml
-------------------
...
<export>
<nodelet plugin="${prefix}/MyNodelet.xml" />
</export>
  1. Finally, we have to modify the start.launch configuration file, which now becomes a little more complicated:
<launch>
<node pkg="nodelet" type="nodelet" name="standalone_nodelet"
args="manager" output="screen"/>
<node pkg="nodelet" type="nodelet" name="MyPublisher"
args="load myns/MyPublisher standalone_nodelet"/>
<node pkg="nodelet" type="nodelet" name="MySubscriber"
args="load myns/MySubscriber standalone_nodelet"/>
</launch>

As you can see, the creation of a Nodelet is somewhat cumbersome ...


Providing RPC services

The probably most obvious advantages of MIRAs usability show up when it comes to Remote Procedure Calls (RPC).

In the following we want to expose all methods of the following class as RPC services:

class MyRPCService
{
public:
void setValue(const MyData& value);
const MyData& getValue() const;
bool checkValue(const MyData& value);
};
MIRAROS
  1. In MIRA we need to add a reflect() method to the above class. In this reflect() method we expose the three methods:
    template <typename Reflector>
    void reflect(Reflector& r)
    {
    r.method("setValue", &MyRPCService::setValue,
    "sets a new value");
    r.method("getValue", &MyRPCService::getValue,
    "gets value");
    r.method("checkValue", &MyRPCService::checkValue,
    "check if value is valid");
    }
  2. For providing those methods as service we only have to add the following line to the initialize() method of our Unit:
    void initialize()
    {
    publishService("MyService", myRPCService);
    }
    // myRPCService is a member of our unit
    MyRPCService myRPCService;

And we are done! All three methods can now be called by other Units via RPC.

  1. In ROS we need to create a service description meta file for each method. This meta describtion is similar to the message description files and contains the parameters and return value types.
    File: SetValue.srv
    ------------------
    MyData value
    ---

Since the signatures of the methods are different, we need to write a service description file for each method:

File: GetValue.srv
------------------
---
MyData result
File: CheckValue.srv
------------------
MyData value
---
bool result
  1. A metacompiler will then create header files from our service descriptions. Therefore, we need to add the following lines to the CMakeLists.txt:
    File: CMakeLists.txt
    --------------------
    # generates code from message descriptions
    rosbuild_gensrv()
  2. Include the header files created by the metacompiler:
    #include <MyPackage/SetValue.h>
    #include <MyPackage/GetValue.h>
    #include <MyPackage/CheckValue.h>
  3. Since ROS cannot call the methods of our class directly, we need to write wrappers for our methods
    bool setValueWrapper(MyRPCService* obj,
    MyPackage::SetValue::Request& request,
    MyPackage::SetValue::Response& response)
    {
    obj->setValue(request.value);
    return true;
    }
    bool getValueWrapper(const MyRPCService* obj,
    MyPackage::GetValue::Request& request,
    MyPackage::GetValue::Response& response)
    {
    response.result = obj->getValue();
    return true;
    }
    bool checkValueWrapper(MyRPCService* obj,
    MyPackage::CheckValue::Request& request,
    MyPackage::CheckValue::Response& response)
    {
    bool result obj->checkValue(request.value);
    response.result = result;
    return true;
    }
  4. Finally, we can advertise our service methods in our node
    MyRPCService myRPCService;
    ros::ServiceServer service = n.advertiseService("setValue",
    boost::bind(setValueWrapper,&myRPCService,_1,_2));
    ros::ServiceServer service1 = n.advertiseService("getValue",
    boost::bind(getValueWrapper,&myRPCService,_1,_2));
    ros::ServiceServer service2 = n.advertiseService("checkValue",
    boost::bind(checkValueWrapper,&myRPCService,_1,_2));
  5. Now, the methods can be called by other nodes.

However, when creating many RPC services, creating the RPC description files and especially writing all the wrapper functions can be very tiresome and error-prone.


Calling RPC services

Now we want to call the methods of the RPC service that is provided in the above example.

MIRAROS
  1. MIRA allows to call the RPC method very similar to normal C-like method calls, i.e. by specifying the method name and a variable number of parameters:
    MyData value;
    ...
    // do the call
    callService<void>("myService","setValue", value);
  2. For obtaining return values from RPC methods, MIRA supports "futures". This allows blocking and non-blocking RPC calls, i.e. the user can decide whether and where he/she wants to wait for the result:
    RPCFuture<bool> result =
    callService<void>("myService","checkValue", value);
    // the call will return immediately. WE can decide whether
    // and where we want to wait for the result:
    if(result.get()) {
    cout << "value is okay" << std::endl;
    }

  1. In ROS we need to wrap the parameters, instead of calling the RPC method in C-like manner:
    MyData value;
    ...
    // wrap the parameter
    MyPackage::SetValue callContext;
    callContext.request.value = value;
    // do the actual call
    ros::service::call("setValue", callContext);
  2. In ROS RPC calls will always block, i.e. we cannot decide where we want to wait for the result (even if we are not interested in the result)
    // wrap the parameter
    MyPackage::CheckValue callContext2;
    callContext2.request.value = value;
    // do the actual call (which blocks)
    ros::service::call("checkValue", callContext2);
    // unwrap the result
    if(recallContext2response.result) {
    cout << "value is okay" << std::endl;
    }

Obsolete

The following will be completely rewritten:

MIRA

ROS

Design and Concepts

Inter-Process Communication MIRA uses Channels to exchange data between software modules. Channels between different processes are exchanged and synchronized via TCP.

ROS also uses TPC or UDP to exchange messages between nodes in different processes.

Intra-Process Communication If software modules are located within the same process, the MIRA framework automatically shares the data within the same memory and allows efficient zero copy passing of data. It also takes care of protecting the data from concurrent access. The underlying communication is fully transparent to the software modules, i.e. the modules are implemented and behave exactly in the same way no matter if the communication is intra or inter process. This allows to decide at configuration time or even runtime where to place different software modules. It also allows the migration of software modules from one process to others in future release of MIRA.

In contrast to MIRA the intra-process communication was not part of the initial design. It was added later in the C Turtle release and therefore does not integrate seamlessly. To use intra process communication a nodelet needs to be implemented instead of a node. This requires to use a different API. Moreover, the data can be exchanged via shared pointers only.

As a result, the usability suffers from these limitations. Additionally, the nodes and nodelets can not be placed in arbitrary processes at configuration or runtime. The decision already has to be made while implementing the modules.
For that reason some developers tend to implement both, nodes and nodelets for the same modules, to allow intra and inter process communication for their modules. This results in unnecessary implementation overhead.

History of data ... natively supported by channel concept

... with filters (requires additional copying, performance penalty)

  • cannot handle audio streams (no guarantee, that no audio frames is mussed)

Serialization, Persistence, Parameters etc. MIRA uses a single serialization concept that does not requires a meta language or meta compilers. The constructs of the C++ language are sufficient. It is necessary to implement a single reflect() method only, where all members of a class are specified. After that objects of that class can be:
  • serialized persistent to an XML-file to store it's state and parameters
  • exchanged via channels (intra and inter process)
  • serialized as binary data and stored into a tape file
  • used in an property editor to change it's properties "live" at runtime
  • used as parameters and return values of RPC calls
Unfortunately, ROS does not provide such a single generic concept. Instead ROS requires many different methods to achieve the same functionalities:
  • For reading and writing parameters it provides the setParam() and getParam() method of the parameter server.
  • To send data as message one has to define an additional message description file which is transformed using a meta compiler into C code. In contrast to MIRA, ROS can not handle arbitrary classes, e.g. classes with pointers. It can handle messages only that consist of atomic members, containers, or other messages.
  • For properties, e.g. in visualizations for rviz, yet another concept is used to define and specify properties. Those properties can be used within the rviz tool only. In contrast, properties that are defined in MIRA can be used everywhere.
  • To enable RPC calls, another meta mechanism is used. It requires to specify a service description file, where the parameters and return values are specified similar to the message meta files. Again this service meta file needs to be compiled by a meta compiler.