<!DOCTYPE HTML>
<html lang="en" class="light" dir="ltr">
<head>
<!-- Book generated using mdBook -->
<meta charset="UTF-8">
<title>safe_drive: Formally Specified Rust Bindings for ROS2</title>
<meta name="robots" content="noindex">
<!-- Custom HTML head -->
<meta name="description" content="">
<meta name="viewport" content="width=device-width, initial-scale=1">
<meta name="theme-color" content="#ffffff">
<link rel="icon" href="favicon.svg">
<link rel="shortcut icon" href="favicon.png">
<link rel="stylesheet" href="css/variables.css">
<link rel="stylesheet" href="css/general.css">
<link rel="stylesheet" href="css/chrome.css">
<link rel="stylesheet" href="css/print.css" media="print">
<!-- Fonts -->
<link rel="stylesheet" href="FontAwesome/css/font-awesome.css">
<link rel="stylesheet" href="fonts/fonts.css">
<!-- Highlight.js Stylesheets -->
<link rel="stylesheet" href="highlight.css">
<link rel="stylesheet" href="tomorrow-night.css">
<link rel="stylesheet" href="ayu-highlight.css">
<!-- Custom theme stylesheets -->
</head>
<body class="sidebar-visible no-js">
<div id="body-container">
<!-- Provide site root to javascript -->
<script>
var path_to_root = "";
var default_theme = window.matchMedia("(prefers-color-scheme: dark)").matches ? "navy" : "light";
</script>
<!-- Work around some values being stored in localStorage wrapped in quotes -->
<script>
try {
var theme = localStorage.getItem('mdbook-theme');
var sidebar = localStorage.getItem('mdbook-sidebar');
if (theme.startsWith('"') && theme.endsWith('"')) {
localStorage.setItem('mdbook-theme', theme.slice(1, theme.length - 1));
}
if (sidebar.startsWith('"') && sidebar.endsWith('"')) {
localStorage.setItem('mdbook-sidebar', sidebar.slice(1, sidebar.length - 1));
}
} catch (e) { }
</script>
<!-- Set the theme before any content is loaded, prevents flash -->
<script>
var theme;
try { theme = localStorage.getItem('mdbook-theme'); } catch(e) { }
if (theme === null || theme === undefined) { theme = default_theme; }
var html = document.querySelector('html');
html.classList.remove('light')
html.classList.add(theme);
var body = document.querySelector('body');
body.classList.remove('no-js')
body.classList.add('js');
</script>
<input type="checkbox" id="sidebar-toggle-anchor" class="hidden">
<!-- Hide / unhide sidebar before it is displayed -->
<script>
var body = document.querySelector('body');
var sidebar = null;
var sidebar_toggle = document.getElementById("sidebar-toggle-anchor");
if (document.body.clientWidth >= 1080) {
try { sidebar = localStorage.getItem('mdbook-sidebar'); } catch(e) { }
sidebar = sidebar || 'visible';
} else {
sidebar = 'hidden';
}
sidebar_toggle.checked = sidebar === 'visible';
body.classList.remove('sidebar-visible');
body.classList.add("sidebar-" + sidebar);
</script>
<nav id="sidebar" class="sidebar" aria-label="Table of contents">
<div class="sidebar-scrollbox">
<ol class="chapter"><li class="chapter-item expanded "><a href="index.html"><strong aria-hidden="true">1.</strong> Top</a></li><li class="chapter-item expanded "><a href="tutorial.html"><strong aria-hidden="true">2.</strong> Tutorial</a></li><li><ol class="section"><li class="chapter-item expanded "><a href="setup.html"><strong aria-hidden="true">2.1.</strong> Setting-up</a></li><li class="chapter-item expanded "><a href="pubsub.html"><strong aria-hidden="true">2.2.</strong> Publish and Subscribe</a></li><li class="chapter-item expanded "><a href="timer.html"><strong aria-hidden="true">2.3.</strong> Timer</a></li><li class="chapter-item expanded "><a href="multi_pubsub.html"><strong aria-hidden="true">2.4.</strong> Multi-threaded Publish and Subscribe</a></li><li class="chapter-item expanded "><a href="message.html"><strong aria-hidden="true">2.5.</strong> User Defined Data Structure</a></li><li class="chapter-item expanded "><a href="service.html"><strong aria-hidden="true">2.6.</strong> Service</a></li><li class="chapter-item expanded "><a href="parameter.html"><strong aria-hidden="true">2.7.</strong> Parameter</a></li><li class="chapter-item expanded "><a href="zerocopy.html"><strong aria-hidden="true">2.8.</strong> Zero Copy Publish and Subscribe</a></li><li class="chapter-item expanded "><a href="allocator.html"><strong aria-hidden="true">2.9.</strong> Custom Memory Allocator</a></li><li class="chapter-item expanded "><a href="pusbsub_and_service.html"><strong aria-hidden="true">2.10.</strong> Request to Server in Callback</a></li></ol></li><li class="chapter-item expanded "><a href="contribution.html"><strong aria-hidden="true">3.</strong> Contribution Guide</a></li><li><ol class="section"><li class="chapter-item expanded "><a href="setup_contribution.html"><strong aria-hidden="true">3.1.</strong> Setting-up for Contribution</a></li><li class="chapter-item expanded "><a href="build_and_test.html"><strong aria-hidden="true">3.2.</strong> Build and Test</a></li><li class="chapter-item expanded "><a href="editor_setup.html"><strong aria-hidden="true">3.3.</strong> Editor Setting-up</a></li><li class="chapter-item expanded "><a href="internal_msgs.html"><strong aria-hidden="true">3.4.</strong> Generating Messages Included by safe_drive</a></li><li class="chapter-item expanded "><a href="c_apis.html"><strong aria-hidden="true">3.5.</strong> C APIs</a></li><li class="chapter-item expanded "><a href="document.html"><strong aria-hidden="true">3.6.</strong> Documentation</a></li></ol></li></ol>
</div>
<div id="sidebar-resize-handle" class="sidebar-resize-handle">
<div class="sidebar-resize-indicator"></div>
</div>
</nav>
<!-- Track and set sidebar scroll position -->
<script>
var sidebarScrollbox = document.querySelector('#sidebar .sidebar-scrollbox');
sidebarScrollbox.addEventListener('click', function(e) {
if (e.target.tagName === 'A') {
sessionStorage.setItem('sidebar-scroll', sidebarScrollbox.scrollTop);
}
}, { passive: true });
var sidebarScrollTop = sessionStorage.getItem('sidebar-scroll');
sessionStorage.removeItem('sidebar-scroll');
if (sidebarScrollTop) {
// preserve sidebar scroll position when navigating via links within sidebar
sidebarScrollbox.scrollTop = sidebarScrollTop;
} else {
// scroll sidebar to current active section when navigating via "next/previous chapter" buttons
var activeSection = document.querySelector('#sidebar .active');
if (activeSection) {
activeSection.scrollIntoView({ block: 'center' });
}
}
</script>
<div id="page-wrapper" class="page-wrapper">
<div class="page">
<div id="menu-bar-hover-placeholder"></div>
<div id="menu-bar" class="menu-bar sticky">
<div class="left-buttons">
<label id="sidebar-toggle" class="icon-button" for="sidebar-toggle-anchor" title="Toggle Table of Contents" aria-label="Toggle Table of Contents" aria-controls="sidebar">
<i class="fa fa-bars"></i>
</label>
<button id="theme-toggle" class="icon-button" type="button" title="Change theme" aria-label="Change theme" aria-haspopup="true" aria-expanded="false" aria-controls="theme-list">
<i class="fa fa-paint-brush"></i>
</button>
<ul id="theme-list" class="theme-popup" aria-label="Themes" role="menu">
<li role="none"><button role="menuitem" class="theme" id="light">Light</button></li>
<li role="none"><button role="menuitem" class="theme" id="rust">Rust</button></li>
<li role="none"><button role="menuitem" class="theme" id="coal">Coal</button></li>
<li role="none"><button role="menuitem" class="theme" id="navy">Navy</button></li>
<li role="none"><button role="menuitem" class="theme" id="ayu">Ayu</button></li>
</ul>
<button id="search-toggle" class="icon-button" type="button" title="Search. (Shortkey: s)" aria-label="Toggle Searchbar" aria-expanded="false" aria-keyshortcuts="S" aria-controls="searchbar">
<i class="fa fa-search"></i>
</button>
</div>
<h1 class="menu-title">safe_drive: Formally Specified Rust Bindings for ROS2</h1>
<div class="right-buttons">
<a href="print.html" title="Print this book" aria-label="Print this book">
<i id="print-button" class="fa fa-print"></i>
</a>
</div>
</div>
<div id="search-wrapper" class="hidden">
<form id="searchbar-outer" class="searchbar-outer">
<input type="search" id="searchbar" name="searchbar" placeholder="Search this book ..." aria-controls="searchresults-outer" aria-describedby="searchresults-header">
</form>
<div id="searchresults-outer" class="searchresults-outer hidden">
<div id="searchresults-header" class="searchresults-header"></div>
<ul id="searchresults">
</ul>
</div>
</div>
<!-- Apply ARIA attributes after the sidebar and the sidebar toggle button are added to the DOM -->
<script>
document.getElementById('sidebar-toggle').setAttribute('aria-expanded', sidebar === 'visible');
document.getElementById('sidebar').setAttribute('aria-hidden', sidebar !== 'visible');
Array.from(document.querySelectorAll('#sidebar a')).forEach(function(link) {
link.setAttribute('tabIndex', sidebar === 'visible' ? 0 : -1);
});
</script>
<div id="content" class="content">
<main>
<h1 id="safe_drive-formally-specified-rust-bindings-for-ros2"><a class="header" href="#safe_drive-formally-specified-rust-bindings-for-ros2">safe_drive: Formally Specified Rust Bindings for ROS2</a></h1>
<p><code>safe_drive</code> is a Rust bindings for ROS2.
This library provides formal specifications and tested the specifications by using a model checker.
Therefore, you can clearly understand how the scheduler work and the safeness of it.</p>
<h2 id="specifications"><a class="header" href="#specifications">Specifications</a></h2>
<p>Some algorithms we adopted are formally specified and tested the safeness by using TLA+.
Original ROS2's executor (rclcpp) is suffering from starvation.
In contrast, the starvation freedom of our executor has been validated by not only dynamic analysis but also
formal verification.</p>
<p>See <a href="https://github.com/tier4/safe_drive/tree/main/specifications">specifications</a>.</p>
<p>We specified and tested as follows.</p>
<ul>
<li>Single Threaded Callback Execution
<ul>
<li>Deadlock freedom</li>
<li>Starvation freedom</li>
</ul>
</li>
<li>Scheduling Core Algorithm
<ul>
<li>Validate the insertion algorithm</li>
<li>Termination</li>
</ul>
</li>
<li>Initialize Once
<ul>
<li>Deadlock freedom</li>
<li>Termination</li>
<li>Initialization is performed just once</li>
</ul>
</li>
</ul>
<div style="break-before: page; page-break-before: always;"></div><h1 id="tutorial"><a class="header" href="#tutorial">Tutorial</a></h1>
<p>This chapter explain how to use <code>safe_drive</code> and
interoperability of existing ROS2's project written in C++ by using <code>colcon</code>.</p>
<p><a href="https://github.com/tier4/safe_drive_tutorial">Source code</a>.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="setting-up"><a class="header" href="#setting-up">Setting-up</a></h1>
<h2 id="install-dependencies"><a class="header" href="#install-dependencies">Install Dependencies</a></h2>
<pre><code class="language-text">$ sudo apt install curl gnupg2 lsb-release python3-pip git
</code></pre>
<h2 id="install-rust"><a class="header" href="#install-rust">Install Rust</a></h2>
<pre><code class="language-text">$ sudo curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh
$ source $HOME/.cargo/env
</code></pre>
<p>Choose <code>Default</code> when installing Rust.</p>
<h2 id="install-ros2"><a class="header" href="#install-ros2">Install ROS2</a></h2>
<pre><code class="language-text">$ curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
$ sudo sh -c 'echo "deb [arch=$(dpkg --print-architecture)] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" > /etc/apt/sources.list.d/ros2-latest.list'
$ sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
</code></pre>
<pre><code class="language-text">$ sudo apt update
$ sudo apt install ros-iron-desktop python3-colcon-common-extensions
</code></pre>
<pre><code class="language-text">$ . /opt/ros/iron/setup.bash
</code></pre>
<h2 id="install-colcon-cargo"><a class="header" href="#install-colcon-cargo">Install Colcon-cargo</a></h2>
<pre><code class="language-text">$ pip install git+https://github.com/tier4/colcon-cargo.git
$ pip install git+https://github.com/colcon/colcon-ros-cargo.git
</code></pre>
<h2 id="install-cargo-ament"><a class="header" href="#install-cargo-ament">Install Cargo-ament</a></h2>
<pre><code class="language-text">$ git clone https://github.com/tier4/cargo-ament-build.git
$ cd cargo-ament-build
$ cargo install --path .
</code></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="publish-and-subscribe"><a class="header" href="#publish-and-subscribe">Publish and Subscribe</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/pubsub">Source code</a>.</p>
<p>This chapter introduces a simple example of publish and subscribe communication.
This communication is so-called topic by ROS2.
There are <code>N</code> senders and <code>M</code> receivers in a topic.
This tutorial implements 1 sender (in Rust) and 2 receivers (in Rust and C++).</p>
<p>The following figure is a example topology.</p>
<pre class="mermaid">graph TD;
Publisher1-->TopicA;
Publisher2-->TopicA;
TopicA-->Subscriber1;
TopicA-->Subscriber2;
TopicA-->Subscriber3;
Publisher3-->TopicB;
Publisher4-->TopicB;
Publisher5-->TopicB;
TopicB-->Subscriber4;
TopicB-->Subscriber5;
</pre>
<p>There are 2 topics, <code>TopicA</code> and <code>TopicB</code> in this figure.
If <code>Publisher2</code> of <code>TopicA</code> send a message,
<code>Subscriber1-3</code> subscribing <code>TopicA</code> receive the message.
<code>Subscriber4</code> and <code>Subscriber5</code> can receive messages sent from
<code>Publisher3-5</code>.</p>
<h2 id="directories"><a class="header" href="#directories">Directories</a></h2>
<p>First of all, create working directories as follows.</p>
<pre><code class="language-text">$ mkdir pubsub
$ mkdir pubsub/src
</code></pre>
<p>Then create projects of Rust by using <code>cargo</code> as follows.</p>
<pre><code class="language-text">$ cd pubsub/src
$ cargo new my_talker
$ cargo new my_listener
</code></pre>
<p>Following directories are important directories
we will use throughout this tutorial.</p>
<div class="table-wrapper"><table><thead><tr><th>Directories</th><th>What?</th></tr></thead><tbody>
<tr><td>pubsub/src/my_talker</td><td>publisher in Rust</td></tr>
<tr><td>pubsub/src/my_listener</td><td>subscriber in Rust</td></tr>
<tr><td>pubsub/install</td><td>created by colcon</td></tr>
</tbody></table>
</div>
<h2 id="workspace-of-rust"><a class="header" href="#workspace-of-rust">Workspace of Rust</a></h2>
<p>To handle multiple projects of <code>cargo</code>, we recommend to prepare <code>Cargo.toml</code> for the workspace as follows.</p>
<p><code>pubsub/src/Cargo.toml</code></p>
<pre><code class="language-toml">[workspace]
members = ["my_talker", "my_listener"]
</code></pre>
<p>The workspace enables <code>rust-analyzer</code> and reduces compilation time.</p>
<hr />
<h2 id="talker-in-rust"><a class="header" href="#talker-in-rust">Talker in Rust</a></h2>
<p>Let's start implementing a publisher.
We created and will edit files of the talker as follows.
These files will automatically created when you do <code>cargo new</code> as described before.</p>
<div class="table-wrapper"><table><thead><tr><th>Files</th><th>What?</th></tr></thead><tbody>
<tr><td>my_talker/Cargo.toml</td><td>for Cargo</td></tr>
<tr><td>my_talker/package.xml</td><td>for ROS2</td></tr>
<tr><td>my_talker/src/main.rs</td><td>source code</td></tr>
</tbody></table>
</div>
<h3 id="edit-my_talkercargotoml"><a class="header" href="#edit-my_talkercargotoml">Edit <code>my_talker/Cargo.toml</code></a></h3>
<p><code>Cargo.toml</code> is used to describe a project of Rust.
Add safe_drive to the dependencies of <code>Cargo.toml</code> to use it.
Currently, safe_drive's repository is private,
and we need to specify the path as follows.</p>
<p><code>pubsub/src/my_talker/Cargo.toml</code></p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
std_msgs = { path = "/tmp/safe_drive_tutorial/pubsub/std_msgs" }
[package.metadata.ros]
msg = ["std_msgs"]
msg_dir = "/tmp/safe_drive_tutorial/pubsub"
safe_drive_version = "0.3"
</code></pre>
<h3 id="edit-my_talkersrcmainrs"><a class="header" href="#edit-my_talkersrcmainrs">Edit <code>my_talker/src/main.rs</code></a></h3>
<p>my_talker is very simple.
This does as follows.</p>
<ol>
<li>Create a context.</li>
<li>Create a node from the context.</li>
<li>Create a publisher from the node.</li>
<li>Send a message periodically.</li>
</ol>
<p>A context is a resource manager of ROS2,
and it must be created first of all.
A node contains publishers, subscribers, servers, and clients.
A node is a functional unit of ROS2.
Publishers and subscribers can be created by a node.</p>
<p>The following figure is an example hierarchy.</p>
<pre class="mermaid">graph TD;
Context-->NodeA
NodeA-->SubscriberA
NodeA-->SubscriberB
NodeA-->PublisherA
NodeA-->PublisherB
NodeA-->PublisherC
</pre>
<p>In this figure, <code>NodeA</code> is created by a context,
and subscribers and publishers are created by the node.</p>
<p>Now, we have understood the basics of ROS2.
The following is a code of my_talker.
You should also understand what this code is doing.</p>
<p><code>pubsub/src/my_talker/src/main.rs</code></p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context, error::DynError, logger::Logger, pr_info
};
use std::time::Duration;
fn main() -> Result<(), DynError> {
// Create a context.
let ctx = Context::new()?;
// Create a node.
let node = ctx.create_node("my_talker", None, Default::default())?;
// Create a publisher.
let publisher = node.create_publisher::<std_msgs::msg::String>("my_topic", None)?;
// Create a logger.
let logger = Logger::new("my_talker");
let mut cnt = 0; // Counter.
let mut msg = std_msgs::msg::String::new().unwrap();
loop {
// Create a message to be sent.
let data = format!("Hello, World!: cnt = {cnt}");
msg.data.assign(&data);
pr_info!(logger, "send: {}", msg.data); // Print log.
// Send a message.
publisher.send(&msg)?;
// Sleep 1s.
cnt += 1;
std::thread::sleep(Duration::from_secs(1));
}
}</code></pre></pre>
<h4 id="my_talker-in-detail"><a class="header" href="#my_talker-in-detail">my_talker in Detail</a></h4>
<p><code>create_node</code> creates a node.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a node.
let node = ctx.create_node("my_talker", None, Default::default())?;
<span class="boring">}</span></code></pre></pre>
<p>The arguments indicate as follows.</p>
<ul>
<li><code>"my_talker"</code> : the name of the node.</li>
<li>Node : namespace.
<ul>
<li>We can pass a namespace like <code>Some("namespace")</code>.</li>
<li>If <code>None</code> is passed, the node has no namespace.</li>
</ul>
</li>
<li><code>Default::default()</code> : option of node.</li>
</ul>
<p><code>create_publisher</code> creates a publisher.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a publisher.
let publisher = node.create_publisher::<std_msgs::msg::String>("my_topic", None)?;
<span class="boring">}</span></code></pre></pre>
<ul>
<li><code><std_msgs::msg::String></code> : the publisher can send values of <code>std_msgs::msg::String</code>.</li>
<li><code>"my_topic"</code> : the topic name to which the publisher send messages.</li>
<li><code>None</code> : QoS of the publisher. QoS will be described in a later chapter.</li>
</ul>
<p>A message can be sent by <code>send</code> method as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a message to be sent.
let data = format!("Hello, World!: cnt = {cnt}");
msg.data.assign(&data);
// Send a message.
publisher.send(&msg)?;
<span class="boring">}</span></code></pre></pre>
<p><code>Logger</code> is used to print some messages.
It can be created as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a logger.
let logger = Logger::new("my_talker");
<span class="boring">}</span></code></pre></pre>
<p>The argument of <code>"my_talker"</code> is the name of the logger.
To print a message, use <code>pr_*</code> macros as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pr_info!(logger, "send: {}", msg.data); // Print log.
<span class="boring">}</span></code></pre></pre>
<p>There are macros for logging as follows.</p>
<ul>
<li><code>pr_debug!</code> : debug</li>
<li><code>pr_info!</code> : information</li>
<li><code>pr_warn!</code> : warning</li>
<li><code>pr_err!</code> : error</li>
<li><code>pr_fatal!</code> : fatal</li>
</ul>
<h3 id="create-my_talkerpackagexml"><a class="header" href="#create-my_talkerpackagexml">Create <code>my_talker/package.xml</code></a></h3>
<p><code>package.xml</code> is used by colcon, which is a build tool used by ROS2.
It contains the package name, maintainer, description, etc, as follows.</p>
<p><code>pubsub/src/my_talker/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>my_talker</name>
<version>0.0.0</version>
<description>My Talker in Rust</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<depend>std_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<p>Copy and paste this, then edit it if you want.</p>
<h3 id="execute-the-talker"><a class="header" href="#execute-the-talker">Execute the Talker</a></h3>
<p>Before compiling, ensure that you load setting of ROS2 as follows.
If you have already done so, you do not need this.</p>
<pre><code class="language-text">$ . /opt/ros/iron/setup.bash
</code></pre>
<p>Then compile by using colcon as follows.
Before compiling, change the current directory to <code>pubsub</code>,
which is the top directory of our project.</p>
<pre><code class="language-text">$ cd pubsub
$ colcon build --cargo-args --release
</code></pre>
<p><code>--cargo-args --release</code> is a option to pass the <code>--release</code> argument to <code>cargo</code>.
<code>cargo</code> optimizes the code when <code>--release</code> is specified.</p>
<p>To launch <code>my_talker</code>,
load the setting and use <code>ros2</code> command as follows.</p>
<pre><code class="language-text">$ . ./install/setup.bash
$ ros2 run my_talker my_talker
[INFO] [1656048392.368568500] [my_talker]: send: Hello, World!: cnt = 0
[INFO] [1656048393.368787500] [my_talker]: send: Hello, World!: cnt = 1
[INFO] [1656048394.368994200] [my_talker]: send: Hello, World!: cnt = 2
</code></pre>
<hr />
<h2 id="listener-in-rust"><a class="header" href="#listener-in-rust">Listener in Rust</a></h2>
<p>Let's then implement a listener.
We created and will edit files of the listener as follows.</p>
<div class="table-wrapper"><table><thead><tr><th>Files</th><th>What?</th></tr></thead><tbody>
<tr><td>my_listener/Cargo.toml</td><td>for Cargo</td></tr>
<tr><td>my_listener/package.xml</td><td>for ROS2</td></tr>
<tr><td>my_listener/src/main.rs</td><td>source code</td></tr>
</tbody></table>
</div>
<h3 id="edit-my_listenercargotoml"><a class="header" href="#edit-my_listenercargotoml">Edit <code>my_listener/Cargo.toml</code></a></h3>
<p><code>my_listener</code> also requires safe_drive.
Add safe_drive to the dependencies as follows.</p>
<pre><code class="language-toml"># pubsub/src/my_listener/Cargo.toml
[dependencies]
safe_drive = "0.4"
std_msgs = { path = "/tmp/safe_drive_tutorial/pubsub/std_msgs" }
[package.metadata.ros]
msg = ["std_msgs"]
msg_dir = "/tmp/safe_drive_tutorial/pubsub"
safe_drive_version = "0.3"
</code></pre>
<h3 id="edit-my_listenersrcmainrs"><a class="header" href="#edit-my_listenersrcmainrs">Edit <code>my_listener/src/main.rs</code></a></h3>
<p>To implement subscriber,
we have to prepare a callback function of the subscriber.
This is the main difference from <code>my_talker</code>.</p>
<p><code>pubsub/src/my_listener/src/main.rs</code></p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context, error::DynError, logger::Logger, pr_info,
};
fn main() -> Result<(), DynError> {
// Create a context.
let ctx = Context::new()?;
// Create a node.
let node = ctx.create_node("my_listener", None, Default::default())?;
// Create a subscriber.
let subscriber = node.create_subscriber::<std_msgs::msg::String>("my_topic", None)?;
// Create a logger.
let logger = Logger::new("my_listener");
// Create a selector.
let mut selector = ctx.create_selector()?;
// Add a callback function.
selector.add_subscriber(
subscriber,
Box::new(move |msg| {
pr_info!(logger, "receive: {}", msg.data);
}),
);
// Spin.
loop {
selector.wait()?;
}
}</code></pre></pre>
<h4 id="my_listener-in-detail"><a class="header" href="#my_listener-in-detail"><code>my_listener</code> in Detail</a></h4>
<p>Similar to the publisher,
<code>create_subscriber</code> creates a subscriber.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a subscriber.
let subscriber = node.create_subscriber::<std_msgs::msg::String>("my_topic", None)?;
<span class="boring">}</span></code></pre></pre>
<p>The arguments are as follows.</p>
<ul>
<li><code>"my_topic"</code> : the name of the topic to which the subscriber is subscribing.</li>
<li><code>None</code> : QoS of the subscriber. Discussed in a later chapter.</li>
</ul>
<p>To add and invoke a callback function.
We need to create a selector,
which can wait some events and invoke callback functions of the events.
A selector is similar to <code>select</code> or <code>epoll</code> function,
and equivalent to a executer of ROS2.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a selector.
let mut selector = ctx.create_selector()?;
// Add a callback function.
selector.add_subscriber(
subscriber,
Box::new(move |msg| {
pr_info!(logger, "receive: {}", msg.data);
}),
);
// Spin.
loop {
selector.wait()?;
}
<span class="boring">}</span></code></pre></pre>
<p>The arguments of <code>add_subscriber</code> method are as follows.</p>
<ul>
<li><code>subscriber</code> : the subscriber.</li>
<li><code>Box::new(move |msg| { pr_info!(logger, "receive: {}", msg.data); })</code> : the callback function.</li>
<li><code>false</code> : the callback function is called only once or not. If <code>false</code> is passed, the callback function is invoked every time and forever.</li>
</ul>
<p><code>selector.wait()</code> wait events.
To receive events forever, use infinite loop.</p>
<h3 id="create-my_listenerpackagexml"><a class="header" href="#create-my_listenerpackagexml">Create <code>my_listener/package.xml</code></a></h3>
<p><code>package.xml</code> is almost same as above.
The only difference is the name of the package,
which is <code>my_listener</code>.</p>
<p><code>pubsub/src/my_listener/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>my_listener</name>
<version>0.0.0</version>
<description>My Listener in Rust</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<depend>std_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<h3 id="execute-the-listener"><a class="header" href="#execute-the-listener">Execute the Listener</a></h3>
<p>Before compiling and executing, execute <code>my_talker</code> in other terminal,
and don't forget to load the setting of ROS2 as mentioned above.
The compilation can be done as follows.</p>
<pre><code class="language-text">$ cd pubsub
$ colcon build --cargo-args --release
</code></pre>
<p>To execute <code>my_listener</code>, load the setting of our projects and
execute it by using <code>ros2</code> command as follows.</p>
<pre><code class="language-text">$ . ./install/setup.bash
$ ros2 run my_listener my_listener
[INFO] [1656050459.231579900] [my_listener]: receive: Hello, World!: cnt = 4
[INFO] [1656050460.231831200] [my_listener]: receive: Hello, World!: cnt = 5
[INFO] [1656050461.232120000] [my_listener]: receive: Hello, World!: cnt = 6
</code></pre>
<p>Nicely done!
We are receiving messages sent from <code>my_talker</code>.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="timer"><a class="header" href="#timer">Timer</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/timers">Source code</a>.</p>
<p>This tutorial does not use <code>colcon</code> to build.
We use only <code>cargo</code>, which is a Rust's standard build system.</p>
<p>Don't forget loading ROS2's environment as follows.
If you already done so, you do not need this.</p>
<pre><code class="language-text">$ . /opt/ros/iron/setup.bash
</code></pre>
<h2 id="wall-timer"><a class="header" href="#wall-timer">Wall-timer</a></h2>
<p>A wall-timer is a timer which periodically invoked.
This section describes how to use a wall-timer.</p>
<p>Let's create a package by using a <code>cargo</code> as follows.</p>
<pre><code class="language-text">$ cargo new wall_timer
$ cd wall_timer
</code></pre>
<p>Then, add <code>safe_drive</code> to the dependencies of <code>Cargo.toml</code>.</p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
</code></pre>
<p>The following code is an example using a wall-timer.
The important method is <code>Selector::add_wall_timer()</code> which takes
a name, a duration, and a callback function.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context, error::DynError, logger::Logger, msg::common_interfaces::std_msgs, pr_info,
};
use std::{rc::Rc, time::Duration};
fn main() -> Result<(), DynError> {
// Create a context, a node, a subscriber, a publisher, and a selector.
let ctx = Context::new()?;
let node = ctx.create_node("my_node", None, Default::default())?;
let subscriber = node.create_subscriber::<std_msgs::msg::UInt64>("my_topic", None)?;
let publisher = node.create_publisher::<std_msgs::msg::UInt64>("my_topic", None)?;
let mut selector = ctx.create_selector()?;
// Create a logger.
// To share this by multiple callback functions, use Rc.
let logger = Rc::new(Logger::new("wall timer example"));
// Add a wall timer to publish periodically.
let mut cnt = Box::new(0);
let mut msg = std_msgs::msg::UInt64::new().unwrap();
let logger1 = logger.clone();
selector.add_wall_timer(
"publisher", // the name of timer
Duration::from_secs(1),
Box::new(move || {
msg.data = *cnt;
*cnt += 1;
publisher.send(&msg).unwrap();
pr_info!(logger1, "send: msg.data = {}", msg.data);
}),
);
// Add a subscriber.
selector.add_subscriber(
subscriber,
Box::new(move |msg| {
pr_info!(logger, "received: msg.data = {}", msg.data);
}),
);
// Spin.
loop {
selector.wait()?;
}
}</code></pre></pre>
<p>Timers can be set by a method of selector as follows,
and the timers will be invoked when calling the <code>Selector::wait()</code> methods.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>selector.add_wall_timer(
"publisher", // the name of timer
Duration::from_secs(1),
Box::new(move || {
msg.data = *cnt;
*cnt += 1;
publisher.send(&msg).unwrap();
pr_info!(logger1, "send: msg.data = {}", msg.data);
}),
);
<span class="boring">}</span></code></pre></pre>
<ul>
<li><code>"publisher"</code> is the name of this timer. The name is used for statistics. You can use any name.</li>
<li><code>Duration::from_secs(1)</code> is the duration for periodic invoking. This argument means the callback function is invoked every 1 second.</li>
<li><code>Box::new(move || ...)</code> is the callback function.</li>
</ul>
<p>There is a publisher invoked by a timer, and a subscriber in this code.
When executing this, transmission and reception will be confirmed as follows.</p>
<pre><code class="language-text">$ cargo run
[INFO] [1656557242.842509800] [wall timer example]: send: msg.data = 0
[INFO] [1656557242.842953300] [wall timer example]: received: msg.data = 0
[INFO] [1656557243.843103800] [wall timer example]: send: msg.data = 1
[INFO] [1656557243.843272900] [wall timer example]: received: msg.data = 1
[INFO] [1656557244.843574600] [wall timer example]: send: msg.data = 2
[INFO] [1656557244.844021200] [wall timer example]: received: msg.data = 2
[INFO] [1656557245.844349800] [wall timer example]: send: msg.data = 3
[INFO] [1656557245.844702900] [wall timer example]: received: msg.data = 3
</code></pre>
<h2 id="one-shot-timer"><a class="header" href="#one-shot-timer">One-shot Timer</a></h2>
<p>A wall-timer is invoked periodically,
but one-shot timer is invoked only once.
A one-shot can be set by the <code>Selector::add_timer()</code> method as follows.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{context::Context, error::DynError, logger::Logger, pr_info};
use std::{cell::RefCell, collections::VecDeque, rc::Rc, time::Duration};
pub fn main() -> Result<(), DynError> {
// Create a context, a publisher, and a logger.
let ctx = Context::new()?;
let mut selector = ctx.create_selector()?;
let logger = Rc::new(Logger::new("one-shot timer example"));
let queue = Rc::new(RefCell::new(VecDeque::new()));
// Add a one-shot timer.
let queue1 = queue.clone();
selector.add_timer(
Duration::from_secs(2),
Box::new(move || {
pr_info!(logger, "fired!");
// Insert a timer to the queue.
let mut q = queue1.borrow_mut();
let logger1 = logger.clone();
q.push_back((
Duration::from_secs(2),
(Box::new(move || pr_info!(logger1, "fired! again!"))),
));
}),
);
// Spin.
loop {
{
// Set timers.
let mut q = queue.borrow_mut();
while let Some((dur, f)) = q.pop_front() {
selector.add_timer(dur, f);
}
}
selector.wait()?;
}
}</code></pre></pre>
<p><code>Selector::add_timer()</code> does not take the name,
but other arguments are same as <code>Selector::add_wall_timer()</code>.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>selector.add_timer(
Duration::from_secs(2),
Box::new(move || ...),
);
<span class="boring">}</span></code></pre></pre>
<ul>
<li><code>Duration::from_secs(2)</code> is a duration indicating when the timer will be invoked.</li>
<li><code>Box::new(move || ...)</code> is the callback function.</li>
</ul>
<p>This code reenables a timer in the callback function.
To reenable, the callback takes a <code>queue</code> and
timers in the <code>queue</code> is reenabled in the spin as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Spin.
loop {
{
// Set timers.
let mut q = queue.borrow_mut();
while let Some((dur, f)) = q.pop_front() {
selector.add_timer(dur, f);
}
}
selector.wait()?;
}
<span class="boring">}</span></code></pre></pre>
<p>The important thing is that the borrowed resources must be released.
To release definitely, the code fraction borrowing the <code>queue</code> is surrounded by braces.</p>
<p>The following is a execution result of this code.</p>
<pre><code>$ cargo run
[INFO] [1657070943.324438900] [one-shot timer example]: fired!
[INFO] [1657070945.324675600] [one-shot timer example]: fired! again!
</code></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="multi-threaded-publish-and-subscribe"><a class="header" href="#multi-threaded-publish-and-subscribe">Multi-threaded Publish and Subscribe</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/mt_pubsub">Source code</a>.</p>
<p>Previous chapters use a selector to wait messages.
A selector can be used by only a single thread.
This means previous implementation is single-threaded.</p>
<p>To execute tasks concurrently, we can use the async/await feature of Rust.
By using this, we can implement multi-threaded applications.
In this chapter, we will describe how to use <code>safe_drive</code> with async/await.
We use <code>async_std</code> as a asynchronous library,
but you can use <code>Tokio</code> instead.</p>
<h2 id="creating-projects"><a class="header" href="#creating-projects">Creating Projects</a></h2>
<p>Before implementing, we need to prepare projects as follows.</p>
<pre><code class="language-text">$ mkdir -p mt_pubsub/src
$ cd mt_pubsub/src
$ cargo new publishers
$ cargo new subscribers
</code></pre>
<p>The <code>mt_pubsub</code> is the root directory of this project,
and we created <code>publishers</code> and <code>subscribers</code> of Rust's projects.
At the moment, the following directories is present.</p>
<div class="table-wrapper"><table><thead><tr><th>Directories</th><th>What?</th></tr></thead><tbody>
<tr><td>mt_pubsub/src/publishers</td><td>publishers in Rust</td></tr>
<tr><td>mt_pubsub/src/subscribers</td><td>subscribers in Rust</td></tr>
</tbody></table>
</div>
<h2 id="common-configuration"><a class="header" href="#common-configuration">Common Configuration</a></h2>
<p>Then, we have to create or edit the following files for basic configurations.</p>
<div class="table-wrapper"><table><thead><tr><th>Files</th><th>What?</th></tr></thead><tbody>
<tr><td>mt_pubsub/src/publishers/Cargo.toml</td><td>for Cargo</td></tr>
<tr><td>mt_pubsub/src/publishers/package.xml</td><td>for ROS2</td></tr>
<tr><td>mt_pubsub/src/publishers/build.rs</td><td>for rustc</td></tr>
<tr><td>mt_pubsub/src/subscribers/Cargo.toml</td><td>for Cargo</td></tr>
<tr><td>mt_pubsub/src/subscribers/package.xml</td><td>for ROS2</td></tr>
<tr><td>mt_pubsub/src/subscribers/build.rs</td><td>for rustc</td></tr>
<tr><td>mt_pubsub/src/Cargo.toml</td><td>for Cargo's workspace</td></tr>
</tbody></table>
</div>
<p>To enable rust-analyzer in the <code>mt_pubsub</code> directory and reduce the compilation time,
prepare workspace's <code>Cargo.toml</code> as follows.</p>
<p><code>mt_pubsub/src/Cargo.toml</code></p>
<pre><code class="language-toml">[workspace]
members = ["publishers", "subscribers"]
</code></pre>
<p><code>package.xml</code>s are almost same as <a href="./pubsub.html">Publish and Subscribe</a>.
If you cannot understand what these files do,
please go back to the previous chapter.</p>
<p><code>publishers/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>publishers</name>
<version>0.0.0</version>
<description>MT-Publishers</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<depend>std_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<p><code>subscribers/package.xml</code></p>
<pre><code class="language-xml"> <name>subscribers</name>
<description>MT-Subscribers</description>
</code></pre>
<p>To use <code>async_std</code>, we have to update <code>Cargo.toml</code> as follows.</p>
<p><code>Cargo.toml</code></p>
<pre><code class="language-toml">[dependencies]
async-std = { version = "1", features = ["attributes"] }
safe_drive = "0.4"
std_msgs = { path = "/tmp/safe_drive_tutorial/mt_pubsub/std_msgs" }
[package.metadata.ros]
msg = ["std_msgs"]
msg_dir = "/tmp/safe_drive_tutorial/mt_pubsub"
safe_drive_version = "0.3"
</code></pre>
<h2 id="publishers"><a class="header" href="#publishers">Publishers</a></h2>
<p>The <code>publishers</code> publishes messages to 2 topics periodically.
This create 2 tasks.
One is send a message every 500ms,
and another is send a message every 250ms.
The code of the <code>publishers</code> is as follows.</p>
<p><code>mt_pubsub/src/publishers/src/main.rs</code></p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{context::Context, error::DynError};
use std::time::Duration;
#[async_std::main]
async fn main() -> Result<(), DynError> {
// Create a context and a node.
let ctx = Context::new()?;
let node = ctx.create_node("publishers", None, Default::default())?;
// Create publishers.
let publisher1 = node.create_publisher::<std_msgs::msg::String>("topic1", None)?;
let publisher2 = node.create_publisher::<std_msgs::msg::String>("topic2", None)?;
// Create a task which sends "Hello, World!".
let task1 = async_std::task::spawn(async move {
let mut msg = std_msgs::msg::String::new().unwrap();
msg.data.assign("Hello, World!");
for _ in 0..50 {
publisher1.send(&msg).unwrap(); // Send a message.
async_std::task::sleep(Duration::from_millis(500)).await; // Sleep 500ms.
}
});
// Create a task which sends "Hello, Universe!".
let task2 = async_std::task::spawn(async move {
let mut msg = std_msgs::msg::String::new().unwrap();
msg.data.assign("Hello, Universe!");
for _ in 0..100 {
publisher2.send(&msg).unwrap(); // Send a message.
async_std::task::sleep(Duration::from_millis(250)).await; // Sleep 250ms.
}
});
task1.await;
task2.await;
Ok(())
}</code></pre></pre>
<p>The <code>async_std::task::spawn</code> creates a asynchronous task,
which is similar to a thread.
The following is a excerpt creating a task which sends "Hello, World!"
to "topic1" every 500ms.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a task which sends "Hello, World!".
let task1 = async_std::task::spawn(async move {
let mut msg = std_msgs::msg::String::new().unwrap();
msg.data.assign("Hello, World!");
for _ in 0..50 {
publisher1.send(&msg).unwrap(); // Send a message.
async_std::task::sleep(Duration::from_millis(500)).await; // Sleep 500ms.
}
});
<span class="boring">}</span></code></pre></pre>
<p>This excerpt sends a message by <code>Publisher::send</code> and sleep by <code>async_std::task::sleep</code>.
Note that this uses <code>async_std::task::sleep</code> instead of <code>std::thread::sleep</code>,
because the former is non-blocking but the the latter is blocking.
Calling blocking functions should be avoided in asynchronous tasks.</p>
<h2 id="subscribers"><a class="header" href="#subscribers">Subscribers</a></h2>
<p>Then, let's implement the <code>subscribers</code>.
The main function is almost same as previous one.</p>
<p><code>mt_pubsub/src/subscribers/src/main</code></p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context, error::DynError, logger::Logger, pr_info, topic::subscriber::Subscriber,
};
#[async_std::main]
async fn main() -> Result<(), DynError> {
// Create a context and a node.
let ctx = Context::new()?;
let node = ctx.create_node("subscribers", None, Default::default())?;
// Create subscribers.
let subscriber1 = node.create_subscriber::<std_msgs::msg::String>("topic1", None)?;
let subscriber2 = node.create_subscriber::<std_msgs::msg::String>("topic2", None)?;
// Receive messages.
let task1 = async_std::task::spawn(receiver(subscriber1));
let task2 = async_std::task::spawn(receiver(subscriber2));
task1.await?;
task2.await?;
Ok(())
}
async fn receiver(mut subscriber: Subscriber<std_msgs::msg::String>) -> Result<(), DynError> {
let logger = Logger::new(subscriber.get_topic_name());
loop {
// Receive a message
let msg = subscriber.recv().await?;
pr_info!(logger, "{}", msg.data);
}
}</code></pre></pre>
<p><code>Subscriber::recv</code> is an asynchronous function to receive a message.
To receive asynchronously, use the <code>.await</code> keyword.
If there is a message to be received, <code>recv().await</code> returns the message immediately.
Otherwise, it yields the execution to another task and sleeps until arriving a message.</p>
<h3 id="modification-for-timeout"><a class="header" href="#modification-for-timeout">Modification for Timeout</a></h3>
<p>By using a timeout mechanism provided by asynchronous libraries,
we can implement receiving with timeout.
Timeout can be implemented as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>use async_std::future::timeout;
use safe_drive::pr_warn;
use std::time::Duration;
async fn receiver(mut subscriber: Subscriber<std_msgs::msg::String>) -> Result<(), DynError> {
let logger = Logger::new(subscriber.get_topic_name());
loop {
// Receive a message with 3s timeout.
match timeout(Duration::from_secs(3), subscriber.recv()).await {
Ok(result) => pr_info!(logger, "received: {}", result?.data),
Err(_) => {
// Timed out. Finish receiving.
pr_warn!(logger, "timeout");
break;
}
}
}
Ok(())
}
<span class="boring">}</span></code></pre></pre>
<p><code>async_std::timeout</code> is a function to represent timeout.
<code>timeout(Duration::from_secs(3), subscriber.recv()).await</code> calls <code>subscriber.recv()</code> asynchronously,
but it will be timed out after 3s later.</p>
<h2 id="execution"><a class="header" href="#execution">Execution</a></h2>
<p>First, execute <code>publishers</code> in a terminal application window as follows.</p>
<pre><code class="language-text">$ cd mt_pubsub
$ colcon build --cargo-args --release
$ . ./install/setup.bash
$ ros2 run publishers publishers
</code></pre>
<p>Then, execute <code>subscribers</code> in another terminal application window as follows.
This uses timeout for receiving.</p>
<pre><code class="language-text">$ cd mt_pubsub.
$ . ./install/setup.bash
$ ros2 run subscribers subscribers
[INFO] [1657076046.969809600] [topic2]: received: Hello, Universe!
[INFO] [1657076047.220104100] [topic2]: received: Hello, Universe!
[INFO] [1657076047.447426100] [topic1]: received: Hello, World!
[INFO] [1657076047.470348600] [topic2]: received: Hello, Universe!
[INFO] [1657076047.721980900] [topic2]: received: Hello, Universe!
[WARN] [1657076050.448393200] [topic1]: timeout
[WARN] [1657076050.722433800] [topic2]: timeout
</code></pre>
<p>Nicely done!
We are sending and receiving messages asynchronously.
In addition to that, the timeouts work correctly.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="user-defined-data-structure"><a class="header" href="#user-defined-data-structure">User Defined Data Structure</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/msgtest">Source code</a>.</p>
<p>Until previous tutorial, we used pre-defined message types.
In this tutorial, we will describe how to define user defined types.</p>
<h2 id="create-project-directory"><a class="header" href="#create-project-directory">Create Project Directory</a></h2>
<p>Then create a project directory as follows.</p>
<pre><code class="language-text">$ mkdir -p msgtest/src
</code></pre>
<p>Throughout this tutorial, we will create 4 packages as follows.</p>
<div class="table-wrapper"><table><thead><tr><th>packages</th><th>description</th></tr></thead><tbody>
<tr><td>msgtest/src/my_interfaces</td><td>defining types of ROS2</td></tr>
<tr><td>msgtest/src/talker</td><td>a publisher</td></tr>
<tr><td>msgtest/src/listener</td><td>a subscriber</td></tr>
</tbody></table>
</div>
<h2 id="workspaces-cargotoml"><a class="header" href="#workspaces-cargotoml">Workspace's <code>Cargo.toml</code></a></h2>
<p>The workspace's <code>Cargo.toml</code> should be created as follows.</p>
<p><code>msgtest/src/Cargo.toml</code></p>
<pre><code class="language-toml">[workspace]
members = ["talker", "listener"]
</code></pre>
<p>Then, create projects as follows.</p>
<pre><code class="language-text">$ cd msgtest/src
$ cargo new talker
$ cargo new listener
</code></pre>
<h2 id="define-user-defined-type"><a class="header" href="#define-user-defined-type">Define User Defined Type</a></h2>
<p>To define message types, we have to create a ROS2's package,
and create a '.msg' files.
The package can be created in the ordinary way of ROS2 as follows.</p>
<pre><code class="language-text">$ cd msgtest/src
$ ros2 pkg create --build-type ament_cmake my_interfaces
$ cd my_interfaces
$ mkdir msg
$ cd msg
</code></pre>
<h3 id="primitive-type-my_interfacesmsgmymsgmsg"><a class="header" href="#primitive-type-my_interfacesmsgmymsgmsg">Primitive Type: <code>my_interfaces/msg/MyMsg.msg</code></a></h3>
<p>Then create a file, <code>msgtest/src/my_interfaces/msg/MyMsg.msg</code>, as follows.</p>
<pre><code class="language-text">int32 integer_value
int32[] unbounded_integer_array
int32[5] five_integers_array
int32[<=5] up_to_five_integers_array
</code></pre>
<p>There are 4 values in this type.</p>
<ul>
<li><code>integer_value</code> : a value of the <code>int32</code> type</li>
<li><code>unbounded_integer_array</code> : an unbounded array of the <code>int32</code> type</li>
<li><code>five_integers_array</code> : an array which size is 5 of the <code>int32</code> type</li>
<li><code>up_to_five_integers_array</code> : an array whose size is up to 5 of the <code>int32</code> type</li>
</ul>
<h3 id="using-user-defiend-type-my_interfacesmsgmymsgsmsg"><a class="header" href="#using-user-defiend-type-my_interfacesmsgmymsgsmsg">Using User Defiend Type: <code>my_interfaces/msg/MyMsgs.msg</code></a></h3>
<p>We can use the <code>MyMsg</code> previously defined in another message type, <code>msgtest/src/my_interfaces/msg/MyMsgs.msg</code>, as follows.</p>
<pre><code class="language-text">MyMsg msg1
MyMsg msg2
</code></pre>
<h3 id="string-type-my_interfacesmsgmymsgstrmsg"><a class="header" href="#string-type-my_interfacesmsgmymsgstrmsg">String Type: <code>my_interfaces/msg/MyMsgStr.msg</code></a></h3>
<p>A size of an array can be specified as described above,
a length of a string can be also specified.
For example, <code>string<=10</code> is a type of string,
but its length is up to 10.</p>
<p>We prepare <code>msgtest/src/my_interfaces/msg/MyMsgStr.msg</code> as follows.</p>
<pre><code class="language-text">string message
string[2] static_array_str
string[] dynamic_array_str
string[<=3] bounded_array_str
string<=10 bounded_str
string<=10[2] static_array_bounded_str
string<=10[] dynamic_array_bounded_str
string<=10[<=3] bounded_array_bounded_str
</code></pre>
<h3 id="edit-my_interfacescmakeliststxt"><a class="header" href="#edit-my_interfacescmakeliststxt">Edit <code>my_interfaces/CMakeLists.txt</code></a></h3>
<p>To generate C or C++ files and libraries for used defined types,
we have to edit <code>CMakeLists.txt</code> as follows.</p>
<p><code>msgtest/src/my_interfaces/CMakeLists.txt</code></p>
<pre><code class="language-cmake">find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/MyMsg.msg"
"msg/MyMsgs.msg"
"msg/MyMsgStr.msg"
)
</code></pre>
<p>We have to specify messages files in <code>CMakeLists.txt</code>.</p>
<h3 id="edit-my_interfacespackagexml"><a class="header" href="#edit-my_interfacespackagexml">Edit <code>my_interfaces/package.xml</code></a></h3>
<p>We also have to edit <code>package.xml</code> as follows.</p>
<p><code>msgtest/src/my_interfaces/package.xml</code></p>
<pre><code class="language-xml"><build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
</code></pre>
<h2 id="user-defined-type-in-rust"><a class="header" href="#user-defined-type-in-rust">User Defined Type in Rust</a></h2>
<p>Primitive types are translated into Rust's types as follows.</p>
<div class="table-wrapper"><table><thead><tr><th>ROS2</th><th>Rust</th></tr></thead><tbody>
<tr><td>bool</td><td>bool</td></tr>
<tr><td>byte</td><td>u8</td></tr>
<tr><td>char</td><td>i8</td></tr>
<tr><td>int8</td><td>i8</td></tr>
<tr><td>uint8</td><td>u8</td></tr>
<tr><td>int16</td><td>i16</td></tr>
<tr><td>uint16</td><td>u16</td></tr>
<tr><td>int32</td><td>i32</td></tr>
<tr><td>uint32</td><td>u32</td></tr>
<tr><td>int64</td><td>i64</td></tr>
<tr><td>uint64</td><td>u64</td></tr>
<tr><td>float32</td><td>f32</td></tr>
<tr><td>float64</td><td>f64</td></tr>
<tr><td>string</td><td>safe_drive::msg::RosString</td></tr>
</tbody></table>
</div>
<h3 id="generated-types"><a class="header" href="#generated-types">Generated Types</a></h3>
<p>Array types are generated as follows.</p>
<div class="table-wrapper"><table><thead><tr><th>ROS2</th><th>Rust</th></tr></thead><tbody>
<tr><td>int32[5]</td><td>[i32; 5]</td></tr>
<tr><td>int32[]</td><td>safe_drive::msg::I32Seq<0></td></tr>
<tr><td>int32[<=5]</td><td>safe_drive::msg::I32Seq<5></td></tr>
</tbody></table>
</div>
<p><code>0</code> of <code>I32Seq<0></code> indicates unbounded, and <code>5</code> of <code>I32Seq<5></code> indicates less than or equal to 5.
So, <code>MyMsg</code> and <code>MyMsgs</code> are generated as follows.</p>
<h2 id="talker"><a class="header" href="#talker">Talker</a></h2>
<p>Let's implement a talker which publishes <code>MyMsgs</code> periodically.</p>
<h3 id="edit-talkercargotoml"><a class="header" href="#edit-talkercargotoml">Edit <code>talker/Cargo.toml</code></a></h3>
<p>To use the generated types in Rust, we have to edit <code>Cargo.toml</code> as follows.
The most important thing is to add <code>my_interfaces</code>, which defines message types we use.</p>
<pre><code class="language-toml"># msgtest/src/talker/Cargo.toml
[dependencies]
safe_drive = "0.4"
my_interfaces = { path = "/tmp/safe_drive_tutorial/msgtest/my_interfaces" }
[package.metadata.ros]
msg = ["my_interfaces"]
msg_dir = "/tmp/safe_drive_tutorial/msgtest"
safe_drive_version = "0.3"
</code></pre>
<h3 id="create-talkerpackagexml"><a class="header" href="#create-talkerpackagexml">Create <code>talker/package.xml</code></a></h3>
<p>Then create <code>package.xml</code> as follows.</p>
<p><code>msgtest/src/talker/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>talker</name>
<version>0.0.0</version>
<description>Talker in Rust</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>my_interfaces</depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<p>Don't forget <code><depend>my_interfaces</depend></code>.</p>
<h3 id="generated-files"><a class="header" href="#generated-files">Generated Files</a></h3>
<p>When you run <code>colcon</code>, it generate <code>my_interfaces</code> in Rust.</p>
<pre><code class="language-text">$ cd msgtest
$ colcon build --cargo-args --release
</code></pre>
<p>Then, you can find Rust's files as follows.</p>
<p><code>/tmp/safe_drive_tutorial/msgtest/my_interfaces/src/msg/my_msg.rs</code></p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>#[repr(C)]
#[derive(Debug)]
pub struct MyMsg {
pub integer_value: i32,
pub unbounded_integer_array: safe_drive::msg::I32Seq<0>,
pub five_integers_array: [i32; 5],
pub up_to_five_integers_array: safe_drive::msg::I32Seq<5>,
}
<span class="boring">}</span></code></pre></pre>
<p><code>/tmp/safe_drive_tutorial/msgtest/my_interfaces/src/msg/my_msgs.rs</code></p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>#[repr(C)]
#[derive(Debug)]
pub struct MyMsgs {
pub msg1: crate::msg::my_msg::MyMsg,
pub msg2: crate::msg::my_msg::MyMsg,
}
<span class="boring">}</span></code></pre></pre>
<h3 id="edit-talkersrcmainrs"><a class="header" href="#edit-talkersrcmainrs">Edit <code>talker/src/main.rs</code></a></h3>
<p>If you want to know how to implement a subscriber or a publisher, please see <a href="./pubsub.html">a tutorial of Pub/Sub</a>. This section describes how to handle a messages generated by <code>ros2msg_to_rs</code>.</p>
<p><code>msgtest/src/talker/src/main.rs</code></p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context,
error::DynError,
logger::Logger,
msg::{I32Seq, RosStringSeq},
pr_info,
};
use std::time::Duration;
fn main() -> Result<(), DynError> {
// Create a context.
let ctx = Context::new()?;
// Create a node.
let node = ctx.create_node("talker", None, Default::default())?;
// Create a publisher.
let publisher = node.create_publisher::<my_interfaces::msg::MyMsgs>("my_topic", None)?;
// Create a logger.
let logger = Logger::new("talker");
// Create a message
let my_msg1 = create_message()?;
let my_msg2 = create_message()?;
let mut my_msgs = my_interfaces::msg::MyMsgs::new().ok_or("failed to create MyMsgs")?;
my_msgs.msg1 = my_msg1;
my_msgs.msg2 = my_msg2;
loop {
pr_info!(logger, "send: {:?}", my_msgs); // Print log.
// Send a message.
publisher.send(&my_msgs)?;
std::thread::sleep(Duration::from_secs(1));
}
}
fn create_message() -> Result<my_interfaces::msg::MyMsg, DynError> {
let mut my_msg = my_interfaces::msg::MyMsg::new().unwrap();
my_msg.integer_value = 10;
// int32[5] five_integers_array
my_msg.five_integers_array[0] = 11;
my_msg.five_integers_array[1] = 13;
my_msg.five_integers_array[2] = 49;
my_msg.five_integers_array[3] = 55;
my_msg.five_integers_array[4] = 19;
// int32[] unbounded_integer_array
let mut msgs = I32Seq::new(3).unwrap();
let ref_msgs = msgs.as_slice_mut();
ref_msgs[0] = 6;
ref_msgs[1] = 7;
ref_msgs[2] = 8;
my_msg.unbounded_integer_array = msgs;
// int32[<=5] up_to_five_integers_array
let mut msgs = I32Seq::new(2).unwrap();
let ref_msgs = msgs.as_slice_mut();
ref_msgs[0] = 2;
ref_msgs[1] = 3;
my_msg.up_to_five_integers_array = msgs;
Ok(my_msg)
}</code></pre></pre>
<p>Primitive types and arrays can be handles in the ordinary way of Rust as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>my_msg.integer_value = 10;
// int32[5] five_integers_array
my_msg.five_integers_array[0] = 11;
my_msg.five_integers_array[1] = 13;
my_msg.five_integers_array[2] = 49;
my_msg.five_integers_array[3] = 55;
my_msg.five_integers_array[4] = 19;
<span class="boring">}</span></code></pre></pre>
<p>To access elements of unbounded or bounded arrays,
we can use <code>as_slice_mut()</code> or <code>as_slice()</code> methods as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// unbounded or unbounded array
let mut msgs = I32Seq::new(3).unwrap();
let ref_msgs = msgs.as_slice_mut();
<span class="boring">}</span></code></pre></pre>
<p><code>as_slice_mut()</code> returns a mutable slice,
you can thus update the elements of the array via the slice.</p>
<h2 id="listener"><a class="header" href="#listener">Listener</a></h2>
<p>Let's then implement a listener which receive messages published by the talker.</p>
<h3 id="edit-listenercargotoml"><a class="header" href="#edit-listenercargotoml">Edit <code>listener/Cargo.toml</code></a></h3>
<p>The listener also requires <code>my_interfaces</code>, and edit <code>Cargo.toml</code> as follows.</p>
<pre><code class="language-toml"># msgtest/src/listener/Cargo.toml
[dependencies]
safe_drive = "0.4"
my_interfaces = { path = "/tmp/safe_drive_tutorial/msgtest/my_interfaces" }
[package.metadata.ros]
msg = ["my_interfaces"]
msg_dir = "/tmp/safe_drive_tutorial/msgtest"
safe_drive_version = "0.3"
</code></pre>
<h3 id="create-listenerpackagexml"><a class="header" href="#create-listenerpackagexml">Create <code>listener/package.xml</code></a></h3>
<p>Then create <code>package.xml</code> as follows.</p>
<p><code>msgtest/src/listener/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>listener</name>
<version>0.0.0</version>
<description>Listener in Rust</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>my_interfaces</depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<p>Don't forget <code><depend>my_interfaces</depend></code>.</p>
<h3 id="edit-listenersrcmainrs"><a class="header" href="#edit-listenersrcmainrs">Edit <code>listener/src/main.rs</code></a></h3>
<p>The listener can also be implemented straightforwardly as follows.</p>
<p><code>msgtest/src/listener/src/main.rs</code></p>
<pre><pre class="playground"><code class="language-rust">use my_interfaces;
use safe_drive::{context::Context, error::DynError, logger::Logger, pr_info};
fn main() -> Result<(), DynError> {
// Create a context.
let ctx = Context::new()?;
// Create a node.
let node = ctx.create_node("listener", None, Default::default())?;
// Create a subscriber.
let subscriber = node.create_subscriber::<my_interfaces::msg::MyMsgs>("my_topic", None)?;
// Create a logger.
let logger = Logger::new("listener");
// Create a selector.
let mut selector = ctx.create_selector()?;
pr_info!(logger, "listening");
// Add a callback function.
selector.add_subscriber(
subscriber,
Box::new(move |msg| {
let msg = &msg.msg1;
pr_info!(logger, "message: {}", msg.integer_value);
for msg in msg.five_integers_array.iter() {
pr_info!(logger, "five_integers_array: {}", msg);
}
for msg in msg.unbounded_integer_array.iter() {
pr_info!(logger, "unbounded_integer_array: {}", msg);
}
for msg in msg.up_to_five_integers_array.iter() {
pr_info!(logger, "up_to_five_integers_array: {}", msg);
}
}),
);
// Spin.
loop {
selector.wait()?;
}
}</code></pre></pre>
<h2 id="compilation-and-execution"><a class="header" href="#compilation-and-execution">Compilation and Execution</a></h2>
<p>Now, we can compile and execute the talker and listener. Let's do it!</p>
<h3 id="compile"><a class="header" href="#compile">Compile</a></h3>
<p>The compilation can be performed by using <code>colcon</code> as follows.</p>
<pre><code class="language-text">$ cd msgtest
$ colcon build --cargo-args --release
$ . ./install/setup.bash
</code></pre>
<h3 id="execute-listener"><a class="header" href="#execute-listener">Execute Listener</a></h3>
<p>The listener can be executed by using <code>ros2</code> as follows.
After executing the talker, it receives messages as follows.</p>
<pre><code class="language-text">$ ros2 run listener listener
[INFO] [1658305910.013449534] [listener]: listening
[INFO] [1658305914.359791460] [listener]: message: 10
[INFO] [1658305914.359839382] [listener]: five_integers_array: 11
[INFO] [1658305914.359867532] [listener]: five_integers_array: 13
[INFO] [1658305914.359880763] [listener]: five_integers_array: 49
[INFO] [1658305914.359889731] [listener]: five_integers_array: 55
[INFO] [1658305914.359900913] [listener]: five_integers_array: 19
[INFO] [1658305914.359912534] [listener]: unbounded_integer_array: 6
[INFO] [1658305914.359924084] [listener]: unbounded_integer_array: 7
[INFO] [1658305914.359936971] [listener]: unbounded_integer_array: 8
[INFO] [1658305914.359946479] [listener]: up_to_five_integers_array: 2
[INFO] [1658305914.359959422] [listener]: up_to_five_integers_array: 3
</code></pre>
<h3 id="execute-talker"><a class="header" href="#execute-talker">Execute Talker</a></h3>
<p>To execute the talker, open a new terminal window and execute it as follows.</p>
<pre><code class="language-text">$ cd msgtest
$ . ./install/setup.bash
$ ros2 run talker talker
[INFO] [1658305913.359250753] [talker]: send: MyMsgs { msg1: MyMsg { integer_value: 10, unbounded_integer_array: I32Seq(rosidl_runtime_c__int32__Sequence { data: 0x55a0653f7aa0, size: 3, capacity: 3 }), five_integers_array: [11, 13, 49, 55, 19], up_to_five_integers_array: I32Seq(rosidl_runtime_c__int32__Sequence { data: 0x55a0653efaa0, size: 2, capacity: 2 }) }, msg2: MyMsg { integer_value: 10, unbounded_integer_array: I32Seq(rosidl_runtime_c__int32__Sequence { data: 0x55a0653f7e30, size: 3, capacity: 3 }), five_integers_array: [11, 13, 49, 55, 19], up_to_five_integers_array: I32Seq(rosidl_runtime_c__int32__Sequence { data: 0x55a0653f7e50, size: 2, capacity: 2 }) }
</code></pre>
<p>Nicely done! Now, we can define new types and handle the types in Rust.</p>
<h2 id="string-type"><a class="header" href="#string-type">String Type</a></h2>
<p>Arrays of string are bit different from arrays of primitive types.
<code>string</code> is unbounded string, and <code>string<=5</code> is bounded string whose length is up to 5.
So, there are arrays for unbounded and bounded strings as follows; <code>msg</code> is <code>safe_drive::msg</code>.</p>
<div class="table-wrapper"><table><thead><tr><th>ROS</th><th>Rust</th></tr></thead><tbody>
<tr><td>string</td><td>msg::RosString<0></td></tr>
<tr><td>string[]</td><td>msg::StringSeq<0, 0></td></tr>
<tr><td>string[<=5]</td><td>msg::StringSeq<0, 5></td></tr>
<tr><td>string[10]</td><td>[msg::RosString<0>; 10]</td></tr>
<tr><td>string<=5</td><td>msg::RosString<5></td></tr>
<tr><td>string<=5[<=10]</td><td>msg::StringSeq<5, 10></td></tr>
<tr><td>string<=5[10]</td><td>[msg::RosString<5>; 10]</td></tr>
</tbody></table>
</div>
<p><code>RosString<0></code> is a type of unbounded string, and <code>RosString<5></code> is a type of bounded string whose length is less than or equal to 5.
<code>5</code> of <code>StringSeq<5, 10></code> indicates the length of a string is less than or equal to 5,
and <code>10</code> of it indicates the length of the array is less than or equal to 10.</p>
<p>For example, the following ROS2 message type can be translated into the <code>MyMsgStr</code> as follows.</p>
<pre><code class="language-text">string message
string[2] static_array_str
string[] dynamic_array_str
string[<=3] bounded_array_str
string<=10 bounded_str
string<=10[2] static_array_bounded_str
string<=10[] dynamic_array_bounded_str
string<=10[<=3] bounded_array_bounded_str
</code></pre>
<p><code>/tmp/safe_drive_tutorial/msgtest/my_interfaces/src/msg/my_msg_str.rs</code></p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>#[repr(C)]
#[derive(Debug)]
pub struct MyMsgStr {
pub message: safe_drive::msg::RosString<0>,
pub static_array_str: [safe_drive::msg::RosString<0>; 2],
pub dynamic_array_str: safe_drive::msg::RosStringSeq<0, 0>,
pub bounded_array_str: safe_drive::msg::RosStringSeq<0, 3>,
pub bounded_str: safe_drive::msg::RosString<10>,
pub static_array_bounded_str: [safe_drive::msg::RosString<10>; 2],
pub dynamic_array_bounded_str: safe_drive::msg::RosStringSeq<10, 0>,
pub bounded_array_bounded_str: safe_drive::msg::RosStringSeq<10, 3>,
}
<span class="boring">}</span></code></pre></pre>
<p>To access to elements of string arrays,
we can use <code>as_slice_mut()</code> or <code>as_slice_mut()</code> as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>fn _create_message_str() -> Result<my_interfaces::msg::MyMsgStr, DynError> {
let mut my_msg = my_interfaces::msg::MyMsgStr::new().unwrap();
// string message
my_msg.message.assign("Hello, World!");
// string[2] static_array_str
my_msg.static_array_str[0].assign("static array 0");
my_msg.static_array_str[1].assign("static array 1");
// string[] dynamic_array_str
let mut msgs = RosStringSeq::new(3).ok_or("failed to create string")?;
let ref_msgs = msgs.as_slice_mut();
ref_msgs[0].assign("dynamic array 0");
ref_msgs[1].assign("dynamic array 1");
ref_msgs[2].assign("dynamic array 2");
my_msg.dynamic_array_str = msgs;
// string[<=3] bounded_array_str
let mut msgs = RosStringSeq::new(2).ok_or("failed to create string")?;
let ref_msgs = msgs.as_slice_mut();
ref_msgs[0].assign("bounded array 0");
ref_msgs[1].assign("bounded array 1");
my_msg.bounded_array_str = msgs;
// string<=10 bounded_str
my_msg.bounded_str.assign("Hello!");
// string<=10[2] static_array_bounded_str
my_msg.static_array_bounded_str[0].assign("msg1");
my_msg.static_array_bounded_str[1].assign("msg2");
// string<=10[] dynamic_array_bounded_str
let mut msgs = RosStringSeq::new(3).ok_or("failed to create string")?;
let ref_msgs = msgs.as_slice_mut();
ref_msgs[0].assign("msg3");
ref_msgs[1].assign("msg4");
ref_msgs[2].assign("msg5");
my_msg.dynamic_array_bounded_str = msgs;
// string<=10[<=3] bounded_array_bounded_str
let mut msgs = RosStringSeq::new(2).ok_or("failed to create string")?;
let ref_msgs = msgs.as_slice_mut();
ref_msgs[0].assign("msg3");
ref_msgs[1].assign("msg5");
my_msg.bounded_array_bounded_str = msgs;
Ok(my_msg)
}
<span class="boring">}</span></code></pre></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="service"><a class="header" href="#service">Service</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/srvtest">Source code</a>.</p>
<p>A service is a communication consisting requests and responses.
There are a server and clients for a service as follows.</p>
<pre class="mermaid">graph TD;
Server--response-->Client1;
Server--response-->Client2;
Server--response-->Client3;
Client1--request-->Server;
Client2--request-->Server;
Client3--request-->Server;
</pre>
<p>A client sends a request and the server replies the request.
In this tutorial, we will describe how to implement a client and a server in Rust by using <code>safe_drive</code>.</p>
<h2 id="create-base-files"><a class="header" href="#create-base-files">Create Base Files</a></h2>
<p>In this tutorial, we prepare 3 Rust's projects and 1 C's project.
The following table shows the directories we use.</p>
<div class="table-wrapper"><table><thead><tr><th>Directories</th><th>Description</th></tr></thead><tbody>
<tr><td>srvtest/src/server</td><td>server in Rust</td></tr>
<tr><td>srvtest/src/client</td><td>client in Rust</td></tr>
<tr><td>srvtest/src/srvmsg</td><td>message type</td></tr>
</tbody></table>
</div>
<p><code>srvmsg</code> is a ROS2's project to define a user defined type for a service we implement.</p>
<pre><code class="language-text">$ mkdir -p srvtest/src
$ cd srvtest/src
$ cargo new server
$ cargo new client
$ ros2 pkg create --build-type ament_cmake srvmsg
</code></pre>
<p>In addition to that, create the workspace's <code>Cargo.toml</code> as follows.</p>
<p><code>srvtest/src/Cargo.toml</code></p>
<pre><code class="language-toml">[workspace]
members = [ "client", "server"]
</code></pre>
<h2 id="define-protocol"><a class="header" href="#define-protocol">Define Protocol</a></h2>
<p>First of all, let's define a protocol for a service.
ROS2 provides a special format to define a protocol,
and it should be described in a <code>.srv</code> file.</p>
<p>Usually, <code>.srv</code> files are placed in a <code>srv</code> directory.
So, we create <code>srv</code> directory as follows.</p>
<pre><code class="language-text">$ cd srvtest/src/srvmsg
$ mkdir srv
</code></pre>
<h3 id="create-srvmsgsrvaddtwointssrv"><a class="header" href="#create-srvmsgsrvaddtwointssrv">Create <code>srvmsg/srv/AddTwoInts.srv</code></a></h3>
<p>Then, create <code>AddTwoInts.srv</code> file in which a protocol is specified as follows.</p>
<pre><code class="language-text">uint32 x
uint32 y
---
uint32 result
</code></pre>
<p><code>uint32 x</code> and <code>uint32 y</code> above <code>--</code> are types which must be
included in a request, and <code>uint32 result</code> is a type which must be
included in a response.
We will implement a server which takes 2 integer values
and returns the summation of the values.</p>
<h3 id="edit-srvmsgcmakeliststxt"><a class="header" href="#edit-srvmsgcmakeliststxt">Edit <code>srvmsg/CMakeLists.txt</code></a></h3>
<p>To generate shared libraries from <code>AddTwoInts.srv</code>,
<code>CMakeLists.txt</code> must be updated as follows.</p>
<pre><code class="language-cmake"># srvtest/src/srvmsg/CMakeLists.txt
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"srv/AddTwoInts.srv"
)
</code></pre>
<h3 id="edit-srvmsgpackagexml"><a class="header" href="#edit-srvmsgpackagexml">Edit <code>srvmsg/package.xml</code></a></h3>
<p>In addition to that, the following lines must be added to <code>package.xml</code>.</p>
<p><code>srvtest/src/srvmsg/package.xml</code></p>
<pre><code class="language-xml"><build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
</code></pre>
<h2 id="server"><a class="header" href="#server">Server</a></h2>
<p>A server can be implemented in a straightforward way.</p>
<h3 id="edit-servercargotoml"><a class="header" href="#edit-servercargotoml">Edit <code>server/Cargo.toml</code></a></h3>
<p>To generate Rust types from <code>.srv</code> files,
we have to edit <code>Cargo.toml</code> as follows.</p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
srvmsg = { path = "/tmp/safe_drive_tutorial/srvtest/srvmsg" }
tokio = { version = "1", features = ["full"] }
[package.metadata.ros]
msg = ["srvmsg"]
msg_dir = "/tmp/safe_drive_tutorial/srvtest"
safe_drive_version = "0.3"
</code></pre>
<h3 id="create-serverpackagexml"><a class="header" href="#create-serverpackagexml">Create <code>server/package.xml</code></a></h3>
<p><code>package.xml</code> is also required as follows.</p>
<p><code>srvtest/src/server/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>server</name>
<version>0.0.0</version>
<description>Server in Rust</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>srvmsg</depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<p>Don't forget <code><depend>srvmsg</depend></code>.</p>
<h2 id="generate-types"><a class="header" href="#generate-types">Generate Types</a></h2>
<p><code>AddTwoInts.srv</code> will be translated to <code>struct AddTwoInts</code> as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>#[derive(Debug)]
pub struct AddTwoInts;
impl ServiceMsg for AddTwoInts {
type Request = AddTwoInts_Request;
type Response = AddTwoInts_Response;
fn type_support() -> *const rcl::rosidl_service_type_support_t {
unsafe {
rosidl_typesupport_c__get_service_type_support_handle__srvmsg__srv__AddTwoInts()
}
}
}
<span class="boring">}</span></code></pre></pre>
<p><code>struct AddTwoInts</code> implements <code>ServiceMsg trait</code>.
<code>ServiceMsg::Request</code> and <code>ServiceMsg::Response</code> are types of request and response, respectively.
<code>AddTwoInts_Request</code> and <code>AddTowInts_Response</code> are as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>#[repr(C)]
#[derive(Debug)]
pub struct AddTwoInts_Request {
pub x: u32,
pub y: u32,
}
#[repr(C)]
#[derive(Debug)]
pub struct AddTwoInts_Response {
pub result: u32,
}
<span class="boring">}</span></code></pre></pre>
<h3 id="edit-serversrcmainrs"><a class="header" href="#edit-serversrcmainrs">Edit <code>server/src/main.rs</code></a></h3>
<p>You have to create a server by <code>create_server()</code> method and register a callback function to a selector as follows.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{context::Context, error::DynError, logger::Logger, pr_error, qos::Profile};
use srvmsg::srv::{AddTwoInts, AddTwoInts_Response};
fn main() -> Result<(), DynError> {
// Create a context.
let ctx = Context::new()?;
// Create a node.
let node = ctx.create_node("server_node", None, Default::default())?;
// Create a server.
let server = node.create_server::<AddTwoInts>("my_service", Some(Profile::default()))?;
// Create a selector.
let mut selector = ctx.create_selector()?;
// Create a logger.
let logger = Logger::new("server");
selector.add_server(
server,
Box::new(move |msg, _header| {
let mut response = AddTwoInts_Response::new().unwrap();
pr_error!(logger, "recv: {:?}", msg);
response.result = msg.x + msg.y;
response
}),
);
loop {
selector.wait()?; // Spin.
}
}</code></pre></pre>
<p>Let's dig into detail.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a server.
let server = node.create_server::<AddTwoInts>("my_service", Some(Profile::default()))?;
<span class="boring">}</span></code></pre></pre>
<p><code>AddTwoInts</code> of <code>create_server::<AddTwoInts></code> indicates the protocol of the server.
The arguments of <code>"my_service"</code> and <code>Some(Profile::default())</code> are the service name and QoS.
If you pass <code>None</code> instead of <code>Some(Profile::default())</code>, <code>Profile::default()</code> is used.</p>
<p>The callback was passed as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>selector.add_server(
server,
Box::new(move |msg, _header| {
let mut response = AddTwoInts_Response::new().unwrap();
pr_error!(logger, "recv: {:?}", msg);
response.result = msg.x + msg.y;
response
}),
);
<span class="boring">}</span></code></pre></pre>
<p>The callback function must take a message sent by a client and a header including sequence number, time, etc.
<code>msg</code>'s types is <code>AddTwoInts_Request</code> and a value of <code>AddTwoInts_Response</code>, which is a response, must be returned.</p>
<h2 id="client"><a class="header" href="#client">Client</a></h2>
<h3 id="edit-clientcargotoml"><a class="header" href="#edit-clientcargotoml">Edit <code>client/Cargo.toml</code></a></h3>
<p><code>safe_drive</code>, and <code>tokio</code> must be added to <code>Cargo.toml</code> as follows.</p>
<p><code>srvtest/src/client/Cargo.toml</code></p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
srvmsg = { path = "/tmp/safe_drive_tutorial/srvtest/srvmsg" }
tokio = { version = "1", features = ["full"] }
[package.metadata.ros]
msg = ["srvmsg"]
msg_dir = "/tmp/safe_drive_tutorial/srvtest"
safe_drive_version = "0.3"
</code></pre>
<h3 id="create-clientpackagexml"><a class="header" href="#create-clientpackagexml">Create <code>client/package.xml</code></a></h3>
<p><code>package.xml</code> is also required as follows.</p>
<p><code>srvtest/src/client/package.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>client</name>
<version>0.0.0</version>
<description>Client in Rust</description>
<maintainer email="yuuki.takano@tier4.jp">Yuuki Takano</maintainer>
<license>Apache License 2.0</license>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>srvmsg</depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>
</code></pre>
<p>Don't forget <code><depend>srvmsg</depend></code>.</p>
<h3 id="edit-clientsrcmainrs"><a class="header" href="#edit-clientsrcmainrs">Edit <code>client/src/main.rs</code></a></h3>
<p>We recommend to use async/await to implement a client,
because a client wait a response, but when the response is replied is unpredictable.
In this tutorial, we use <a href="https://tokio.rs/">Tokio</a>, which is the most popular asynchronous library of Rust.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context, error::DynError, logger::Logger, pr_error, pr_info, pr_warn, qos::Profile,
};
use srvmsg::srv::{AddTwoInts, AddTwoInts_Request};
use std::time::Duration;
use tokio::time::timeout;
#[tokio::main]
async fn main() -> Result<(), DynError> {
// Create a context and a node.
let ctx = Context::new()?;
let node = ctx.create_node("client", None, Default::default())?;
let logger = Logger::new("client");
// Create a client.
let mut client = node.create_client::<AddTwoInts>("my_service", Some(Profile::default()))?;
let mut n = 0;
loop {
let mut request = AddTwoInts_Request::new().unwrap();
request.x = n;
request.y = n + 1;
n += 1;
// Send a request.
let client_rcv = client.send(&request)?;
// Receive a request.
let mut receiver = client_rcv.recv();
match timeout(Duration::from_secs(1), &mut receiver).await {
Ok(Ok((c, response, _header))) => {
pr_info!(logger, "received {:?}", response);
client = c;
}
Ok(Err(e)) => {
pr_error!(logger, "error: {e}");
return Err(e);
}
Err(elapsed) => {
pr_warn!(logger, "timeout: {elapsed}");
client = receiver.give_up();
}
}
tokio::time::sleep(Duration::from_secs(1)).await;
}
}</code></pre></pre>
<p>Because a response will be never returned,
we use <code>tokio::time::timeout</code> to receive a response.
<code>timeout(Duration::from_secs(1), &mut receiver).await</code>
takes a duration and a awaitable future.
The awaitable future can be taken by <code>client_rcv.recv()</code>.</p>
<p>Note that it uses <code>tokio::time::sleep</code> instead of
<code>std::thread::sleep</code> because to avoid calling blocking functions.</p>
<p><code>client.send()</code> consumes <code>client</code> and it returns <code>client_recv</code>
to receive a response.
<code>client_rcv.recv()</code> consumes <code>client_recv</code> and <code>client_rcv.recv().await</code>
returns new client, a response, and a header.
The new client must be used to send next request.</p>
<p>This means that you cannot ignore receiving a response.
If you forget to receive a response,
you cannot send any request again,
because you need to get a new client by receiving a response..
Otherwise, you encountered compilation errors.</p>
<h2 id="execution-1"><a class="header" href="#execution-1">Execution</a></h2>
<p>First of all, you have to compile it and execute a server as follows.</p>
<pre><code class="language-text">$ cd srvtest
$ colcon build --cargo-args --release
$ . ./install/setup.bash
$ ros2 run server server
</code></pre>
<p>Then, in another terminal, execute a client as follows.</p>
<pre><code class="language-text">$ cd srvtest
$ . ./install/setup.bash
$ ros2 run client client
[WARN] [1659604527.720730018] [client]: timeout: deadline has elapsed
[INFO] [1659604528.722220697] [client]: received AddTwoInts_Response { result: 3 }
[INFO] [1659604529.723525686] [client]: received AddTwoInts_Response { result: 5 }
[INFO] [1659604530.724820326] [client]: received AddTwoInts_Response { result: 7 }
</code></pre>
<p>Nicely done!
We used async/await for the client,
and it can be used for the server as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>async { server.recv().await };
<span class="boring">}</span></code></pre></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="parameter"><a class="header" href="#parameter">Parameter</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/params">Source code</a>.</p>
<p>This chapter introduces how to use parameters.
A node can have parameters as follows.</p>
<pre class="mermaid">graph TD;
NodeA --> ParamA1:i64;
NodeA --> ParamA2:bool;
NodeA --> ParamA3:String;
NodeB --> ParamB1:f64;
NodeB --> ParamB2:f64;
</pre>
<p>In this figure, NodeA has 3 parameters whose types are
<code>i64</code>, <code>bool</code>, and <code>String</code>, respectively,
and NodeB has 2 parameters whose types are <code>f64</code>.
Parameters can be read/write from external nodes.</p>
<p>To receive a notification of updating a parameter,
we can use a callback function or async/await.
In this chapter, we will explain how to handle it.</p>
<h2 id="packages"><a class="header" href="#packages">Packages</a></h2>
<p>We will prepare 2 packages as follows.</p>
<pre><code class="language-text">$ mkdir params
$ cd params
$ cargo new param_server
$ cargo new async_param_server
</code></pre>
<p><code>param_server</code> explains a callback based parameter handling, and <code>async_param_server</code> explains an async/await based.</p>
<p>To manage 2 packages, let's prepare <code>Cargo.toml</code> file for a workspace as follows.</p>
<p><code>params/Cargo.toml</code></p>
<pre><code class="language-toml">[workspace]
members = ["param_server", "async_param_server"]
</code></pre>
<p>The following table shows files we use in this chapter.</p>
<div class="table-wrapper"><table><thead><tr><th>File</th><th>What?</th></tr></thead><tbody>
<tr><td>params/param_server/</td><td>callback based parameter server</td></tr>
<tr><td>params/async_param_server/</td><td>async/await based parameter server</td></tr>
<tr><td>params/Cargo.toml</td><td>workspace configuration</td></tr>
</tbody></table>
</div>
<h2 id="type-of-parameter"><a class="header" href="#type-of-parameter">Type of Parameter</a></h2>
<p>Before explaining handlers,
let's see types of parameters.</p>
<p>The type of parameter value is defined by <code>safe_drive::parameter::Value</code> as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pub enum Value {
NotSet,
Bool(bool),
I64(i64),
F64(f64),
String(String),
VecBool(Vec<bool>),
VecI64(Vec<i64>),
VecU8(Vec<u8>),
VecF64(Vec<f64>),
VecString(Vec<String>),
}
<span class="boring">}</span></code></pre></pre>
<p>This means that <code>i64</code> is valid,
but <code>i8</code>, <code>i32</code>, and other user defined types are invalid.</p>
<p>A parameter is associated with a descriptor of <code>safe_drive::parameter::Descriptor</code> as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pub struct Descriptor {
pub description: String,
pub additional_constraints: String,
pub read_only: bool,
pub dynamic_typing: bool,
pub floating_point_range: Option<FloatingPointRange>,
pub integer_range: Option<IntegerRange>,
}
<span class="boring">}</span></code></pre></pre>
<p>So, a parameter and parameters can be represented by <code>safe_drive::parameter::{Parameter, Parameters}</code> as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pub struct Parameter {
pub descriptor: Descriptor,
pub value: Value,
}
pub struct Parameters { /* omitted private fields */ }
<span class="boring">}</span></code></pre></pre>
<p>and a parameter server can be represented by
<code>safe_drive::parameter::ParameterServer</code> as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pub struct ParameterServer {
pub params: Arc<RwLock<Parameters>>
// omitted private fields
}
<span class="boring">}</span></code></pre></pre>
<p>In summary, a parameter server can be represented as follows.</p>
<pre class="mermaid">graph TD;
ParameterServer --> Parameters;
Parameters --> Parameter;
Parameter --> Descriptor;
Parameter --> Value;
</pre>
<h2 id="parameter-setting-and-waiting-update-by-callback"><a class="header" href="#parameter-setting-and-waiting-update-by-callback">Parameter Setting and Waiting Update by Callback</a></h2>
<p>We will explain how to set parameters,
and how to wait updating by using a callback function.</p>
<h3 id="edit-param_servercargotoml"><a class="header" href="#edit-param_servercargotoml">Edit <code>param_server/Cargo.toml</code></a></h3>
<p>Add <code>safe_drive</code> to the dependencies section of <code>Cargo.toml</code> as follows.</p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
</code></pre>
<h3 id="edit-param_serversrcmainrs"><a class="header" href="#edit-param_serversrcmainrs">Edit <code>param_server/src/main.rs</code></a></h3>
<p><code>param_server</code> can be implemented as follows.
This sets 2 parameters up and waits updating.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context,
error::DynError,
logger::Logger,
parameter::{Descriptor, Parameter, Value},
pr_info,
};
fn main() -> Result<(), DynError> {
// Create a context and a node.
let ctx = Context::new()?;
let node = ctx.create_node("param_server", None, Default::default())?;
// Create a parameter server.
let param_server = node.create_parameter_server()?;
{
// Set parameters.
let mut params = param_server.params.write(); // Write lock
// Statically typed parameter.
params.set_parameter(
"my_flag".to_string(), // parameter name
Value::Bool(false), // value
false, // read only?
Some("my flag's description".to_string()), // description
)?;
// Dynamically typed parameter.
params.set_dynamically_typed_parameter(
"my_dynamic_type_flag".to_string(), // parameter name
Value::Bool(false), // value
false, // read only?
Some("my dynamic type flag's description".to_string()), // description
)?;
// Add Directly from Parameter struct
let parameter_to_set = Parameter {
descriptor: Descriptor {
description: "my parameter description".to_string(), // parameter description
additional_constraints: "my parameter addutional_constraints".to_string(), // parameter additional constraints
read_only: false, // read only ?
dynamic_typing: false, // static or Dynamic
floating_point_range: None, // floating point range
integer_range: None, // integer point range
},
value: Value::Bool(false), // value
};
params.add_parameter(
("my parameter").to_string(), // name
parameter_to_set, // parameter
)?;
}
// Create a logger and a selector.
let logger = Logger::new("param_server");
let mut selector = ctx.create_selector()?;
// Add a callback function to the parameter server.
selector.add_parameter_server(
param_server,
Box::new(move |params, updated| {
// Print updated parameters.
let mut keys = String::new();
for key in updated.iter() {
let value = &params.get_parameter(key).unwrap().value;
keys = format!("{keys}{key} = {}, ", value);
}
pr_info!(logger, "updated parameters: {keys}");
}),
);
// Spin.
loop {
selector.wait()?;
}
}</code></pre></pre>
<h3 id="param_server-in-detail"><a class="header" href="#param_server-in-detail"><code>param_server</code> in Detail</a></h3>
<p>First of all, we have to create a parameter server by <code>create_parameter_server()</code> method as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create a parameter server.
let param_server = node.create_parameter_server()?;
<span class="boring">}</span></code></pre></pre>
<p>Then set parameters as follows.
To update parameters, we have to acquire a write lock
for mutual exclusion by <code>write()</code> method.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>{
// Set parameters.
let mut params = param_server.params.write(); // Write lock
// Statically typed parameter.
params.set_parameter(
"my_flag".to_string(), // parameter name
Value::Bool(false), // value
false, // read only?
Some("my flag's description".to_string()), // description
)?;
// Dynamically typed parameter.
params.set_dynamically_typed_parameter(
"my_dynamic_type_flag".to_string(), // parameter name
Value::Bool(false), // value
false, // read only?
Some("my dynamic type flag's description".to_string()), // description
)?;
// Add Directly from Parameter struct
let parameter_to_set = Parameter {
descriptor: Descriptor {
description: "my parameter description".to_string(), // parameter description
additional_constraints: "my parameter addutional_constraints".to_string(), // parameter additional constraints
read_only: false, // read only ?
dynamic_typing: false, // static or Dynamic
floating_point_range: None, // floating point range
integer_range: None, // integer point range
},
value: Value::Bool(false), // value
};
params.add_parameter(
("my parameter").to_string(), // name
parameter_to_set, // parameter
)?;
}
<span class="boring">}</span></code></pre></pre>
<p>To set a statically typed parameters, use <code>set_parameter()</code>.
A statically typed parameter cannot be updated
by a value whose type is different from original type.</p>
<p>To set a dynamically typed parameters, use <code>set_dynamically_typed_parameter()</code>.
A dynamically typed parameter can be updated by an arbitrary type.</p>
<p>To set directly from the Parameter struct, use <code>add_parameter()</code>.
A Parameter struct can contain additional_constraints.</p>
<p>Finally, register a callback function to wait updating
parameters as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Add a callback function to the parameter server.
selector.add_parameter_server(
param_server,
Box::new(move |params, updated| {
// Print updated parameters.
let mut keys = String::new();
for key in updated.iter() {
let value = &params.get_parameter(key).unwrap().value;
keys = format!("{keys}{key} = {}, ", value);
}
pr_info!(logger, "updated parameters: {keys}");
}),
);
// Spin.
loop {
selector.wait()?;
}
<span class="boring">}</span></code></pre></pre>
<p>1st argument of the closure, <code>params</code>, is a value of parameters,
and 2nd argument, <code>updated</code> is a value containing updated parameters.</p>
<h3 id="execute-param_server"><a class="header" href="#execute-param_server">Execute <code>param_server</code></a></h3>
<p>Then, let's execute <code>param_server</code> and get/set a parameter.
First, execute <code>param_server</code> in a terminal application window as follows.</p>
<pre><code class="language-text">$ cargo run --bin param_server
Finished dev [unoptimized + debuginfo] target(s) in 0.01s
Running `target/debug/param_server`
[INFO] [1669873997.622330908] [param_server]: updated parameters: my_flag = true,
</code></pre>
<p>Then, get and set the parameter by using <code>ros2</code> command in another terminal application window as follows.</p>
<pre><code class="language-text">$ ros2 param get param_server my_flag
Boolean value is: False
$ ros2 param set param_server my_flag True
Set parameter successful
$ ros2 param get param_server my_flag
Boolean value is: True
$ ros2 param set param_server my_flag 10
Setting parameter failed: failed type checking: dst = Bool, src = I64
</code></pre>
<p>We can get and set boolean values,
but integer value cannot be set because <code>my_flag</code> is boolean type
and statically typed.</p>
<hr />
<h2 id="asynchronous-wait"><a class="header" href="#asynchronous-wait">Asynchronous Wait</a></h2>
<p>Then, we explain async/await based parameter server.</p>
<h3 id="edit-async_param_servercargotoml"><a class="header" href="#edit-async_param_servercargotoml">Edit <code>async_param_server/Cargo.toml</code></a></h3>
<p>Add <code>safe_drive</code> and <code>tokio</code> to the dependencies section of <code>Cargo.toml</code> as follows.</p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
tokio = { version = "1", features = ["full"] }
</code></pre>
<h3 id="edit-async_param_serversrcmainrs"><a class="header" href="#edit-async_param_serversrcmainrs">Edit <code>async_param_server/src/main.rs</code></a></h3>
<p><code>async_param_server</code> can be implemented as follows.
This sets 2 parameters up and waits updating.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context,
error::DynError,
logger::Logger,
parameter::{Descriptor, Parameter, Value},
pr_info,
};
#[tokio::main]
async fn main() -> Result<(), DynError> {
// Create a context and a node.
let ctx = Context::new()?;
let node = ctx.create_node("async_param_server", None, Default::default())?;
// Create a parameter server.
let mut param_server = node.create_parameter_server()?;
{
// Set parameters.
let mut params = param_server.params.write(); // Write lock
// Statically typed parameter.
params.set_parameter(
"my_flag".to_string(), // parameter name
Value::Bool(false), // value
false, // read only?
Some("my flag's description".to_string()), // description
)?;
// Dynamically typed parameter.
params.set_dynamically_typed_parameter(
"my_dynamic_type_flag".to_string(), // parameter name
Value::Bool(false), // value
false, // read only?
Some("my dynamic type flag's description".to_string()), // description
)?;
// Add Directly from Parameter struct
let parameter_to_set = Parameter {
descriptor: Descriptor {
description: "my parameter description".to_string(), // parameter description
additional_constraints: "my parameter addutional_constraints".to_string(), // parameter additional constraints
read_only: false, // read only ?
dynamic_typing: false, // static or Dynamic
floating_point_range: None, // floating point range
integer_range: None, // integer point range
},
value: Value::Bool(false), // value
};
params.add_parameter(
("my parameter").to_string(), // name
parameter_to_set, // parameter
)?;
}
// Create a logger.
let logger = Logger::new("async_param_server");
loop {
// Wait update asynchronously.
let updated = param_server.wait().await?;
let params = param_server.params.read(); // Read lock
// Print updated parameters.
let mut keys = String::new();
for key in updated.iter() {
let value = &params.get_parameter(key).unwrap().value;
keys = format!("{keys}{key} = {}, ", value);
}
pr_info!(logger, "updated parameters: {keys}");
}
}</code></pre></pre>
<p>Important things are only following 2 lines.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Wait update asynchronously.
let updated = param_server.wait().await?;
let params = param_server.params.read(); // Read lock
<span class="boring">}</span></code></pre></pre>
<p>To wait updating, use <code>wait().await</code>
and acquire a read lock by <code>read()</code> method
to read parameters.
<code>wait().await</code> returns updated parameters.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="zero-copy-publish-and-subscribe"><a class="header" href="#zero-copy-publish-and-subscribe">Zero Copy Publish and Subscribe</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/zerocopy">Source code</a>.</p>
<p>In this chapter, we will introduce how to use zero copy communications by CycloneDDS.
To use CycloneDDS, please install it as <a href="http://docs.ros.org.ros.informatik.uni-freiburg.de/en/humble/Installation/DDS-Implementations/Working-with-Eclipse-CycloneDDS.html">Eclipse Cyclone DDS</a>.</p>
<h2 id="create-project"><a class="header" href="#create-project">Create Project</a></h2>
<p>First of all, create a project as follows.</p>
<pre><code>$ cargo new zerocpy
</code></pre>
<p>The files we use are as follows. <code>cyclonedds.xml</code> will be created and used later.</p>
<div class="table-wrapper"><table><thead><tr><th>Files</th><th>What?</th></tr></thead><tbody>
<tr><td>zerocopy/Cargo.toml</td><td>Cargo.toml</td></tr>
<tr><td>zerocopy/src/main.rs</td><td>main.rs</td></tr>
<tr><td>zerocopy/cyclonedds.xml</td><td>configuration of CycloneDDS</td></tr>
</tbody></table>
</div>
<p>Add <code>safe_drive</code> to dependencies section of <code>Cargo.toml</code> as follows.</p>
<p><code>Cargo.toml</code></p>
<pre><code class="language-toml">[dependencies]
safe_drive = "0.4"
</code></pre>
<h2 id="mainrs"><a class="header" href="#mainrs"><code>main.rs</code></a></h2>
<p><code>main.rs</code> can be implemented as follows,
but almost every lines are same as shown before.</p>
<p><code>main.rs</code></p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{context::Context, msg::common_interfaces::std_msgs};
use std::{error::Error, time::Duration};
const TOPIC_NAME: &str = "pubsub_loaned";
fn main() -> Result<(), Box<dyn Error + Sync + Send + 'static>> {
// create a context
let ctx = Context::new()?;
// create a subscribe node
let node_sub = ctx.create_node("loaned_sub_node", None, Default::default())?;
// create a publish node
let node_pub = ctx.create_node("loaned_pub_node", None, Default::default())?;
std::thread::sleep(Duration::from_millis(500));
// create a publisher and a subscriber
let subscriber = node_sub.create_subscriber::<std_msgs::msg::Bool>(TOPIC_NAME, None)?;
let publisher = node_pub.create_publisher::<std_msgs::msg::Bool>(TOPIC_NAME, None)?;
let mut loaned = publisher.borrow_loaned_message()?;
*loaned = std_msgs::msg::Bool::new().ok_or("failed to new Bool")?;
loaned.data = false;
publisher.send_loaned(loaned)?; // send message
std::thread::sleep(Duration::from_millis(500));
// wait messages
let mut selector = ctx.create_selector()?;
selector.add_subscriber(
subscriber,
Box::new(move |msg| {
assert!(!msg.data);
}),
);
selector.wait()?;
Ok(())
}</code></pre></pre>
<p>The important thing is using <code>borrow_loaned_message()</code> and <code>send_loaned()</code> methods as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>let mut loaned = publisher.borrow_loaned_message()?;
*loaned = std_msgs::msg::Bool::new().ok_or("failed to new Bool")?;
loaned.data = false;
publisher.send_loaned(loaned)?; // send message
<span class="boring">}</span></code></pre></pre>
<p><code>borrow_loaned_message()</code> borrows a memory region from CycloneDDS and
<code>send_loaned()</code> sends a message in the borrowed region.
<code>safe_drive</code> automatically check whether zero copy is available or not,
and it uses conventional copied APIs if zero copy is not available.</p>
<h2 id="setting-up-zero-copy"><a class="header" href="#setting-up-zero-copy">Setting-up Zero Copy</a></h2>
<p>To enable zero copy, please prepare cyclonedds.xml, which is a configuration file of CycloneDDS, as follows.
You can use arbitrary name for it.</p>
<p><code>cyclonedds.xml</code></p>
<pre><code class="language-xml"><?xml version="1.0" encoding="UTF-8" ?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/iceoryx/etc/cyclonedds.xsd">
<Domain id="any">
<SharedMemory>
<Enable>true</Enable>
<LogLevel>info</LogLevel>
</SharedMemory>
</Domain>
</CycloneDDS>
</code></pre>
<p><code><SharedMemory></code> tag indicates the configuration of zero copy.</p>
<p>To use zero copy enabled CycloneDDS, please set environment arguments as follows.</p>
<pre><code class="language-text">$ export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
$ export CYCLONEDDS_URI=file://path/to/cyclonedds.xml
</code></pre>
<p>In addition to that, CycloneDDS requires <code>iox-roudi</code> daemon to use zero copy.
It can be launched as follows.</p>
<pre><code class="language-text">$ iox-roudi
</code></pre>
<h2 id="execute"><a class="header" href="#execute">Execute</a></h2>
<p>After that, zero copy communications can be performed!</p>
<pre><code class="language-text">$ cargo run
</code></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="custom-memory-allocator"><a class="header" href="#custom-memory-allocator">Custom Memory Allocator</a></h1>
<p>Under construction.</p>
<pre><code class="language-text">$ mkdir custom_alloc
$ cargo new forwarder
$ cargo new requester
</code></pre>
<pre><code class="language-text">$ cat Cargo.toml
[workspace]
members = ["requester", "forwarder"]
</code></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="request-to-server-in-callback"><a class="header" href="#request-to-server-in-callback">Request to Server in Callback</a></h1>
<p><a href="https://github.com/tier4/safe_drive_tutorial/tree/main/pubsubsrv">Source code</a>.</p>
<p>In this chapter, we will introduce how to access a server in a callback function.
The code introduced here can be implemented by using async/await more beautifully.</p>
<h2 id="subscriber-and-client"><a class="header" href="#subscriber-and-client">Subscriber and Client</a></h2>
<p>The concept here is very simple.
We use 2 selectors for a callback function and accessing a server,
and <code>recv_timeout()</code> to receive a response from the server.</p>
<p>We only show Rust code of a publisher as follows.
Other files can be found in <a href="https://github.com/tier4/safe_drive_tutorial/tree/main/pubsubsrv">Source code</a>.</p>
<pre><pre class="playground"><code class="language-rust">use safe_drive::{
context::Context,
error::DynError,
logger::Logger,
msg::common_interfaces::{std_msgs, std_srvs},
pr_fatal, pr_info,
selector::Selector,
service::client::Client,
topic::subscriber::Subscriber,
RecvResult,
};
use std::time::Duration;
fn main() -> Result<(), DynError> {
// Create a context and a node.
let ctx = Context::new()?;
let node = ctx.create_node("listen_client", None, Default::default())?;
// Create 2 selectors.
let selector = ctx.create_selector()?;
let selector_client = ctx.create_selector()?;
// Create a subscriber, a client, and a logger.
let subscriber = node.create_subscriber::<std_msgs::msg::Empty>("pubsubsrv_topic", None)?;
let client = node.create_client::<std_srvs::srv::Empty>("pubsubsrv_service", None)?;
worker(selector, selector_client, subscriber, client)?;
Ok(())
}
fn worker(
mut selector: Selector,
mut selector_client: Selector,
subscriber: Subscriber<std_msgs::msg::Empty>,
client: Client<std_srvs::srv::Empty>,
) -> Result<(), DynError> {
let mut client = Some(client);
let logger = Logger::new("listen_client");
selector.add_subscriber(
subscriber,
Box::new(move |_msg| {
pr_info!(logger, "receive a message");
// Take the client.
let c = client.take().unwrap();
let request = std_srvs::srv::EmptyRequest::new().unwrap();
// Send a request.
let receiver = c.send(&request).unwrap();
// Receive a response.
match receiver.recv_timeout(Duration::from_millis(20), &mut selector_client) {
RecvResult::Ok((c, _response, _header)) => {
pr_info!(logger, "receive a response");
client = Some(c)
}
RecvResult::RetryLater(r) => client = Some(r.give_up()),
RecvResult::Err(e) => {
pr_fatal!(logger, "{e}");
panic!()
}
}
}),
);
loop {
selector.wait()?;
}
}</code></pre></pre>
<h2 id="in-detail"><a class="header" href="#in-detail">in Detail</a></h2>
<p>The important pieces are as follows.
This code create 2 selectors first.
<code>selector_client</code> is used for a service.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Create 2 selectors.
let selector = ctx.create_selector()?;
let selector_client = ctx.create_selector()?;
<span class="boring">}</span></code></pre></pre>
<p>In the callback function, <code>recv_timeout()</code> method, which takes
<code>selector_client</code>, is used as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Send a request.
let receiver = c.send(&request).unwrap();
// Receive a response.
match receiver.recv_timeout(Duration::from_millis(20), &mut selector_client) {
RecvResult::Ok((c, _response, _header)) => {
pr_info!(logger, "receive a response");
client = Some(c)
}
RecvResult::RetryLater(r) => client = Some(r.give_up()),
RecvResult::Err(e) => {
pr_fatal!(logger, "{e}");
panic!()
}
}
<span class="boring">}</span></code></pre></pre>
<p>In this callback function,
it sends a request to the server and receives a response
by <code>recv_timeout()</code> method.</p>
<h2 id="state-change"><a class="header" href="#state-change">State Change</a></h2>
<p>A service's state can be represented as follows.</p>
<pre class="mermaid">graph LR;
Start-->Send
Send-->Receive
Receive-->Send
</pre>
<p>To represent the state, <code>safe_drive</code> uses the type system of Rust.</p>
<p>First, a client is created as follows.
At that time, it must be <code>Send</code> state.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>let mut client = Some(client); // Send state.
<span class="boring">}</span></code></pre></pre>
<p><code>send()</code> method consumes the client and returns
<code>receiver</code>.
It means the state is changed from Send to Receive.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>let c = client.take().unwrap();
let receiver = c.send(&request).unwrap(); // Change state from Send to Receive.
<span class="boring">}</span></code></pre></pre>
<p><code>recv_timeout()</code> also consumes <code>receiver</code> and returns a new client
to send a new request if it successfully receives a response.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>// Receive a response.
match receiver.recv_timeout(Duration::from_millis(20), &mut selector_client) {
RecvResult::Ok((c, _response, _header)) => {
pr_info!(logger, "receive a response");
client = Some(c)
}
RecvResult::RetryLater(r) => client = Some(r.give_up()),
RecvResult::Err(e) => {
pr_fatal!(logger, "{e}");
panic!()
}
}
<span class="boring">}</span></code></pre></pre>
<p>When it has timed out, you can choose retrying or giving up.
This code chooses giving up by <code>give_up()</code> method.
<code>give_up()</code> methods consumes a receiver and return a new
client to send a new request.</p>
<p>This code will work, but we think using async/await is better than this because it is designed for asynchronous programming.
I recommend to rewrite this code by using async/await.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="contribution-guide"><a class="header" href="#contribution-guide">Contribution Guide</a></h1>
<p>This chapter explains <code>safe_drive</code>'s internal briefly to contribute to it.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="setting-up-for-contribution"><a class="header" href="#setting-up-for-contribution">Setting-up for Contribution</a></h1>
<h2 id="basic-setting-up"><a class="header" href="#basic-setting-up">Basic Setting-up</a></h2>
<p>See <a href="./setup.html">Setting-up</a> for basic setting-up.</p>
<h2 id="setting-up-development-environment"><a class="header" href="#setting-up-development-environment">Setting-up Development Environment</a></h2>
<p>To build <code>safe_drive</code>,
you need install <code>bindgen-cli</code> and <code>ros2msg_to_rs</code> as follows.</p>
<pre><code class="language-text">$ cargo install bindgen-cli
$ cargo install --git https://github.com/tier4/ros2msg_to_rs.git
</code></pre>
<p><code>bindgen_cli</code> is a transpiler from C to Rust,
and <code>ros2msg_to_rs</code> is also a transpiler from .msg and .srv to Rust.</p>
<p>If you want to contribute to documents you are reading now,
please install <code>mdbook</code> and <code>mdbook-mermaind</code> as follows.</p>
<pre><code class="language-text">$ cargo install mdbook
$ cargo install mdbook-mermaid
</code></pre>
<p>Finally, download <code>safe_drive</code> as follows.</p>
<pre><code class="language-text">$ git clone https://github.com/tier4/safe_drive
$ cd safe_drive
</code></pre>
<p>Following chapters introduce how to hack <code>safe_drive</code> in this directory.</p>
<h2 id="use-docker"><a class="header" href="#use-docker">Use Docker</a></h2>
<p>We provide Docker files in <a href="https://github.com/tier4/safe_drive/tree/main/docker">docker</a>.
You can use this to hack <code>safe_drive</code> as follows, alternatively.</p>
<pre><code class="language-text">$ git clone https://github.com/tier4/safe_drive.git
$ cd safe_drive/docker
$ docker compose build
$ docker compose up -d
$ docker exec -it docker-safe_drive-1 /bin/zsh
</code></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="build-and-test"><a class="header" href="#build-and-test">Build and Test</a></h1>
<p>Build and test can be done by using <code>make</code> as follows.</p>
<p>Build:</p>
<pre><code class="language-text">$ make
</code></pre>
<p>Test:</p>
<pre><code class="language-text">$ make test
</code></pre>
<p><code>make test</code> executes test codes in <a href="https://github.com/tier4/safe_drive/tree/main/tests">tests</a>,
and codes in documentation comment.</p>
<p><code>cargo test</code> may not work because it requires some environment variables
and some code generation.
Please see <a href="https://github.com/tier4/safe_drive/blob/main/Makefile">Makefile</a>.</p>
<p>Cleaning-up can be done as follows.</p>
<pre><code class="language-text">$ make clean
</code></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="editor-setting-up"><a class="header" href="#editor-setting-up">Editor Setting-up</a></h1>
<p><code>safe_drive</code> has features like <code>iron</code>, <code>humble</code> or <code>galactic</code>, which indicates ROS2 version.
We recommend pass one of a feature to enable editor's support.</p>
<p>If you use ROS2 humble and Visual Studio Code,
please add <code>iron</code> in <code>rust-analyzer -> cargo -> features</code> as follows.</p>
<pre><code class="language-json">{
"rust-analyzer.cargo.features": [
"iron"
]
}
</code></pre>
<p>Client applications not necessary to specify a feature of ROS2 version,
because <a href="https://github.com/tier4/safe_drive/blob/main/build.rs">build.rs</a> detects
ROS2 version from <code>ROS_DISTRO</code> environment variable.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="generating-messages-included-by-safe_drive"><a class="header" href="#generating-messages-included-by-safe_drive">Generating Messages Included by safe_drive</a></h1>
<p>For client applications, <code>safe_drive</code> provides a way to transpile from ROS2's .idl files to Rust crates by using <a href="https://github.com/tier4/safe_drive_msg">safe_drive_msg</a>.
<code>safe_drive</code> itself includes ROS2's some basic messages to handle parameter
servers.</p>
<p>The basic messages can be generated by <a href="https://github.com/tier4/ros2msg_to_rs">ros2msg_to_rs</a>,
and located in <a href="https://github.com/tier4/safe_drive/tree/main/src/msg">src/msg</a>.</p>
<p><code>safe_drive</code> contains <a href="https://github.com/ros2/common_interfaces.git">common_interfaces</a>,
<a href="https://github.com/ros2/unique_identifier_msgs.git">unique_identifier_msgs</a>,
and <a href="https://github.com/ros2/rcl_interfaces.git">rcl_interfaces</a>.
These messages can be transpiled as follows.
<code>{safe_drive}</code> of the following means a directory path to <code>safe_drive</code>.</p>
<pre><code class="language-text">$ git clone https://github.com/ros2/common_interfaces.git -b humble
$ ros2msg_to_rs --disable-common-interfaces -s crate -i common_interfaces -o {safe_drive}/src/msg/humble/common_interfaces
</code></pre>
<pre><code class="language-text">$ mkdir ros2msg && cd ros2msg
$ git clone https://github.com/ros2/unique_identifier_msgs.git -b humble
$ ros2msg_to_rs --disable-common-interfaces -s crate -i . -o {safe_drive}/src/msg/humble/ros2msg
</code></pre>
<pre><code class="language-text">$ git clone https://github.com/ros2/rcl_interfaces.git -b humble
$ rm -rf rcl_interfaces/test_msgs rcl_interfaces/builtin_interfaces
$ ros2msg_to_rs --disable-common-interfaces -s crate -i rcl_interfaces -o {safe_drive}/src/msg/humble/interfaces
</code></pre>
<p><code>-s crate</code> means <code>crate</code> is the name of top module.
<code>-i</code> and <code>-o</code> means input and output directories.
Because <code>safe_drive</code> defines <code>builtin_interfaces</code> internally, it must be removed before transpilation.</p>
<p>To support newer version of ROS2, these files should be updated.</p>
<div style="break-before: page; page-break-before: always;"></div><h1 id="c-apis"><a class="header" href="#c-apis">C APIs</a></h1>
<p>C APIs of ROS2 are defined in
<a href="https://github.com/tier4/safe_drive/blob/main/src/msg/humble/runtime_c.rs">src/msg/humble/runtime_c.rs</a>
and <a href="https://github.com/tier4/safe_drive/tree/main/src/rcl">src/rcl</a>.
These files are generated by Makefile in <a href="https://github.com/tier4/safe_drive/tree/main/supplements/bindgen">supplements/bindgen</a>.</p>
<h2 id="mt-unsafe-apis"><a class="header" href="#mt-unsafe-apis">MT Unsafe APIs</a></h2>
<p>MT unsafe APIs requires mutex to prevent data races.
So, these MT unsafe APIs must be redefined in <code>MTUnsafeFn</code> in <a href="https://github.com/tier4/safe_drive/blob/main/src/rcl.rs">src/rcl.rs</a>.
The redefined functions can be called via <code>rcl::MT_UNSAFE_FN</code>, which is a global variable, after locking.
For example, <code>rcl::rcl_guard_condition_init()</code> are defined as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pub(crate) static MT_UNSAFE_FN: Lazy<Mutex<MTUnsafeFn>> =
Lazy::new(|| Mutex::new(MTUnsafeFn::new()));
pub(crate) struct MTUnsafeFn;
impl MTUnsafeFn {
pub fn rcl_guard_condition_init(
&self,
guard_condition: *mut rcl_guard_condition_t,
context: *mut rcl_context_t,
options: rcl_guard_condition_options_t,
) -> RCLResult<()> {
ret_val_to_err(unsafe { self::rcl_guard_condition_init(guard_condition, context, options) })
}
}
<span class="boring">}</span></code></pre></pre>
<p>It can be called as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>let guard = rcl::MT_UNSAFE_FN.lock();
guard.rcl_guard_condition_init(
&mut guard_condition,
unsafe { context.as_ptr_mut() },
rcl::rcl_guard_condition_options_t { allocator },
)?;
<span class="boring">}</span></code></pre></pre>
<h2 id="mt-safe-apis"><a class="header" href="#mt-safe-apis">MT Safe APIs</a></h2>
<p>MT safe APIs are redefined in <code>MTSafeFn</code> in <a href="https://github.com/tier4/safe_drive/blob/main/src/rcl.rs">src/rcl.rs</a>.
For example, <code>rcl::rcl_shutdown()</code> is defined as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>pub(crate) struct MTSafeFn;
impl MTSafeFn {
pub fn rcl_shutdown(context: *mut rcl_context_t) -> RCLResult<()> {
ret_val_to_err(unsafe { self::rcl_shutdown(context) })
}
}
<span class="boring">}</span></code></pre></pre>
<p>It can be called without lock as follows.</p>
<pre><pre class="playground"><code class="language-rust"><span class="boring">#![allow(unused)]
</span><span class="boring">fn main() {
</span>rcl::MTSafeFn::rcl_shutdown(&mut self.context).unwrap();
<span class="boring">}</span></code></pre></pre>
<div style="break-before: page; page-break-before: always;"></div><h1 id="documentation"><a class="header" href="#documentation">Documentation</a></h1>
<p>You can contribute to documents you are reading now.
Documents are written in Markdown and located in <a href="https://github.com/tier4/safe_drive/tree/main/mdbook">mdbook</a>.
These Markdown files are compiled to HTML files and located in <a href="https://github.com/tier4/safe_drive/tree/main/docs">docs</a>,
and published at <a href="https://tier4.github.io/safe_drive/">https://tier4.github.io/safe_drive/</a>.</p>
<p>You can use (Mermaid)[https://mermaid.js.org/#/] notation in Markdown as follows.</p>
<pre class="mermaid">graph TD;
A-->B;
A-->C;
B-->D;
C-->D;
</pre>
<p>The compilation can be done by <code>make</code> as follows.</p>
<pre><code class="language-text">$ make doc
</code></pre>
<p>We are not native English speaker.
So, we need your help to improve documents!</p>
</main>
<nav class="nav-wrapper" aria-label="Page navigation">
<!-- Mobile navigation buttons -->
<div style="clear: both"></div>
</nav>
</div>
</div>
<nav class="nav-wide-wrapper" aria-label="Page navigation">
</nav>
</div>
<script>
window.playground_copyable = true;
</script>
<script src="elasticlunr.min.js"></script>
<script src="mark.min.js"></script>
<script src="searcher.js"></script>
<script src="clipboard.min.js"></script>
<script src="highlight.js"></script>
<script src="book.js"></script>
<!-- Custom JS scripts -->
<script src="mermaid.min.js"></script>
<script src="mermaid-init.js"></script>
<script>
window.addEventListener('load', function() {
window.setTimeout(window.print, 100);
});
</script>
</div>
</body>
</html>