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.
This guide assumes basic Rust knowledge. If you're new to Rust, complete the Rust Book first for the best experience.
Setup
Add ros-z dependencies to your Cargo.toml:
[dependencies]
ros-z = "*"
ros-z-msgs = "*" # Standard ROS 2 message types
tokio = { version = "1", features = ["full"] } # Async runtime
An async runtime is required for ros-z. This example uses Tokio, the most popular choice in the Rust ecosystem.
Your 1st Example
Here's a complete publisher and subscriber in one application:
use std::time::Duration;
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
// Nodes are logical groupings of publishers, subscribers, services, etc.
let node = ctx.create_node("Sub").build()?;
// Create a subscriber for the specified topic
// The type parameter RosString determines what message type we'll receive
let zsub = node.create_sub::<RosString>(&topic).build()?;
// Continuously receive messages asynchronously
// This loop will block waiting for messages on the topic
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<()> {
// Create a ROS 2 node for publishing
let node = ctx.create_node("Pub").build()?;
// Create a publisher for the specified topic
// The type parameter RosString determines what message type we'll send
let zpub = node.create_pub::<RosString>(&topic).build()?;
let mut count = 0;
loop {
// Create a new message with incrementing counter
let str = RosString {
data: format!("{payload} - #{count}"),
};
println!("Telling:>> {}", str.data);
// Publish the message asynchronously to all subscribers on this topic
zpub.async_publish(&str).await?;
// Wait for the specified period before publishing again
let _ = tokio::time::sleep(period).await;
count += 1;
}
}
// The #[tokio::main] attribute sets up the async runtime
// ros-z requires an async runtime (Tokio is the most common choice)
#[tokio::main]
async fn main() -> Result<()> {
let args = Args::parse();
// Create a ZContext - the entry point for ros-z applications
// ZContext manages the connection to the Zenoh network and coordinates
// communication between nodes. It can be configured with different modes:
// - "peer" mode: nodes discover each other via multicast scouting
// - "client" mode: nodes connect to a Zenoh router
let ctx = if let Some(e) = args.endpoint {
ZContextBuilder::default()
.with_mode(args.mode)
.with_connect_endpoints([e])
.build()?
} else {
ZContextBuilder::default().with_mode(args.mode).build()?
};
let period = std::time::Duration::from_secs_f64(args.period);
zenoh::init_log_from_env_or("error");
// Run as either a publisher (talker) or subscriber (listener)
// Both share the same ZContext but perform different roles
if args.role == "listener" {
run_subscriber(ctx, args.topic).await?;
} else if args.role == "talker" {
run_publisher(ctx, args.topic, period, args.data).await?;
} else {
println!(
"Please use \"talker\" or \"listener\" as role, {} is not supported.",
args.role
);
}
Ok(())
}
use clap::Parser;
#[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>,
}
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") |
Running the Application
ros-z uses a router-based architecture (matching ROS 2's rmw_zenoh), so you'll need to start a Zenoh router first.
Open three terminal windows and run:
Terminal 1 - Start the Zenoh Router:
cargo run --example zenoh_router
Terminal 2 - Start the Listener:
cargo run --example z_pubsub -- -r listener
Terminal 3 - Start the Talker:
cargo run --example z_pubsub -- -r talker
You should see the listener receiving messages published by the talker in real-time. Press Ctrl+C to stop any process.
ros-z now 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 Zenoh Configuration chapter for customization options, including how to revert to multicast scouting mode if needed.
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.
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