The following instructions show you how to install the iceoryx rmw implementation. The installation of rmw_iceoryx is pretty straight forward as iceoryx is available in ros2.repos. All provided packages can be built with colcon so that you can easily build rmw_iceoryx within your ROS 2 workspace. rmw_iceoryx is using the rosidl_typesupport_introspection which allows for building iceoryx on top of an existing ROS 2 workspace or even debian installation as no ROS 2 messages have to be built again.
To install rmw_iceoryx in a ROS 2 workspace with the latest ROS version, just execute the steps below:
mkdir -p ~/iceoryx_ws/src
cd $_
# LATEST_ROS_VERSION could be e.g. iron
git clone --branch LATEST_ROS_VERSION https://github.com/ros2/rmw_iceoryx.git
For alternative installation instructions and more details about iceoryx's internals, please see iceoryx's GitHub repo.
rmw_iceoryx is compatible with ROS 2 starting with Eloquent release. Assuming you have ROS 2 installed correctly, you can compile the iceoryx workspace with colcon:
cd ~/iceoryx_ws/
source /opt/ros/LATEST_ROS_VERSION/setup.bash # alternatively source your own ROS 2 workspace
rosdep update
rosdep install --from-paths src --ignore-src --rosdistro LATEST_ROS_VERSION -y
colcon build
# or with more options
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release -DBUILD_TESTING=OFF
That's it! You've installed iceoryx and are ready to rumble.
iceoryx is based on shared memory and features a shared memory management application called RouDi. RouDi is a daemon taking care of allocating enough space within the shared memory each node and is responsible for transporting messages between these nodes.
Before starting any iceoryx application, we therefore have to start the daemon.
./iceoryx_ws/install/iceoryx_posh/bin/iox-roudi # /iceoryx_ws/install/bin/iox-roudi if you installed with as a merged workspace
You can then use rmw_iceoryx_cpp just like any other available rmw implementation.
In order to specify the rmw implementation, you have to set the environment variable RMW_IMPLEMENTATION
to rmw_iceoryx_cpp
.
To run the ROS 2 c++ demo nodes with iceoryx, you can thus execute the following command:
source ~/iceoryx_ws/install/setup.bash
RMW_IMPLEMENTATION=rmw_iceoryx_cpp ros2 run demo_nodes_cpp talker
In another terminal, you can then subscribe to the talker as always:
source ~/iceoryx_ws/install/setup.bash
RMW_IMPLEMENTATION=rmw_iceoryx_cpp ros2 run demo_nodes_cpp listener
To exploit iceoryx's full potential, we want to leverage the zero copy transport mechanism it provides. For this to work, we have to take one step back and look at the details of what it means to enable zero copy data transport.
The basic zero copy workflow works as depicted in the picture below:
Step 1 loan_message()
) A publisher asks rmw_iceoryx_cpp to loan a message from it.
rmw_iceoryx_cpp allocates the appropriate message in its shared memory and loans it to the publisher.
Step 2 publish()
) The publisher can fill in the data into the loaned message.
When calling publish, the loaned message will be returned to the middleware and the publisher has no longer ownership over the message.
Step 3 take_loaned_message()
) A subscription wants to take a message from the middleware.
rmw_iceoryx_cpp gives a loaned message to the subscription which can execute their respective callbacks.
Step 4 return_loaned_message()
) A subscription callback is finished and the loaned message is getting returned to the middleware.
Starting from ROS 2 Eloquent, these features are implemented within rclcpp. An application using these new features is shown in the code snippet below. For a fully working implementation, please have a look at this demo node.
auto non_pod_pub_ = node->create_publisher<std_msgs::msg::String>("/chatter", 1);
// Ask the publisher to loan a String message
auto non_pod_loaned_msg = non_pod_pub_->borrow_loaned_message();
non_pod_loaned_msg.get().data = "Hello World";
// Return ownership of that string message
non_pod_pub_->publish(std::move(non_pod_loaned_msg));
The code above has one problem though: How can the middleware allocate enough memory for the string message? The middleware can't possibly know the size of the string the user wants to put into that message.
That being said, in order to enable a true zero copy data transport we have to limit ourselves to fixed size data structures. The picture below tries to illustrate the difference between a fixed size message and a dynamically resizable message.
The plain old datatype (POD) on the left side is very well suited for zero copy data transport as its size is definitely defined (on compile time). The message definition shown on the right size is not made for zero copy transport as its size might vary during runtime and rmw_iceoryx_cpp can't determine how much memory should be allocated in the shared memory.
Thus, in order to make our demo work with zero copy, we can alternatively send a float64, as its size is clearly defined.
auto pod_pub_ = node->create_publisher<std_msgs::msg::Float64>("/float", 1);
// Ask the publisher to loan a Float64 message
auto pod_loaned_msg = pod_pub_->borrow_loaned_message();
pod_loaned_msg.get().data = 123.456f;
// Return ownership of that Float64 message
pod_pub_->publish(std::move(pod_loaned_msg));
If you'd like to play around with the zero copy transport, we recommend to checkout the fixed size image transport demo, which illustrates how iceoryx can be used to publish and subscribe up to even 4K images without having to copy them.
rmw_iceoryx_cpp is currently under heavy development. Unfortunately, not all features are yet fully fleshed out.
ROS 2 command/feature | Status |
---|---|
ros2 topic list |
✔️ |
ros2 topic echo |
✔️ |
ros2 topic type |
✔️ |
ros2 topic info |
✔️ |
ros2 topic hz |
✔️ |
ros2 topic bw |
✔️ |
ros2 node list |
✔️ |
ros2 node info |
✔️ |
ros2 interface * |
✔️ |
ros2 service * |
✔️ |
ros2 param list |
❌ |
rqt_graph |
✔️ |
rqt_top |
✔️ |
rqt_console |
✔️ |
rqt_plot |
✔️ |
rviz2 |
✔️ |
ros2 bag |
❔ |
urdf | ❔ |
tf2 | ❔ |
RMW Pub/Sub Events | ❌ |