Quick Start¶
Get ros-z running in under 5 minutes with this hands-on tutorial. Build a complete publisher-subscriber system to understand the core concepts through working code.
Tip
This guide assumes basic Rust knowledge. If you're new to Rust, complete the Rust Book first for the best experience.
Prerequisites:
- Rust 1.85+ (requires edition 2024) — install via rustup
- Tokio 1.x — ros-z requires an async runtime (added to
Cargo.tomlin Option 2 below) - No ROS 2 installation needed for the examples in this guide
Choose Your Path¶
There are two ways to get started with ros-z:
- Try the Examples — Clone the ros-z repository and run pre-built examples (fastest way to see it in action)
- Option 2: Create Your Own Project — Start a new Rust project with ros-z as a dependency
Option 1: Try the Examples¶
The quickest way to experience ros-z is to run the included examples from the repository.
Clone the Repository¶
Start the Eclipse Zenoh Router¶
ros-z uses a router-based architecture (matching ROS 2's rmw_zenoh — the ROS 2 middleware plugin for Zenoh), so you'll need to start a Zenoh router first. The router acts as a rendezvous point for all nodes: publishers and subscribers discover each other through it instead of via multicast.
Terminal 1 - Start the Router:
Run the Pub/Sub Example¶
Open two more terminals and navigate to the same ros-z directory:
Terminal 2 - Start the Listener:
Terminal 3 - Start the Talker:
Success
You should see the listener receiving messages published by the talker in real-time. Press Ctrl+C to stop any process.
Understanding the Code¶
Here's the complete example you ran:
use std::time::Duration;
use clap::{Parser, ValueEnum};
use ros_z::{
Builder, Result,
context::{ZContext, ZContextBuilder},
};
use ros_z_msgs::std_msgs::String as RosString;
/// Subscriber function that continuously receives messages from a topic
async fn run_subscriber(ctx: ZContext, topic: String) -> Result<()> {
// Create a ROS 2 node - the fundamental unit of computation
let node = ctx.create_node("Sub").build()?;
// Create a subscriber for the specified topic
let zsub = node.create_sub::<RosString>(&topic).build()?;
// Continuously receive messages asynchronously
while let Ok(msg) = zsub.async_recv().await {
println!("Hearing:>> {}", msg.data);
}
Ok(())
}
/// Publisher function that continuously publishes messages to a topic
async fn run_publisher(
ctx: ZContext,
topic: String,
period: Duration,
payload: String,
) -> Result<()> {
let node = ctx.create_node("Pub").build()?;
let zpub = node.create_pub::<RosString>(&topic).build()?;
let mut count = 0;
loop {
let str = RosString {
data: format!("{payload} - #{count}"),
};
println!("Telling:>> {}", str.data);
zpub.async_publish(&str).await?;
let _ = tokio::time::sleep(period).await;
count += 1;
}
}
#[tokio::main]
async fn main() -> Result<()> {
let args = Args::parse();
let format = match args.backend {
Backend::RmwZenoh => ros_z_protocol::KeyExprFormat::RmwZenoh,
#[cfg(feature = "ros2dds")]
Backend::Ros2Dds => ros_z_protocol::KeyExprFormat::Ros2Dds,
};
// Create a ZContext - the entry point for ros-z applications
let ctx = if let Some(e) = args.endpoint {
ZContextBuilder::default()
.with_mode(args.mode)
.with_connect_endpoints([e])
.keyexpr_format(format)
.build()?
} else {
ZContextBuilder::default()
.with_mode(args.mode)
.keyexpr_format(format)
.build()?
};
let period = std::time::Duration::from_secs_f64(args.period);
zenoh::init_log_from_env_or("error");
match args.role.as_str() {
"listener" => run_subscriber(ctx, args.topic).await?,
"talker" => run_publisher(ctx, args.topic, period, args.data).await?,
role => println!(
"Please use \"talker\" or \"listener\" as role, {} is not supported.",
role
),
}
Ok(())
}
#[derive(Debug, Clone, Copy, ValueEnum)]
enum Backend {
/// RmwZenoh backend (default) - compatible with rmw_zenoh nodes
RmwZenoh,
#[cfg(feature = "ros2dds")]
Ros2Dds,
}
#[derive(Debug, Parser)]
struct Args {
#[arg(short, long, default_value = "Hello ros-z")]
data: String,
#[arg(short, long, default_value = "/chatter")]
topic: String,
#[arg(short, long, default_value = "1.0")]
period: f64,
#[arg(short, long, default_value = "listener")]
role: String,
#[arg(short, long, default_value = "peer")]
mode: String,
#[arg(short, long)]
endpoint: Option<String>,
#[arg(short, long, value_enum, default_value = "rmw-zenoh")]
backend: Backend,
}
Option 2: Create Your Own Project¶
Ready to build your own ros-z application? Follow these steps to create a new project from scratch.
1. Install the Zenoh Router¶
Since you won't have access to the zenoh_router example outside the ros-z repository, you'll need to install a Zenoh router. Here are the quickest options:
Option A: Using cargo (if you have Rust):
Option B: Using pre-built binary (no Rust needed):
Download the latest release for your platform from: https://github.com/eclipse-zenoh/zenoh/releases
Then extract and run:
Option C: Using Docker:
Start the router:
Tip
For more installation options (apt, brew, Windows, etc.), see the comprehensive Zenoh Router Installation Guide.
Note
Keep the router running in a separate terminal. All ros-z applications will connect to it.
2. Create a New Rust Project¶
3. Add Dependencies¶
Add ros-z to your Cargo.toml:
[dependencies]
ros-z = { git = "https://github.com/ZettaScaleLabs/ros-z.git" }
ros-z-msgs = { git = "https://github.com/ZettaScaleLabs/ros-z.git" } # Standard ROS 2 message types
tokio = { version = "1", features = ["full"] } # Async runtime
Note
ros-z requires an async runtime. This example uses Tokio, the most popular choice in the Rust ecosystem.
4. Write Your First Application¶
Replace the contents of src/main.rs with this simple publisher example:
Simpler imports with prelude
Instead of importing Builder, Result, and ZContextBuilder separately, use use ros_z::prelude::*; to bring all common ros-z types into scope at once.
use std::time::Duration;
use ros_z::{Builder, Result, context::ZContextBuilder};
use ros_z_msgs::std_msgs::String as RosString;
#[tokio::main]
async fn main() -> Result<()> {
// Initialize ros-z context (connects to router on localhost:7447)
let ctx = ZContextBuilder::default()
.with_connect_endpoints(["tcp/127.0.0.1:7447"])
.build()?;
// Create a ROS 2 node
let node = ctx.create_node("my_talker").build()?;
// Create a publisher for the /chatter topic
let pub_handle = node.create_pub::<RosString>("/chatter").build()?;
// Publish messages every second
let mut count = 0;
loop {
let msg = RosString {
data: format!("Hello from ros-z #{}", count),
};
println!("Publishing: {}", msg.data);
pub_handle.async_publish(&msg).await?;
count += 1;
tokio::time::sleep(Duration::from_secs(1)).await;
}
}
5. Run Your Application¶
Make sure the Zenoh router (zenohd) is running in another terminal, then:
Success
You should see the application publishing messages every second. It will continue until you press Ctrl+C.
6. Test with Multiple Nodes¶
Open another terminal and create a simple listener to verify communication:
Create src/bin/listener.rs:
use ros_z::{Builder, Result, context::ZContextBuilder};
use ros_z_msgs::std_msgs::String as RosString;
#[tokio::main]
async fn main() -> Result<()> {
let ctx = ZContextBuilder::default()
.with_connect_endpoints(["tcp/127.0.0.1:7447"])
.build()?;
let node = ctx.create_node("my_listener").build()?;
let sub = node.create_sub::<RosString>("/chatter").build()?;
println!("Listening on /chatter...");
while let Ok(msg) = sub.async_recv().await {
println!("Received: {}", msg.data);
}
Ok(())
}
Run both:
# Terminal 1: Router
zenohd
# Terminal 2: Publisher
cargo run
# Terminal 3: Listener
cargo run --bin listener
Key Components¶
| Component | Purpose | Usage |
|---|---|---|
| ZContextBuilder | Initialize ros-z environment | Entry point, configure settings |
| ZContext | Manages ROS 2 connections | Create nodes from this |
| Node | Logical unit of computation | Publishers/subscribers attach here |
| Publisher | Sends messages to topics | node.create_pub::<Type>("topic") |
| Subscriber | Receives messages from topics | node.create_sub::<Type>("topic") |
Why a Zenoh router?
ros-z uses router-based discovery by default, aligning with ROS 2's official Zenoh middleware (rmw_zenoh_cpp). This provides:
- Better scalability for large deployments with many nodes
- Lower network overhead compared to multicast discovery
- Production-ready architecture used in real ROS 2 systems
See the Networking chapter for customization options.
Key Terms
key expression — Zenoh's topic addressing scheme. A string like 0/chatter/std_msgs::msg::dds_::String_/RIHS01_<hash> that identifies where messages flow. ros-z maps ROS 2 topic names to key expressions automatically.
CDR — Common Data Representation, the binary serialization format used by all ROS 2 middleware. ros-z serializes message structs to CDR bytes before publishing.
RIHS01 — ROS Interface Hash Scheme 01, a hash of the message definition that ensures publisher and subscriber agree on the exact message fields. If the hash differs, messages are silently dropped.
RMW — ROS MiddleWare interface, the plugin layer that connects ROS 2 nodes to an underlying transport (DDS, Zenoh, etc.). rmw_zenoh_cpp is the RMW that lets standard ROS 2 C++/Python nodes speak Zenoh.
What's Happening?¶
sequenceDiagram
participant T as Talker
participant Z as Zenoh Network
participant L as Listener
T->>Z: Publish "Hello 0"
Z->>L: Deliver message
L->>L: Print to console
Note over T: Wait 1 second
T->>Z: Publish "Hello 1"
Z->>L: Deliver message
L->>L: Print to console
The talker publishes messages every second to the /chatter topic. The listener subscribes to the same topic and prints each received message. Zenoh handles the network transport transparently.
Info
Both nodes run independently. You can start/stop them in any order, and multiple listeners can receive from one talker simultaneously.
Next Steps¶
Now that you understand the basics:
Core Concepts:
- Pub/Sub - Deep dive into pub-sub patterns and QoS
- Services - Request-response communication
- Actions - Long-running tasks with feedback
- Message Generation - How message types work
- Custom Messages - Define your own message types
Development:
- Building - Build configurations and dependencies
- Networking - Zenoh router setup and options