Keyboard shortcuts

Press or to navigate between chapters

Press S or / to search in the book

Press ? to show this help

Press Esc to hide this help

Introduction

ros-z is a native Rust ROS 2 implementation powered by Zenoh, delivering high-performance robotics communication with type safety and zero-cost abstractions. Build reliable robot applications using modern Rust idioms while maintaining full ROS 2 compatibility.

Architecture

ros-z provides three integration paths to suit different use cases:

Why Choose ros-z?

FeatureDescriptionBenefit
Native RustPure Rust implementation with no C/C++ dependenciesMemory safety, concurrency without data races
Zenoh TransportHigh-performance pub-sub engineLow latency, efficient bandwidth usage
ROS 2 CompatibleWorks seamlessly with standard ROS 2 toolsIntegrate with existing robotics ecosystems
Flexible Key Expression FormatsCompatible with rmw_zenoh_cpp and zenoh-bridge-ros2ddsInteroperate with different Zenoh-ROS bridges
Multiple SerializationsSupport for various data representations: CDR (ROS default), ProtobufFlexible message encoding for different performance and interoperability needs
Type SafetyCompile-time message validationCatch errors before deployment
Modern APIIdiomatic Rust patternsErgonomic developer experience
Safety FirstOwnership model prevents common bugsNo data races, null pointers, or buffer overflows at compile time
High ProductivityCargo ecosystem with excellent toolingFast development without sacrificing reliability

Note

ros-z is designed for both new projects and gradual migration. Deploy ros-z nodes alongside existing ROS 2 C++/Python nodes with full interoperability.

Communication Patterns

ros-z supports all essential ROS 2 communication patterns:

PatternUse CaseLearn More
Pub/SubContinuous data streaming, sensor data, status updatesPub/Sub
ServicesRequest-response operations, remote procedure callsServices
ActionsLong-running tasks with feedback and cancellation supportActions

Tip

Start with pub/sub for data streaming, use services for request-response operations, and leverage actions for long-running tasks that need progress feedback.

Ergonomic API Design

ros-z provides flexible, idiomatic Rust APIs that adapt to your preferred programming style:

Flexible Builder Pattern:

let pub = node.create_pub::<Vector3>("vector")
    // Quality of Service settings
    .with_qos(QosProfile {
        reliability: QosReliability::Reliable,
        ..Default::default()
    })
    // custom serialization
    .with_serdes::<ProtobufSerdes<Vector3>>()
    .build()?;

Async & Sync Patterns:

// Publishers: sync and async variants
zpub.publish(&msg)?;
zpub.async_publish(&msg).await?;

// Subscribers: sync and async receiving
let msg = zsub.recv()?;
let msg = zsub.async_recv().await?;

Callback or Polling Style for Subscribers:

// Callback style - process messages with a closure
let sub = node.create_sub::<RosString>("topic")
    .build_with_callback(|msg| {
        println!("Received: {}", msg);
    })?;

// Polling style - receive messages on demand
let sub = node.create_sub::<RosString>("topic").build()?;
while let Ok(msg) = sub.recv() {
    println!("Received: {}", msg);
}

Next Step

Ready to build safer, faster robotics applications? Start with the Quick Start Guide.

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.

Choose Your Path

There are two ways to get started with ros-z:

  1. Try the Examples - Clone the ros-z repository and run pre-built examples (fastest way to see it in action)
  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

git clone https://github.com/ZettaScaleLabs/ros-z.git
cd ros-z

Start the Zenoh Router

ros-z uses a router-based architecture (matching ROS 2's rmw_zenoh), so you'll need to start a Zenoh router first.

Terminal 1 - Start the Router:

cargo run --example zenoh_router

Run the Pub/Sub Example

Open two more terminals in the same ros-z directory:

Terminal 2 - Start the Listener:

cargo run --example z_pubsub -- -r listener

Terminal 3 - Start the Talker:

cargo run --example z_pubsub -- -r 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 just 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
    // 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();

    // Convert backend enum to KeyExprFormat
    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
    // 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])
            .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");

    // Run as either a publisher (talker) or subscriber (listener)
    // Both share the same ZContext but perform different roles
    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
    /// Uses key expressions with domain prefix: <domain_id>/<topic>/**
    RmwZenoh,
    /// Ros2Dds backend - compatible with zenoh-bridge-ros2dds
    /// Uses key expressions without domain prefix: <topic>/**
    #[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>,
    /// Backend selection: rmw-zenoh (default) or ros2-dds
    #[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):

cargo install zenohd

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:

unzip zenoh-*.zip
chmod +x zenohd
./zenohd

Option C: Using Docker:

docker run --init --net host eclipse/zenoh:latest

Start the router:

zenohd

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

cargo new my_ros_z_project
cd my_ros_z_project

3. Add Dependencies

Add ros-z to your Cargo.toml:

[dependencies]
ros-z = "*"
ros-z-msgs = "*"  # Standard ROS 2 message types
tokio = { version = "1", features = ["full"] }  # Async runtime

Note

An async runtime is required for ros-z. 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:

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().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:

cargo run

Success

You should see messages being published every second. The application 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().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

ComponentPurposeUsage
ZContextBuilderInitialize ros-z environmentEntry point, configure settings
ZContextManages ROS 2 connectionsCreate nodes from this
NodeLogical unit of computationPublishers/subscribers attach here
PublisherSends messages to topicsnode.create_pub::<Type>("topic")
SubscriberReceives messages from topicsnode.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, 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.

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:

Development:

  • Building - Build configurations and dependencies
  • Networking - Zenoh router setup and options

Publishers and Subscribers

ros-z implements ROS 2's publish-subscribe pattern with type-safe, zero-copy messaging over Zenoh. This enables efficient, decoupled communication between nodes with minimal overhead.

Note

The pub-sub pattern forms the foundation of ROS 2 communication, allowing nodes to exchange data without direct coupling. ros-z leverages Zenoh's efficient transport layer for optimal performance.

Visual Flow

graph TD
    A[ZContextBuilder] -->|configure| B[ZContext]
    B -->|create| C[Node]
    C -->|publisher| D[Publisher]
    C -->|subscriber| E[Subscriber]
    D -->|publish| F[Topic]
    F -->|deliver| E
    E -->|callback| G[Message Handler]

Key Features

FeatureDescriptionBenefit
Type SafetyStrongly-typed messages using Rust structsCompile-time error detection
Zero-CopyEfficient message passing via ZenohReduced latency and CPU usage
QoS ProfilesConfigurable reliability, durability, historyFine-grained delivery control
Async/BlockingDual API for both paradigmsFlexible integration patterns

Publisher Example

This example demonstrates publishing "Hello World" messages to a topic. The publisher sends messages periodically, showcasing the fundamental publishing pattern.

/// Talker node that publishes "Hello World" messages to a topic
///
/// # Arguments
/// * `ctx` - The ROS-Z context
/// * `topic` - The topic name to publish to
/// * `period` - Duration between messages
/// * `max_count` - Optional maximum number of messages to publish. If None, publishes indefinitely.
pub async fn run_talker(
    ctx: ZContext,
    topic: &str,
    period: Duration,
    max_count: Option<usize>,
) -> Result<()> {
    // Create a node named "talker"
    let node = ctx.create_node("talker").build()?;

    // Create a publisher with a custom Quality of Service profile
    let qos = QosProfile {
        history: QosHistory::KeepLast(NonZeroUsize::new(7).unwrap()),
        ..Default::default()
    };
    let publisher = node.create_pub::<RosString>(topic).with_qos(qos).build()?;

    let mut count = 1;

    loop {
        // Create the message
        let msg = RosString {
            data: format!("Hello World: {}", count),
        };

        // Log the message being published
        println!("Publishing: '{}'", msg.data);

        // Publish the message (non-blocking)
        publisher.async_publish(&msg).await?;

        // Check if we've reached the max count
        if let Some(max) = max_count
            && count >= max
        {
            break;
        }

        // Wait for the next publish cycle
        tokio::time::sleep(period).await;

        count += 1;
    }

    Ok(())
}

Key points:

  • QoS Configuration: Uses KeepLast(7) to buffer the last 7 messages
  • Async Publishing: Non-blocking async_publish() for efficient I/O
  • Rate Control: Uses tokio::time::sleep() to control publishing frequency
  • Bounded Operation: Optional max_count for testing scenarios

Running the publisher:

# Basic usage
cargo run --example demo_nodes_talker

# Custom topic and rate
cargo run --example demo_nodes_talker -- --topic /my_topic --period 0.5

# Publish 10 messages then exit
cargo run --example demo_nodes_talker -- --max-count 10

Subscriber Example

This example demonstrates subscribing to messages from a topic. The subscriber receives and displays messages, showing both timeout-based and async reception patterns.

/// Listener node that subscribes to a topic
///
/// # Arguments
/// * `ctx` - The ROS-Z context
/// * `topic` - The topic name to subscribe to
/// * `max_count` - Optional maximum number of messages to receive. If None, listens indefinitely.
/// * `timeout` - Optional timeout duration. If None, waits indefinitely.
///
/// # Returns
/// A vector of received messages
pub async fn run_listener(
    ctx: ZContext,
    topic: &str,
    max_count: Option<usize>,
    timeout: Option<Duration>,
) -> Result<Vec<String>> {
    // Create a node named "listener"
    let node = ctx.create_node("listener").build()?;

    // Create a subscription to the "chatter" topic
    let qos = QosProfile {
        history: QosHistory::KeepLast(NonZeroUsize::new(10).unwrap()),
        ..Default::default()
    };
    let subscriber = node.create_sub::<RosString>(topic).with_qos(qos).build()?;

    let mut received_messages = Vec::new();
    let start = std::time::Instant::now();

    // Receive messages in a loop
    loop {
        // Check timeout
        if let Some(t) = timeout
            && start.elapsed() > t
        {
            break;
        }

        // Try to receive with a small timeout to allow checking other conditions
        let recv_result = if timeout.is_some() || max_count.is_some() {
            subscriber.recv_timeout(Duration::from_millis(100))
        } else {
            // If no limits, use async_recv
            subscriber.async_recv().await
        };

        match recv_result {
            Ok(msg) => {
                // Log the received message
                println!("I heard: [{}]", msg.data);
                received_messages.push(msg.data.clone());

                // Check if we've received enough messages
                if let Some(max) = max_count
                    && received_messages.len() >= max
                {
                    break;
                }
            }
            Err(_) => {
                // Continue if timeout on recv_timeout
                if timeout.is_some() || max_count.is_some() {
                    continue;
                } else {
                    break;
                }
            }
        }
    }

    Ok(received_messages)
}

Key points:

  • Flexible Reception: Supports timeout-based and indefinite blocking
  • Testable Design: Returns received messages for verification
  • Bounded Operation: Optional max_count and timeout parameters
  • QoS Configuration: Uses KeepLast(10) for message buffering

Running the subscriber:

# Basic usage
cargo run --example demo_nodes_listener

# Custom topic
cargo run --example demo_nodes_listener -- --topic /my_topic

# Receive 5 messages then exit
cargo run --example demo_nodes_listener -- --max-count 5

Complete Pub-Sub Workflow

To see publishers and subscribers in action together, you'll need to start a Zenoh router first:

Terminal 1 - Start Zenoh Router:

cargo run --example zenoh_router

Terminal 2 - Start Subscriber:

cargo run --example demo_nodes_listener

Terminal 3 - Start Publisher:

cargo run --example demo_nodes_talker

Subscriber Patterns

ros-z provides three patterns for receiving messages, each suited for different use cases:

Pattern 1: Blocking Receive (Pull Model)

Best for: Simple sequential processing, scripting

let subscriber = node
    .create_sub::<RosString>("topic_name")
    .build()?;

while let Ok(msg) = subscriber.recv() {
    println!("Received: {}", msg.data);
}

Pattern 2: Async Receive (Pull Model)

Best for: Integration with async codebases, handling multiple streams

let subscriber = node
    .create_sub::<RosString>("topic_name")
    .build()?;

while let Ok(msg) = subscriber.async_recv().await {
    println!("Received: {}", msg.data);
}

Pattern 3: Callback (Push Model)

Best for: Event-driven architectures, low-latency response

let subscriber = node
    .create_sub::<RosString>("topic_name")
    .build_with_callback(|msg| {
        println!("Received: {}", msg.data);
    })?;

// No need to call recv() - callback handles messages automatically
// Your code continues while messages are processed in the background

Tip

Use callbacks for low-latency event-driven processing. Use blocking/async receive when you need explicit control over when messages are processed.

Pattern Comparison

AspectBlocking ReceiveAsync ReceiveCallback
Control FlowSequentialSequentialEvent-driven
LatencyMedium (poll-based)Medium (poll-based)Low (immediate)
MemoryQueue size × messageQueue size × messageNo queue
BackpressureBuilt-in (queue full)Built-in (queue full)None (drops if slow)
Use CaseSimple scriptsAsync applicationsReal-time response

Quality of Service (QoS)

QoS profiles control message delivery behavior:

use ros_z::qos::{QosProfile, QosHistory, Reliability};

let qos = QosProfile {
    history: QosHistory::KeepLast(10),
    reliability: Reliability::Reliable,
    ..Default::default()
};

let publisher = node
    .create_pub::<RosString>("topic")
    .with_qos(qos)
    .build()?;

Tip

Use QosHistory::KeepLast(1) for sensor data and Reliability::Reliable for critical commands. Match QoS profiles between publishers and subscribers for optimal message delivery.

ROS 2 Interoperability

ros-z publishers and subscribers work seamlessly with ROS 2 C++ and Python nodes:

# List active topics
ros2 topic list

# Echo messages from ros-z publisher
ros2 topic echo /chatter

# Publish to ros-z subscriber from ROS 2
ros2 topic pub /chatter std_msgs/msg/String "data: 'Hello from ROS 2'"

# Check topic info
ros2 topic info /chatter

Success

ros-z provides full ROS 2 compatibility via Zenoh bridge or rmw_zenoh, enabling cross-language communication.

Resources

Start with the examples above to understand the basic pub-sub workflow, then explore custom messages for domain-specific communication.

Services

ros-z implements ROS 2's service pattern with type-safe request-response communication over Zenoh. This enables synchronous, point-to-point interactions between nodes using a pull-based model for full control over request processing.

Note

Services provide request-response communication for operations that need immediate feedback. Unlike topics, services are bidirectional and ensure a response for each request. ros-z uses a pull model that gives you explicit control over when to process requests.

Visual Flow

graph TD
    A[ZContextBuilder] -->|configure| B[ZContext]
    B -->|create| C[Client Node]
    B -->|create| D[Server Node]
    C -->|create_client| E[Service Client]
    D -->|create_service| F[Service Server]
    E -->|send_request| G[Service Call]
    G -->|route| F
    F -->|take_request| H[Request Handler]
    H -->|send_response| G
    G -->|deliver| E
    E -->|take_response| I[Response Handler]

Key Features

FeatureDescriptionBenefit
Type SafetyStrongly-typed service definitions with Rust structsCompile-time error detection
Pull ModelExplicit control over request processing timingPredictable concurrency and backpressure
Async/BlockingDual API for both paradigmsFlexible integration patterns
Request TrackingKey-based request/response matchingReliable message correlation

Service Server Example

This example demonstrates a service server that adds two integers. The server waits for requests, processes them, and sends responses back to clients.

/// AddTwoInts server node that provides a service to add two integers
///
/// # Arguments
/// * `ctx` - The ROS-Z context
/// * `max_requests` - Optional maximum number of requests to handle. If None, handles requests indefinitely.
pub fn run_add_two_ints_server(ctx: ZContext, max_requests: Option<usize>) -> Result<()> {
    // Create a node named "add_two_ints_server"
    let node = ctx.create_node("add_two_ints_server").build()?;

    // Create a service that will handle requests
    let mut service = node.create_service::<AddTwoInts>("add_two_ints").build()?;

    println!("AddTwoInts service server started, waiting for requests...");

    let mut request_count = 0;

    loop {
        // Wait for a request
        let (key, req) = service.take_request()?;
        println!("Incoming request\na: {} b: {}", req.a, req.b);

        // Compute the sum
        let sum = req.a + req.b;

        // Create the response
        let resp = AddTwoIntsResponse { sum };

        println!("Sending response: {}", resp.sum);

        // Send the response
        service.send_response(&resp, &key)?;

        request_count += 1;

        // Check if we've reached the max requests
        if let Some(max) = max_requests
            && request_count >= max
        {
            break;
        }
    }

    Ok(())
}

Key points:

  • Pull Model: Uses take_request() for explicit control over when to accept requests
  • Request Key: Each request has a unique key for matching responses
  • Bounded Operation: Optional max_requests parameter for testing
  • Simple Processing: Demonstrates synchronous request handling

Running the server:

# Basic usage - runs indefinitely
cargo run --example demo_nodes_add_two_ints_server

# Handle 5 requests then exit
cargo run --example demo_nodes_add_two_ints_server -- --count 5

# Connect to specific Zenoh router
cargo run --example demo_nodes_add_two_ints_server -- --endpoint tcp/localhost:7447

Service Client Example

This example demonstrates a service client that sends addition requests to the server and displays the results.

/// AddTwoInts client node that calls the service to add two integers
///
/// # Arguments
/// * `ctx` - The ROS-Z context
/// * `a` - First number to add
/// * `b` - Second number to add
/// * `async_mode` - Whether to use async response waiting
pub fn run_add_two_ints_client(ctx: ZContext, a: i64, b: i64, async_mode: bool) -> Result<i64> {
    // Create a node named "add_two_ints_client"
    let node = ctx.create_node("add_two_ints_client").build()?;

    // Create a client for the service
    let client = node.create_client::<AddTwoInts>("add_two_ints").build()?;

    println!(
        "AddTwoInts service client started (mode: {})",
        if async_mode { "async" } else { "sync" }
    );

    // Create the request
    let req = AddTwoIntsRequest { a, b };
    println!("Sending request: {} + {}", req.a, req.b);

    // Wait for the response
    let resp = if async_mode {
        tokio::runtime::Runtime::new().unwrap().block_on(async {
            client.send_request(&req).await?;
            client.take_response_async().await
        })?
    } else {
        tokio::runtime::Runtime::new()
            .unwrap()
            .block_on(async { client.send_request(&req).await })?;
        client.take_response_timeout(Duration::from_secs(5))?
    };

    println!("Received response: {}", resp.sum);

    Ok(resp.sum)
}

Key points:

  • Async Support: Supports both blocking and async response patterns
  • Timeout Handling: Uses take_response_timeout() for reliable operation
  • Simple API: Send request, receive response, process result
  • Type Safety: Request and response types are enforced at compile time

Running the client:

# Basic usage
cargo run --example demo_nodes_add_two_ints_client -- --a 10 --b 20

# Using async mode
cargo run --example demo_nodes_add_two_ints_client -- --a 5 --b 3 --async-mode

# Connect to specific Zenoh router
cargo run --example demo_nodes_add_two_ints_client -- --a 100 --b 200 --endpoint tcp/localhost:7447

Complete Service Workflow

To see services in action, you'll need to start a Zenoh router first:

Terminal 1 - Start Zenoh Router:

cargo run --example zenoh_router

Terminal 2 - Start Server:

cargo run --example demo_nodes_add_two_ints_server

Terminal 3 - Send Client Requests:

# Request 1
cargo run --example demo_nodes_add_two_ints_client -- --a 10 --b 20

# Request 2
cargo run --example demo_nodes_add_two_ints_client -- --a 100 --b 200

Success

Each client request is processed immediately by the server, demonstrating synchronous request-response communication over Zenoh.

Service Server Patterns

Service servers in ros-z follow a pull model pattern, similar to subscribers. You explicitly receive requests when ready to process them, giving you full control over request handling timing and concurrency.

Info

This pull-based approach is consistent with subscriber's recv() pattern, allowing you to control when work happens rather than having callbacks interrupt your flow.

Pattern 1: Blocking Request Handling

Best for: Simple synchronous service implementations

let mut service = node
    .create_service::<ServiceType>("service_name")
    .build()?;

loop {
    let (key, request) = service.take_request()?;
    let response = process_request(&request);
    service.send_response(&response, &key)?;
}

Pattern 2: Async Request Handling

Best for: Services that need to await other operations

let mut service = node
    .create_service::<ServiceType>("service_name")
    .build()?;

loop {
    let (key, request) = service.take_request_async().await?;
    let response = async_process_request(&request).await;
    service.send_response(&response, &key)?;
}

Why Pull Model?

AspectPull Model (take_request)Push Model (callback)
ControlExplicit control over when to accept requestsInterrupts current work
ConcurrencyEasy to reason aboutRequires careful synchronization
BackpressureNatural - slow processing slows acceptanceCan overwhelm if processing is slow
ConsistencySame pattern as subscriber recv()Different pattern

Service Client Patterns

Service clients send requests to servers and receive responses. Both blocking and async patterns are supported.

Pattern 1: Blocking Client

Best for: Simple synchronous request-response operations

let client = node
    .create_client::<ServiceType>("service_name")
    .build()?;

let request = create_request();
client.send_request(&request)?;
let response = client.take_response()?;

Pattern 2: Async Client

Best for: Integration with async codebases

let client = node
    .create_client::<ServiceType>("service_name")
    .build()?;

let request = create_request();
client.send_request(&request).await?;
let response = client.take_response_async().await?;

Tip

Match your client and server patterns for consistency. Use blocking patterns for simple scripts and async patterns when integrating with async runtimes like tokio.

ROS 2 Interoperability

ros-z services work seamlessly with ROS 2 C++ and Python nodes:

# List available services
ros2 service list

# Call ros-z service from ROS 2 CLI
ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 42, b: 58}"

# Show service type
ros2 service type /add_two_ints

# Get service info
ros2 service info /add_two_ints

Success

ros-z service servers and clients are fully compatible with ROS 2 via Zenoh bridge or rmw_zenoh, enabling cross-language service calls.

Resources

Start with the examples above to understand the basic service workflow, then explore custom service types for domain-specific operations.

Actions

Actions enable long-running tasks with progress feedback and cancellation support, perfect for operations that take seconds or minutes to complete. Unlike services that return immediately, actions provide streaming feedback while executing complex workflows.

Tip

Use actions for robot navigation, trajectory execution, or any operation where you need progress updates and the ability to cancel mid-execution. Use services for quick request-response operations.

Action Lifecycle

stateDiagram-v2
    [*] --> Idle
    Idle --> Accepted: Send Goal
    Accepted --> Executing: Start Processing
    Executing --> Executing: Send Feedback
    Executing --> Succeeded: Complete
    Executing --> Canceled: Cancel Request
    Executing --> Aborted: Error Occurs
    Succeeded --> [*]
    Canceled --> [*]
    Aborted --> [*]

Components

ComponentTypePurpose
GoalInputDefines the desired outcome
FeedbackStreamProgress updates during execution
ResultOutputFinal outcome when complete
StatusStateCurrent execution state

Communication Pattern

sequenceDiagram
    participant C as Client
    participant S as Server

    C->>S: Send Goal
    S->>C: Goal Accepted
    loop During Execution
        S->>C: Feedback Update
    end
    alt Success
        S->>C: Result (Success)
    else Canceled
        C->>S: Cancel Request
        S->>C: Result (Canceled)
    else Error
        S->>C: Result (Aborted)
    end

Use Cases

Robot Navigation:

  • Goal: Target position and orientation
  • Feedback: Current position, distance remaining, obstacles detected
  • Result: Final position, success/failure reason

Gripper Control:

  • Goal: Desired grip force and position
  • Feedback: Current force, contact detection
  • Result: Grip achieved, object secured

Long Computations:

  • Goal: Computation parameters
  • Feedback: Progress percentage, intermediate results
  • Result: Final computed value, execution time

Info

Actions excel when operations take more than a few seconds and users need visibility into progress. For sub-second operations, prefer services for simplicity.

Action Server Example

This example demonstrates an action server that computes Fibonacci sequences. The server accepts goals, publishes periodic feedback with partial results, and supports cancellation.

/// Fibonacci action server node that computes Fibonacci sequences
///
/// # Arguments
/// * `ctx` - The ROS-Z context
/// * `timeout` - Optional timeout duration. If None, runs until ctrl+c.
pub async fn run_fibonacci_action_server(ctx: ZContext, timeout: Option<Duration>) -> Result<()> {
    // Create a node named "fibonacci_action_server"
    let node = ctx.create_node("fibonacci_action_server").build()?;

    // Create an action server
    // Note: The server variable must be kept alive for the duration of the function
    // to ensure the action server and its background tasks remain active
    let _server = node
        .create_action_server::<Fibonacci>("fibonacci")
        .build()?
        .with_handler(|executing: ExecutingGoal<Fibonacci>| async move {
            let order = executing.goal.order;
            let mut sequence = vec![0, 1];

            println!("Executing Fibonacci goal with order {}", order);

            let mut canceled = false;
            let mut cancel_sequence = None;

            for i in 2..=order {
                // Check for cancellation
                if executing.is_cancel_requested() {
                    println!("Goal canceled!");
                    canceled = true;
                    cancel_sequence = Some(sequence.clone());
                    break;
                }

                let next = sequence[i as usize - 1] + sequence[i as usize - 2];
                sequence.push(next);

                // Publish feedback
                executing
                    .publish_feedback(FibonacciFeedback {
                        partial_sequence: sequence.clone(),
                    })
                    .expect("Failed to publish feedback");

                tokio::time::sleep(Duration::from_millis(500)).await;
            }

            if canceled {
                executing
                    .canceled(FibonacciResult {
                        sequence: cancel_sequence.unwrap(),
                    })
                    .unwrap();
            } else {
                println!("Goal succeeded!");
                executing.succeed(FibonacciResult { sequence }).unwrap();
            }
        });

    println!("Fibonacci action server started");

    if let Some(timeout) = timeout {
        // For testing: run for the specified timeout
        tokio::time::sleep(timeout).await;
    } else {
        tokio::signal::ctrl_c().await?;
    }

    Ok(())
}

Key points:

  • Handler Pattern: Uses .with_handler() to define asynchronous goal execution
  • Feedback Publishing: Sends partial results periodically via publish_feedback()
  • Cancellation Support: Checks is_cancel_requested() and handles graceful cancellation
  • Completion: Uses .succeed() or .canceled() to send final result

Running the server:

# Start Zenoh router first
cargo run --example zenoh_router

# Run the server (runs until Ctrl+C)
cargo run --example demo_nodes_fibonacci_action_server

Action Client Example

This example demonstrates an action client that sends goals and monitors execution progress with feedback updates.

/// Fibonacci action client node that sends goals to compute Fibonacci sequences
///
/// # Arguments
/// * `ctx` - The ROS-Z context
/// * `order` - The order of the Fibonacci sequence to compute
pub async fn run_fibonacci_action_client(ctx: ZContext, order: i32) -> Result<Vec<i32>> {
    // Create a node named "fibonacci_action_client"
    let node = ctx.create_node("fibonacci_action_client").build()?;

    // Create an action client
    let client = node
        .create_action_client::<Fibonacci>("fibonacci")
        .build()?;

    // Wait a bit for the server to be discovered
    tokio::time::sleep(tokio::time::Duration::from_secs(1)).await;

    println!(
        "Fibonacci action client started, sending goal with order {}",
        order
    );

    // Send the goal
    let mut goal_handle = client.send_goal(FibonacciGoal { order }).await?;
    println!("Goal sent and accepted!");

    // Set up feedback monitoring
    if let Some(mut feedback_stream) = goal_handle.feedback() {
        tokio::spawn(async move {
            while let Some(fb) = feedback_stream.recv().await {
                println!("Feedback: {:?}", fb.partial_sequence);
            }
        });
    }

    // Wait for the result with timeout
    println!("Waiting for result (timeout: 10s)...");
    let result = match tokio::time::timeout(
        tokio::time::Duration::from_secs(10),
        goal_handle.result(),
    )
    .await
    {
        Ok(Ok(result)) => {
            println!("Final result: {:?}", result.sequence);
            result
        }
        Ok(Err(e)) => {
            eprintln!("Action failed: {}", e);
            return Err(e);
        }
        Err(_) => {
            eprintln!("Timeout waiting for action result");
            return Err(zenoh::Error::from("Timeout waiting for action result"));
        }
    };

    Ok(result.sequence)
}

Key points:

  • Goal Sending: Uses send_goal() to submit goals and get a handle
  • Feedback Monitoring: Spawns async task to receive and display feedback
  • Result Handling: Waits for completion with timeout and error handling
  • Type Safety: Strongly-typed goal, feedback, and result messages

Running the client:

# Basic usage - compute Fibonacci(10)
cargo run --example demo_nodes_fibonacci_action_client

# Compute Fibonacci(15)
cargo run --example demo_nodes_fibonacci_action_client -- --order 15

# Connect to specific router
cargo run --example demo_nodes_fibonacci_action_client -- --endpoint tcp/localhost:7447

Complete Action Workflow

Terminal 1 - Start Zenoh Router:

cargo run --example zenoh_router

Terminal 2 - Start Action Server:

cargo run --example demo_nodes_fibonacci_action_server

Terminal 3 - Send Goals from Client:

cargo run --example demo_nodes_fibonacci_action_client -- --order 10

You'll see:

  • Client: Goal sent, feedback updates with partial sequences, final result
  • Server: Goal received, executing with feedback, completion status

Warning

Always implement timeout mechanisms for action clients. Long-running actions can fail or hang, and clients need graceful degradation strategies.

Comparison with Other Patterns

PatternDurationFeedbackCancellationUse Case
Pub-SubContinuousNoN/ASensor data streaming
Service< 1 secondNoNoQuick queries
ActionSeconds to minutesYesYesLong-running tasks

Resources

Action implementation is evolving. Check the ros-z repository for the latest examples and API updates.

Building ros-z

ros-z is designed to work without ROS 2 dependencies by default, enabling pure Rust development while optionally integrating with existing ROS 2 installations. This flexible approach lets you choose your dependency level based on project requirements.

Philosophy

ros-z follows a dependency-optional design:

  • Build pure Rust applications without ROS 2 installed
  • Use bundled message definitions for common types
  • Opt-in to ROS 2 integration when needed
  • Pay only for what you use

Adding ros-z to Your Project

Get started by adding ros-z to your Cargo.toml. Choose the dependency setup that matches your needs:

Scenario 1: Pure Rust with Custom Messages

Use when: You want to define your own message types without ROS 2 dependencies

Add to your Cargo.toml:

[dependencies]
ros-z = "0.x"
tokio = { version = "1", features = ["full"] }  # Async runtime required

What you get:

  • Full ros-z functionality
  • Custom message support via derive macros
  • Zero external dependencies
  • Fast build times

Scenario 2: Using Bundled ROS Messages

Use when: You need standard ROS 2 message types (no ROS 2 installation required)

Add to your Cargo.toml:

[dependencies]
ros-z = "0.x"
ros-z-msgs = "0.x"  # Includes core_msgs by default
tokio = { version = "1", features = ["full"] }

Default message packages (core_msgs):

  • std_msgs - Primitive types (String, Int32, Float64, etc.)
  • geometry_msgs - Spatial data (Point, Pose, Transform, Twist)
  • sensor_msgs - Sensor data (LaserScan, Image, Imu, PointCloud2)
  • nav_msgs - Navigation (Path, OccupancyGrid, Odometry)
  • example_interfaces - Tutorial services (AddTwoInts)
  • action_tutorials_interfaces - Tutorial actions (Fibonacci)

Scenario 3: All Message Packages

Use when: You need all available message types including test messages

Requirements: None (all messages are vendored)

Add to your Cargo.toml:

[dependencies]
ros-z = "0.x"
ros-z-msgs = { version = "0.x", features = ["all_msgs"] }
tokio = { version = "1", features = ["full"] }

Build your project:

cargo build

All available packages:

  • std_msgs - Basic types
  • geometry_msgs - Spatial data
  • sensor_msgs - Sensor data
  • nav_msgs - Navigation
  • example_interfaces - Tutorial services (AddTwoInts)
  • action_tutorials_interfaces - Tutorial actions (Fibonacci)
  • test_msgs - Test types

Tip

The default core_msgs feature includes everything except test_msgs. Use all_msgs only if you need test message types.

ROS 2 Distribution Compatibility

ros-z defaults to ROS 2 Jazzy compatibility, which is the recommended distribution for new projects. If you need to target a different distribution like Humble, see the ROS 2 Distribution Compatibility chapter for detailed instructions.

Quick reference:

# Default (Jazzy) - works out of the box
cargo build

# For Humble - use --no-default-features
cargo build --no-default-features --features humble

# For Rolling/Iron - just add the feature
cargo build --features rolling

The distribution choice affects type hash support and interoperability with ROS 2 nodes. See the Distribution Compatibility chapter for full details.

Development

This section is for contributors working on ros-z itself. If you're using ros-z in your project, you can skip this section.

Package Organization

The ros-z repository is organized as a Cargo workspace with multiple packages:

PackageDefault BuildPurposeDependencies
ros-zYesCore Zenoh-native ROS 2 libraryNone
ros-z-codegenYesMessage generation utilitiesNone
ros-z-msgsNoPre-generated message typesNone (all vendored)
ros-z-testsNoIntegration testsros-z-msgs
rcl-zNoRCL C bindingsROS 2 required

Note

Only ros-z and ros-z-codegen build by default. Other packages are optional for development, testing, and running examples.

Building the Repository

When contributing to ros-z, you can build different parts of the workspace:

# Build core library
cargo build

# Run tests
cargo test

# Build with bundled messages for examples
cargo build -p ros-z-msgs

# Build all packages (requires ROS 2)
source /opt/ros/jazzy/setup.bash
cargo build --all

Message Package Resolution

The build system automatically locates ROS message definitions:

Search order:

  1. System ROS installation (AMENT_PREFIX_PATH, CMAKE_PREFIX_PATH)
  2. Common ROS paths (/opt/ros/{rolling,jazzy,iron,humble})
  3. Bundled assets (built-in message definitions in ros-z-codegen)

This fallback mechanism enables builds without ROS 2 installed.

Common Development Commands

# Fast iterative development
cargo check                # Quick compile check
cargo build                # Debug build
cargo build --release      # Optimized build
cargo test                 # Run tests
cargo clippy              # Lint checks

# Clean builds
cargo clean                # Remove all build artifacts
cargo clean -p ros-z-msgs  # Clean specific package

Warning

After changing feature flags or updating ROS 2, run cargo clean -p ros-z-msgs to force message regeneration.

Next Steps

Start with the simplest build and add dependencies incrementally as your project grows.

ROS 2 Distribution Compatibility

ros-z supports multiple ROS 2 distributions through compile-time feature flags. This chapter explains the differences between distributions and how to target specific ROS 2 versions.

Supported Distributions

DistributionStatusType Hash SupportDefault
Jazzy Jalisco✅ Fully Supported✅ YesYes
Humble Hawksbill✅ Supported❌ No (placeholder)No
Rolling Ridley✅ Supported✅ YesNo
Iron Irwini✅ Supported✅ YesNo

Default: ros-z defaults to Jazzy compatibility, which is the recommended distribution for new projects.

Distribution Differences

Type Hash Support

The most significant difference between distributions is type hash support:

Jazzy/Rolling/Iron (Modern):

  • Supports real type hashes computed from message definitions
  • Format: RIHS01_<64-hex-chars> (ROS IDL Hash Standard version 1)
  • Enables type safety checks during pub/sub matching
  • Type hashes are embedded in Zenoh key expressions for discovery

Humble (Legacy):

  • Does not support real type hashes
  • Uses constant placeholder: "TypeHashNotSupported"
  • No type safety validation during discovery
  • Compatible with rmw_zenoh_cpp v0.1.8

Example Key Expressions

Jazzy:

@ros2_lv/0/<zid>/<nid>/<eid>/MP/%/<namespace>/<node>/chatter/std_msgs%msg%String/RIHS01_1234567890abcdef.../...

Humble:

@ros2_lv/0/<zid>/<nid>/<eid>/MP/%/<namespace>/<node>/chatter/std_msgs%msg%String/TypeHashNotSupported/...

Building for Different Distributions

Using Jazzy (Default)

By default, ros-z builds with Jazzy compatibility. No special flags needed:

# Build with default (Jazzy)
cargo build

# Run examples
cargo run --example demo_nodes_talker

# Run tests
cargo nextest run

Using Humble

To build for Humble, use --no-default-features --features humble:

# Build for Humble
cargo build --no-default-features --features humble

# Run examples for Humble
cargo run --no-default-features --features humble --example demo_nodes_talker

# Run tests for Humble
cargo nextest run --no-default-features --features humble

Using Other Distributions

For Rolling or Iron, simply specify the distro feature:

# Build for Rolling
cargo build --features rolling

# Build for Iron
cargo build --features iron

Running Examples

Note

The examples described here are part of the ros-z repository. To run them, you must first clone the repository.

git clone https://github.com/ZettaScaleLabs/ros-z.git
cd ros-z

Start the Zenoh Router

All examples require a Zenoh router to be running first (see Networking for why ros-z uses router-based architecture by default).

From the ros-z Repository

If you're working in the ros-z repository, use the included router example:

cargo run --example zenoh_router

From Your Own Project

If you're working on your own project, you need to install a Zenoh router. Quick options:

# Using cargo
cargo install zenohd

# Using Docker
docker run --init --net host eclipse/zenoh:latest

# Using apt (Ubuntu/Debian)
echo "deb [trusted=yes] https://download.eclipse.org/zenoh/debian-repo/ /" | sudo tee /etc/apt/sources.list.d/zenoh.list
sudo apt update && sudo apt install zenoh

Then run:

zenohd

Tip

See the comprehensive Zenoh Router Installation Guide for all installation methods including pre-built binaries, package managers, and more.


Available Examples

Leave the router running in a separate terminal, then run any example in another terminal from the ros-z repository root:

# Pure Rust example with custom messages (no ros-z-msgs needed)
cargo run --example z_custom_message -- --mode status-pub

# Examples using bundled messages (requires ros-z-msgs)
cargo run --example z_pubsub          # Publisher/Subscriber with std_msgs
cargo run --example twist_pub         # Publishing geometry_msgs
cargo run --example battery_state_sub # Receiving sensor_msgs
cargo run --example z_srvcli          # Service example with example_interfaces

Tip

For a detailed walkthrough of creating your own project with ros-z (not using the repository examples), see the Quick Start guide.


Demo Nodes

The demo_nodes examples are basic ROS 2 patterns referenced from ROS 2 demo_nodes_cpp. These demonstrate fundamental pub/sub and service patterns.

Talker (Publisher)

A simple publisher node that publishes "Hello World" messages to the /chatter topic.

Features:

  • Publishes std_msgs/String messages
  • Uses async API for non-blocking publishing
  • Publishes at 1 Hz (configurable)
  • Uses QoS history depth of 7 (KeepLast)

Usage:

# Default settings (topic: chatter, period: 1.0s)
cargo run --example demo_nodes_talker

# Custom topic and faster publishing
cargo run --example demo_nodes_talker -- --topic /my_topic --period 0.5

# Connect to specific Zenoh router
cargo run --example demo_nodes_talker -- --endpoint tcp/localhost:7447

Command-line Options:

OptionDescriptionDefault
-t, --topic <TOPIC>Topic name to publish tochatter
-p, --period <PERIOD>Publishing period in seconds1.0
-m, --mode <MODE>Zenoh session mode (peer/client/router)peer
-e, --endpoint <ENDPOINT>Zenoh router endpoint to connect to-

Listener (Subscriber)

A simple subscriber node that listens to messages on a topic.

Features:

  • Subscribes to std_msgs/String messages
  • Uses async API for receiving messages
  • Uses QoS history depth of 10 (KeepLast)
  • Prints received messages to console

Usage:

# Default settings (topic: chatter)
cargo run --example demo_nodes_listener

# Custom topic
cargo run --example demo_nodes_listener -- --topic /my_topic

# Connect to specific Zenoh router
cargo run --example demo_nodes_listener -- --endpoint tcp/localhost:7447

Command-line Options:

OptionDescriptionDefault
-t, --topic <TOPIC>Topic name to subscribe tochatter
-m, --mode <MODE>Zenoh session mode (peer/client/router)peer
-e, --endpoint <ENDPOINT>Zenoh router endpoint to connect to-

Test the pub/sub pattern:

Terminal 1:

cargo run --example demo_nodes_talker

Terminal 2:

cargo run --example demo_nodes_listener

Expected output in Terminal 2:

I heard: [Hello World: 1]
I heard: [Hello World: 2]
I heard: [Hello World: 3]
...

Add Two Ints Server

A simple service server that adds two integers and returns the result.

Features:

  • Provides example_interfaces/AddTwoInts service
  • Handles addition requests synchronously
  • Uses async API for service handling
  • Prints received requests and sent responses

Usage:

# Default settings (handles unlimited requests)
cargo run --example demo_nodes_add_two_ints_server

# Handle only one request and exit
cargo run --example demo_nodes_add_two_ints_server -- --count 1

# Connect to specific Zenoh router
cargo run --example demo_nodes_add_two_ints_server -- --endpoint tcp/localhost:7447

Command-line Options:

OptionDescriptionDefault
-c, --count <COUNT>Number of requests to handle before exiting (0 for unlimited)0
-m, --mode <MODE>Zenoh session mode (peer/client/router)peer
-e, --endpoint <ENDPOINT>Zenoh router endpoint to connect to-

Add Two Ints Client

A simple service client that sends addition requests to the server.

Features:

  • Calls example_interfaces/AddTwoInts service
  • Supports both synchronous and asynchronous response waiting
  • Uses async API for client operations
  • Configurable numbers to add

Usage:

# Default settings (sync mode, adds 2 + 3)
cargo run --example demo_nodes_add_two_ints_client

# Async mode
cargo run --example demo_nodes_add_two_ints_client -- --async-mode

# Custom numbers
cargo run --example demo_nodes_add_two_ints_client -- --a 10 --b 20

# Async mode with custom numbers
cargo run --example demo_nodes_add_two_ints_client -- --a 10 --b 20 --async-mode

# Connect to specific Zenoh router
cargo run --example demo_nodes_add_two_ints_client -- --endpoint tcp/localhost:7447

Command-line Options:

OptionDescriptionDefault
-a, --a <A>First number to add2
-b, --b <B>Second number to add3
--async-modeUse asynchronous response waitingfalse
-m, --mode <MODE>Zenoh session mode (peer/client/router)peer
-e, --endpoint <ENDPOINT>Zenoh router endpoint to connect to-

Test the service pattern:

Terminal 1 (Server):

cargo run --example demo_nodes_add_two_ints_server -- --count 1

Terminal 2 (Client - sync mode):

cargo run --example demo_nodes_add_two_ints_client

Or Terminal 2 (Client - async mode):

cargo run --example demo_nodes_add_two_ints_client -- --async-mode

Expected output (Client):

AddTwoInts service client started (mode: sync/async)
Sending request: 2 + 3
Received response: 5
Result: 5

Expected output (Server):

AddTwoInts service server started
Received request: 2 + 3
Sending response: 5

Custom Messages Demo

This example demonstrates how to generate Rust types from user-defined ROS 2 message definitions. See the Custom Messages chapter for comprehensive documentation.

Quick start:

cd crates/ros-z/examples/custom_msgs_demo
ROS_Z_MSG_PATH="./my_robot_msgs" cargo build

Protobuf Demo

This example demonstrates using protobuf serialization with ros-z, both for ROS messages and custom protobuf messages. See the Protobuf Serialization chapter for comprehensive documentation.

Quick start:

cd crates/ros-z/examples/protobuf_demo
cargo run

Networking

Configure ros-z's Zenoh transport layer for optimal performance in your deployment environment. ros-z uses router-based architecture by default, matching ROS 2's official rmw_zenoh_cpp middleware for production-ready scalability.

graph TB
    Router["zenohd <br> (router)"]

    Talker["Talker node <br> (peer)"]
    Listener["Listener node <br> (peer)"]

    Router <-->|Discovery| Talker
    Router <-->|Discovery| Listener
    Talker <-.->|P2P Communication| Listener

Router-Based Architecture

ros-z uses a centralized Zenoh router for node discovery and communication, providing:

BenefitDescription
ScalabilityCentralized discovery handles large deployments efficiently
Lower Network OverheadTCP-based discovery instead of multicast broadcasts
ROS 2 CompatibilityMatches rmw_zenoh_cpp behavior for seamless interoperability
Production ReadyBattle-tested configuration used in real robotics systems

Quick Start

The default ros-z configuration connects to a Zenoh router on tcp/localhost:7447:

use ros_z::context::ZContextBuilder;
use ros_z::Builder;

// Uses default ROS session config (connects to tcp/localhost:7447)
let ctx = ZContextBuilder::default().build()?;
let node = ctx.create_node("my_node").build()?;

Success

That's it! The default configuration automatically connects to the router. Now you just need to run one.

Running the Zenoh Router

ros-z applications require a Zenoh router to be running. There are several ways to get one - choose based on your environment and requirements.

Quick Comparison

MethodBest ForRequiresSetup Speed
Cargo InstallRust developersRust toolchainSlower (build from source)
Pre-built BinaryQuick setup, no RustNoneFast
DockerContainers, CI/CDDockerFast
Package ManagerSystem-wide installapt/brew/etcFast
ros-z Exampleros-z repo developersros-z repositoryVery Fast
ROS 2 rmw_zenohROS 2 interop testingROS 2 installedAlready installed

Method 1: Cargo Install

Recommended for Rust developers building standalone projects.

Install the official Zenoh router using Cargo:

cargo install zenohd

Run the router:

zenohd

Pros:

  • Always up-to-date with latest Zenoh
  • Builds optimized for your system
  • Easy to update: cargo install zenohd --force

Cons:

  • Requires Rust toolchain
  • Takes 2-5 minutes to compile

Method 2: Pre-built Binary

Fastest way to get started without Rust installed.

Download: Go to the Zenoh Releases page and download the appropriate archive for your platform:

  • Linux (x86_64): zenoh-*-x86_64-unknown-linux-gnu-standalone.zip
  • macOS (Apple Silicon): zenoh-*-aarch64-apple-darwin-standalone.zip
  • macOS (Intel): zenoh-*-x86_64-apple-darwin-standalone.zip
  • Windows: zenoh-*-x86_64-pc-windows-msvc-standalone.zip

Extract and run:

Linux/macOS:

unzip zenoh-*.zip
chmod +x zenohd
./zenohd

Windows (PowerShell):

Expand-Archive zenoh-*.zip
.\zenoh\zenohd.exe

Pros:

  • No build tools required
  • Instant startup
  • Portable - can run from any directory

Cons:

  • Manual download and extraction
  • Need to track updates yourself

More info: https://zenoh.io/docs/getting-started/installation/


Method 3: Docker

Perfect for containerized deployments and CI/CD pipelines.

Pull and run the official Zenoh router image:

docker run --init --net host eclipse/zenoh:latest

For production with persistent config:

docker run -d \
  --name zenoh-router \
  --net host \
  -v /path/to/config:/zenoh/config \
  eclipse/zenoh:latest \
  --config /zenoh/config/zenoh.json5

Pros:

  • Isolated from host system
  • Easy to deploy and scale
  • Works great in Kubernetes/Docker Compose
  • Consistent across environments

Cons:

  • Requires Docker installed
  • Network setup can be tricky (use --net host for simplicity)

Docker Hub: https://hub.docker.com/r/eclipse/zenoh/tags


Method 4: Package Manager (apt, brew)

Best for system-wide installation on Linux/macOS.

Ubuntu/Debian (via apt):

echo "deb [trusted=yes] https://download.eclipse.org/zenoh/debian-repo/ /" | sudo tee /etc/apt/sources.list.d/zenoh.list
sudo apt update
sudo apt install zenoh

Run as a service:

sudo systemctl enable zenoh
sudo systemctl start zenoh

Or run manually:

zenohd

macOS (via Homebrew):

brew tap eclipse-zenoh/homebrew-zenoh
brew install zenoh
zenohd

Arch Linux (via AUR):

yay -S zenoh
zenohd

Pros:

  • System-wide installation
  • Easy updates via package manager
  • Can run as systemd service (Linux)
  • Integrates with OS security/firewall settings

Cons:

  • May not have the absolute latest version
  • Requires sudo/admin privileges

Method 5: ros-z Example Router

Only available when working in the ros-z repository - perfect for quick development/testing.

If you've cloned the ros-z repository:

cd /path/to/ros-z
cargo run --example zenoh_router

This runs a pre-configured router that matches ros-z defaults exactly.

Pros:

  • No installation needed
  • Already configured for ros-z
  • Useful for debugging ros-z itself

Cons:

  • Only available in the ros-z repository
  • Not suitable for standalone projects
  • Slower startup (rebuilds if code changes)

Warning

This method is for ros-z repository development only. If you're building your own project with ros-z as a dependency, use one of the other methods instead.


Method 6: ROS 2 rmw_zenoh

Use this if you have ROS 2 installed and want to test interoperability with ROS 2 nodes.

If you have ROS 2 Jazzy or newer with the Zenoh middleware:

ros2 run rmw_zenoh_cpp rmw_zenohd

Pros:

  • Already installed with ROS 2 Jazzy+
  • Guaranteed compatibility with ROS 2 nodes
  • Can interoperate ros-z nodes with C++/Python ROS 2 nodes

Cons:

  • Requires full ROS 2 installation
  • Overkill if you only want to use ros-z

Tip

This is excellent for testing interoperability - run ros-z nodes alongside standard ROS 2 nodes using the same router.


Verifying the Router is Running

After starting a router with any method above, verify it's working:

Check the router is listening on port 7447:

# Linux/macOS
netstat -an | grep 7447

# Or use lsof
lsof -i :7447

Test with a ros-z application:

# In another terminal, try running a ros-z node
# If it connects successfully, the router is working

You should see log output from the router showing connections when your ros-z nodes start.

Next Steps

Choose the configuration approach that fits your needs:

Ready to optimize your deployment? Experiment with different configurations and measure performance impact.

Configuration Options

ros-z provides multiple ways to configure Zenoh, from simple to advanced.

Use the built-in ROS session config for standard deployments:

let ctx = ZContextBuilder::default().build()?;

What it does:

  • Connects to router at tcp/localhost:7447
  • Uses ROS-compatible timeouts and buffer sizes
  • Disables multicast discovery (uses router instead)

Option 2: Custom Router Endpoint

Connect to a router on a different host or port:

let ctx = ZContextBuilder::default()
    .with_router_endpoint("tcp/192.168.1.100:7447")
    .build()?;

Use cases:

  • Distributed systems with remote router
  • Custom port configurations
  • Multiple isolated networks

Option 3: Environment Variable Overrides

Override any Zenoh configuration setting using the ROSZ_CONFIG_OVERRIDE environment variable without changing code:

# Override mode and endpoint
export ROSZ_CONFIG_OVERRIDE='mode="client";connect/endpoints=["tcp/192.168.1.100:7447"]'

# Run your application
cargo run --example my_app
// No code changes needed - overrides are applied automatically
let ctx = ZContextBuilder::default().build()?;

Format:

  • Semicolon-separated key=value pairs
  • Values use JSON5 syntax
  • Keys use slash-separated paths (e.g., connect/endpoints, scouting/multicast/enabled)

Common examples:

# Connect to remote router
export ROSZ_CONFIG_OVERRIDE='connect/endpoints=["tcp/10.0.0.5:7447"]'

# Enable multicast scouting explicitly
export ROSZ_CONFIG_OVERRIDE='scouting/multicast/enabled=true'

# Multiple overrides
export ROSZ_CONFIG_OVERRIDE='mode="client";connect/timeout_ms=5000;scouting/multicast/enabled=false'

Tip

Environment variable overrides have the highest priority and will override any programmatic configuration or config file settings.

Option 4: Advanced Configuration Builders

Fine-tune session or router settings programmatically:

use ros_z::config::{SessionConfigBuilder, RouterConfigBuilder};

// Customize session config
let session_config = SessionConfigBuilder::new()
    .with_router_endpoint("tcp/192.168.1.100:7447")
    .build()?;

let ctx = ZContextBuilder::default()
    .with_zenoh_config(session_config)
    .build()?;

// Or build a custom router config
let router_config = RouterConfigBuilder::new()
    .with_listen_port(7448)  // Custom port
    .build()?;

zenoh::open(router_config).await?;

Key builder methods:

BuilderMethodsPurpose
SessionConfigBuilderwith_router_endpoint(endpoint)Connect to custom router
RouterConfigBuilderwith_listen_port(port)Set custom router port

Option 5: Peer Mode Using Multicast Discovery (No Router Required)

Revert to multicast peer discovery for simple setups:

// Use vanilla Zenoh config (peer mode with multicast)
let ctx = ZContextBuilder::default()
    .with_zenoh_config(zenoh::Config::default())
    .build()?;

Warning

Multicast scouting discovery is convenient for quick testing but doesn't scale well and won't work with ROS 2 nodes using rmw_zenoh_cpp (which expects a zenoh router).

Option 6: Load from Config File

Use JSON5 config files for complex deployments:

let ctx = ZContextBuilder::default()
    .with_config_file("/etc/zenoh/session_config.json5")
    .build()?;

When to use:

  • Deploying across multiple machines
  • Environment-specific configurations
  • Version-controlled infrastructure

Advanced Configuration

Generating Config Files

ros-z can generate JSON5 config files matching rmw_zenoh_cpp defaults. This is opt-in via the generate-configs feature flag.

Basic Generation

cargo build --features generate-configs

Output location:

target/debug/build/ros-z-*/out/ros_z_config/
  ├── DEFAULT_ROSZ_ROUTER_CONFIG.json5
  └── DEFAULT_ROSZ_SESSION_CONFIG.json5

Custom Output Directory

Specify a custom directory using the ROS_Z_CONFIG_OUTPUT_DIR environment variable:

Absolute path:

ROS_Z_CONFIG_OUTPUT_DIR=/etc/zenoh cargo build --features generate-configs

Relative path (from package root):

ROS_Z_CONFIG_OUTPUT_DIR=./config cargo build --features generate-configs

From workspace root:

ROS_Z_CONFIG_OUTPUT_DIR=$PWD/config cargo build -p ros-z --features generate-configs

Tip

Generated files include inline comments explaining each setting, making them perfect documentation references.

Using Generated Files

let ctx = ZContextBuilder::default()
    .with_config_file("./config/DEFAULT_ROSZ_SESSION_CONFIG.json5")
    .build()?;

Configuration Reference

Key Settings Explained

SettingRouterSessionPurpose
ModerouterpeerRouter relays messages, peers connect directly
Listen Endpointtcp/[::]:7447-Router accepts connections
Connect Endpoint-tcp/localhost:7447Session connects to router
MulticastDisabledDisabledUses TCP gossip for discovery
Unicast Timeout60s60sHandles slow networks/large deployments
Query Timeout10min10minLong-running service calls
Max Sessions10,000-Supports concurrent node startup
Keep-Alive2s2sOptimized for loopback

Note

These defaults are tuned for ROS 2 deployments and match rmw_zenoh_cpp exactly. Only modify them if you have specific performance requirements.

Message Generation

Automatic Rust type generation from ROS 2 message definitions at build time. The code generation system converts .msg, .srv, and .action files into type-safe Rust structs with full serialization support and ROS 2 compatibility.

Success

Message generation happens automatically during builds. You write ROS 2 message definitions, ros-z generates idiomatic Rust code.

System Architecture

graph LR
    A[.msg/.srv files] --> B[ros-z-codegen]
    B --> C[Parse & Resolve]
    C --> D[Type Hashing]
    D --> E[Code Generation]
    E --> F[Rust Generator]
    E --> G[Protobuf Generator]
    F --> H[Rust Structs + Traits]
    G --> I[Proto Files + Rust]
    H --> J[ros-z-msgs]
    I --> J

Key Features

FeatureDescriptionBenefit
Build-time generationRuns during cargo buildNo manual steps
Bundled definitionsIncludes common ROS typesWorks without ROS 2
Type safetyFull Rust type systemCompile-time validation
CDR compatibleROS 2 DDS serializationFull interoperability
Optional protobufAdditional serializationCross-language support

Component Stack

ros-z-codegen

Internal message generation library for ros-z:

  • Parses .msg, .srv, and .action file syntax
  • Resolves message dependencies across packages
  • Calculates ROS 2 type hashes (RIHS algorithm)
  • Generates Rust structs with serde
  • Bundles common message definitions

Info

ros-z-codegen provides bundled messages for std_msgs, geometry_msgs, sensor_msgs, and nav_msgs. These work without ROS 2 installation.

Orchestration Layer

ros-z-codegen's orchestration capabilities:

  • Coordinates message discovery across sources
  • Manages build-time code generation
  • Provides code generators for different serialization formats
  • Generates ros-z-specific traits

Discovery workflow:

sequenceDiagram
    participant B as build.rs
    participant D as Discovery
    participant S as Sources

    B->>D: Find packages
    D->>S: Check AMENT_PREFIX_PATH
    alt Found in system
        S-->>D: System messages
    else Not found
        D->>S: Check /opt/ros/*
        alt Found in standard path
            S-->>D: System messages
        else Not found
            D->>S: Check bundled assets
            S-->>D: Bundled messages
        end
    end
    D-->>B: Package paths
    B->>B: Generate Rust code

Code Generators

Rust Generator (default):

  • Generates structs with serde
  • CDR-compatible serialization via ros-z-cdr
  • Full ROS 2 DDS interoperability
  • No additional dependencies

Protobuf Generator (optional):

  • Generates .proto files
  • Protobuf-compatible types
  • Cross-language data exchange
  • Requires protobuf feature

Generated Code

For each ROS 2 message, ros-z generates:

Message Struct

#[derive(Debug, Clone, Serialize, Deserialize, Default)]
pub struct String {
    pub data: std::string::String,
}

Type Information Traits

impl MessageTypeInfo for std_msgs::String {
    fn type_name() -> &'static str {
        "std_msgs::msg::dds_::String_"
    }

    fn type_hash() -> TypeHash {
        TypeHash::from_rihs_string("RIHS01_abc123...")
            .expect("Invalid hash")
    }
}

impl WithTypeInfo for std_msgs::String {
    fn type_info() -> TypeInfo {
        TypeInfo::new(Self::type_name(), Self::type_hash())
    }
}

These traits enable:

  • Runtime type identification
  • ROS 2 compatibility validation
  • Proper DDS topic naming
  • Type-safe message passing

Note

Type hashes are critical for ROS 2 interoperability. They ensure nodes agree on message structure before exchanging data.

Build Process

ros-z-msgs Build Script

The generation happens in build.rs:

flowchart TD
    A[Start build.rs] --> B[Read enabled features]
    B --> C[Discover package paths]
    C --> D{Messages found?}
    D -->|Yes| E[Parse message definitions]
    D -->|No| F[Build error]
    E --> G[Resolve dependencies]
    G --> H[Generate Rust code]
    H --> I[Write to OUT_DIR]
    I --> J[Compile completes]

Configuration:

let config = GeneratorConfig {
    generate_cdr: true,        // CDR-compatible types
    generate_protobuf: false,  // Optional protobuf
    generate_type_info: true,  // Trait implementations
    output_dir: out_dir,
};

Package Discovery Order

flowchart LR
    A[Feature Flags] --> B{System ROS?}
    B -->|Found| C[AMENT_PREFIX_PATH]
    B -->|Not Found| D{/opt/ros/distro?}
    D -->|Found| E[Standard paths]
    D -->|Not Found| F[Bundled assets]

    C --> G[Generate from system]
    E --> G
    F --> H[Generate from bundled]
  1. System ROS: $AMENT_PREFIX_PATH, $CMAKE_PREFIX_PATH
  2. Standard paths: /opt/ros/{rolling,jazzy,iron,humble}
  3. Bundled assets: Built-in message definitions in ros-z-codegen

This fallback enables development without ROS 2 installation.

Using Generated Messages

Import Pattern

use ros_z_msgs::ros::std_msgs::String as RosString;
use ros_z_msgs::ros::geometry_msgs::Twist;
use ros_z_msgs::ros::sensor_msgs::LaserScan;

Namespace Structure

ros_z_msgs::ros::{package}::{MessageName}

Examples:

  • ros_z_msgs::ros::std_msgs::String
  • ros_z_msgs::ros::geometry_msgs::Point
  • ros_z_msgs::ros::sensor_msgs::Image

Service Types

Services generate three types:

// Service definition
use ros_z_msgs::ros::example_interfaces::AddTwoInts;

// Request type
use ros_z_msgs::ros::example_interfaces::AddTwoIntsRequest;

// Response type
use ros_z_msgs::ros::example_interfaces::AddTwoIntsResponse;

Tip

Import the service type for creation, then use the request/response types when handling calls.

Message Packages

Bundled Packages

Available without ROS 2:

PackageMessagesUse Cases
std_msgsString, Int32, Float64, etc.Basic data types
geometry_msgsPoint, Pose, Twist, TransformSpatial data
sensor_msgsLaserScan, Image, Imu, PointCloud2Sensor readings
nav_msgsPath, Odometry, OccupancyGridNavigation
# Build with bundled messages
cargo build -p ros-z-msgs --features bundled_msgs

Additional Packages

These packages are bundled and available without ROS 2 installation:

PackageMessagesUse Cases
example_interfacesAddTwoInts, FibonacciTutorials
action_tutorials_interfacesFibonacci actionAction tutorials
test_msgsTest typesTesting
# All packages are bundled by default
cargo build -p ros-z-msgs --features all_msgs

Manual Custom Messages

For rapid prototyping without .msg files:

Define the Struct

use serde::{Deserialize, Serialize};

#[derive(Debug, Clone, Serialize, Deserialize, Default)]
pub struct RobotStatus {
    pub robot_id: String,
    pub battery_percentage: f64,
    pub position: [f64; 2],
    pub is_moving: bool,
}

Implement Required Traits

use ros_z::{MessageTypeInfo, WithTypeInfo, entity::TypeHash};

impl MessageTypeInfo for RobotStatus {
    fn type_name() -> &'static str {
        "custom_msgs::msg::dds_::RobotStatus_"
    }

    fn type_hash() -> TypeHash {
        // For ros-z-to-ros-z only
        TypeHash::zero()
    }
}

impl WithTypeInfo for RobotStatus {}

Warning

Manual messages with TypeHash::zero() work only between ros-z nodes. For ROS 2 interoperability, use generated messages with proper type hashes.

When to Use Each Approach

flowchart TD
    A[Need Custom Message?] --> B{Prototyping?}
    B -->|Yes| C[Manual Implementation]
    B -->|No| D{ROS 2 Interop?}
    D -->|Required| E[Generate from .msg]
    D -->|Not Required| F{Want Type Safety?}
    F -->|Yes| E
    F -->|No| C
ApproachProsConsUse When
ManualFast, flexibleNo ROS 2 interopPrototyping, internal only
GeneratedType hashes, portableRequires .msg filesProduction, ROS 2 systems

Serialization Formats

CDR (Default)

Common Data Representation - ROS 2 standard:

  • Full DDS compatibility
  • Efficient binary encoding
  • Used by all ROS 2 implementations
  • Automatic via serde
// Generated with CDR support
#[derive(Serialize, Deserialize)]
pub struct String {
    pub data: std::string::String,
}

Protobuf (Optional)

Protocol Buffers alternative:

cargo build -p ros-z-msgs --features protobuf
cargo build -p ros-z --features protobuf

Benefits:

  • Schema evolution
  • Cross-language compatibility
  • Familiar ecosystem
  • Efficient encoding

Tradeoffs:

  • Not ROS 2 standard format
  • Additional dependencies
  • Requires feature flag

Info

Use protobuf when you need schema evolution or cross-language data exchange beyond ROS 2 ecosystem. See Protobuf Serialization for detailed usage guide.

Extending Message Packages

Add new packages to ros-z-msgs:

1. Add Feature Flag

Edit ros-z-msgs/Cargo.toml:

[features]
bundled_msgs = ["std_msgs", "geometry_msgs", "your_package"]
your_package = []

2. Update Build Script

Edit ros-z-msgs/build.rs:

fn get_bundled_packages() -> Vec<&'static str> {
    let mut names = vec!["builtin_interfaces"];

    #[cfg(feature = "your_package")]
    names.push("your_package");

    names
}

3. Rebuild

cargo build -p ros-z-msgs --features your_package

The build system automatically:

  • Searches for the package
  • Parses all message definitions
  • Generates Rust types with traits
  • Outputs to generated module

Advanced Topics

Message Filtering

The generator automatically filters:

  • Deprecated actionlib messages - Old ROS 1 format
  • wstring fields - Poor Rust support
  • Duplicate definitions - Keeps first occurrence

Type Hash Calculation

ros-z uses the RIHS (ROS IDL Hash) algorithm:

flowchart LR
    A[Message Definition] --> B[Parse Structure]
    B --> C[Include Dependencies]
    C --> D[Calculate Hash]
    D --> E[RIHS String]
    E --> F[TypeHash Object]

Properties:

  • Includes message structure and field types
  • Incorporates dependency hashes
  • Changes when definition changes
  • Ensures type safety across network

In generated code:

TypeHash::from_rihs_string("RIHS01_1234567890abcdef...")
    .expect("Invalid RIHS hash string")

Custom Code Generation

For custom build scripts:

use ros_z_codegen::{MessageGenerator, GeneratorConfig};

let config = GeneratorConfig {
    generate_cdr: true,
    generate_protobuf: false,
    generate_type_info: true,
    output_dir: out_dir.clone(),
};

let generator = MessageGenerator::new(config);
generator.generate_from_msg_files(&package_paths)?;

Troubleshooting

Package Not Found

# Check ROS 2 is sourced
echo $AMENT_PREFIX_PATH

# Verify package exists
ros2 pkg list | grep your_package

# Install if missing
sudo apt install ros-jazzy-your-package

# Bundled packages are built into ros-z-codegen
cargo build -p ros-z-msgs --features bundled_msgs

Build Failures

ErrorCauseSolution
"Cannot find package"Missing dependencyEnable feature or install ROS 2 package
"Type conflict"Duplicate definitionRemove manual implementation
"Hash error"Version mismatchUpdate ros-z-codegen dependency

See Troubleshooting Guide for detailed solutions.

Resources

Message generation is transparent. Focus on writing ROS 2 message definitions and let ros-z handle the Rust code generation.

Custom Messages

ros-z supports two approaches for defining custom message types:

ApproachDefinitionBest For
Rust-NativeWrite Rust structs directlyPrototyping, ros-z-only systems
Schema-GeneratedWrite .msg/.srv files, generate RustProduction, ROS 2 interop
flowchart TD
    A[Need Custom Messages?] -->|Yes| B{ROS 2 Interop Needed?}
    B -->|Yes| C[Schema-Generated]
    B -->|No| D{Quick Prototype?}
    D -->|Yes| E[Rust-Native]
    D -->|No| C
    A -->|No| F[Use Standard Messages]

Rust-Native Messages

Define messages directly in Rust by implementing required traits. This approach is fast for prototyping but only works between ros-z nodes.

Warning

Rust-Native messages use TypeHash::zero() and won't interoperate with ROS 2 C++/Python nodes.

Workflow of Rust-Native Messages

graph LR
    A[Define Struct] --> B[Impl MessageTypeInfo]
    B --> C[Add Serde Traits]
    C --> D[Impl WithTypeInfo]
    D --> E[Use in Pub/Sub]

Required Traits

TraitPurposeKey Method
MessageTypeInfoType identificationtype_name(), type_hash()
WithTypeInforos-z integrationtype_info()
Serialize/DeserializeData encodingFrom serde

Message Example

use ros_z::{MessageTypeInfo, entity::{TypeHash, TypeInfo}};
use ros_z::ros_msg::WithTypeInfo;
use serde::{Serialize, Deserialize};

#[derive(Debug, Clone, Serialize, Deserialize)]
struct RobotStatus {
    battery_level: f32,
    position_x: f32,
    position_y: f32,
    is_moving: bool,
}

impl MessageTypeInfo for RobotStatus {
    fn type_name() -> &'static str {
        "my_msgs::msg::dds_::RobotStatus_"
    }

    fn type_hash() -> TypeHash {
        TypeHash::zero()  // ros-z-to-ros-z only
    }
}

impl WithTypeInfo for RobotStatus {
    fn type_info() -> TypeInfo {
        TypeInfo::new(Self::type_name(), Self::type_hash())
    }
}

Service Example

use ros_z::{ServiceTypeInfo, msg::ZService};

#[derive(Debug, Clone, Serialize, Deserialize)]
struct NavigateToRequest {
    target_x: f32,
    target_y: f32,
}

#[derive(Debug, Clone, Serialize, Deserialize)]
struct NavigateToResponse {
    success: bool,
}

struct NavigateTo;

impl ServiceTypeInfo for NavigateTo {
    fn service_type_info() -> TypeInfo {
        TypeInfo::new("my_msgs::srv::dds_::NavigateTo_", TypeHash::zero())
    }
}

impl ZService for NavigateTo {
    type Request = NavigateToRequest;
    type Response = NavigateToResponse;
}

See the z_custom_message example:

# Terminal 1: Router
cargo run --example zenoh_router

# Terminal 2: Subscriber
cargo run --example z_custom_message -- --mode status-sub

# Terminal 3: Publisher
cargo run --example z_custom_message -- --mode status-pub

Schema-Generated Messages

Define messages in .msg/.srv files and generate Rust code using ros-z-codegen. This approach provides proper type hashes and can reference standard ROS 2 types.

Tip

Schema-Generated messages get proper RIHS01 type hashes and can reference types from ros_z_msgs like geometry_msgs/Point.

Workflow of Schema-Generated Messages

graph LR
    A[Write .msg files] --> B[Create Rust crate]
    B --> C[Add build.rs]
    C --> D[Set ROS_Z_MSG_PATH]
    D --> E[cargo build]
    E --> F[Use generated types]

Step 1: Create Message Package

Create a ROS 2 style directory structure:

my_robot_msgs/
├── msg/
│   ├── RobotStatus.msg
│   └── SensorReading.msg
└── srv/
    └── NavigateTo.srv

Step 2: Define Messages

Messages can reference standard ROS 2 types:

# RobotStatus.msg
string robot_id
geometry_msgs/Point position
bool is_moving
# SensorReading.msg
builtin_interfaces/Time timestamp
float64[] values
string sensor_id
# NavigateTo.srv
geometry_msgs/Point target
float64 max_speed
---
bool success
string message

Step 3: Create Rust Crate

Cargo.toml:

[package]
name = "my-robot-msgs"
version = "0.1.0"
edition = "2021"

# Standalone package (not part of parent workspace)
[workspace]

[dependencies]
ros-z-msgs = { version = "0.1" }
ros-z = { version = "0.1", default-features = false }
serde = { version = "1", features = ["derive"] }
smart-default = "0.7"
zenoh-buffers = "1"

[build-dependencies]
ros-z-codegen = { version = "0.1" }
anyhow = "1"

build.rs:

use std::path::PathBuf;
use std::env;

fn main() -> anyhow::Result<()> {
    let out_dir = PathBuf::from(env::var("OUT_DIR")?);
    ros_z_codegen::generate_user_messages(&out_dir, false)?;
    println!("cargo:rerun-if-env-changed=ROS_Z_MSG_PATH");
    Ok(())
}

src/lib.rs:

// Re-export standard types from ros-z-msgs
pub use ros_z_msgs::*;

// Include generated user messages
include!(concat!(env!("OUT_DIR"), "/generated.rs"));

Step 4: Build

Set ROS_Z_MSG_PATH and build:

ROS_Z_MSG_PATH="./my_robot_msgs" cargo build

For multiple packages, use colon-separated paths:

ROS_Z_MSG_PATH="./my_msgs:./other_msgs" cargo build

Step 5: Use Generated Types

use my_robot_msgs::ros::my_robot_msgs::{RobotStatus, SensorReading};
use my_robot_msgs::ros::my_robot_msgs::srv::NavigateTo;
use ros_z_msgs::ros::geometry_msgs::Point;
use ros_z_msgs::ros::builtin_interfaces::Time;

let status = RobotStatus {
    robot_id: "robot_1".to_string(),
    position: Point { x: 1.0, y: 2.0, z: 0.0 },
    is_moving: true,
};

let reading = SensorReading {
    timestamp: Time { sec: 1234, nanosec: 0 },
    values: vec![1.0, 2.0, 3.0],
    sensor_id: "lidar_1".to_string(),
};

See ros-z/examples/custom_msgs_demo/ for a working example:

cd ros-z/examples/custom_msgs_demo
ROS_Z_MSG_PATH="./my_robot_msgs" cargo build

Comparison

FeatureRust-NativeSchema-Generated
DefinitionRust structs.msg/.srv files
Type HashesTypeHash::zero()Proper RIHS01 hashes
Standard Type RefsManualAutomatic (geometry_msgs, etc.)
ROS 2 InteropNoPartial (messages yes, services limited)
Setup ComplexityLowMedium (build.rs required)
Best ForPrototypingProduction

Type Naming Convention

Both approaches should follow ROS 2 DDS naming:

# Messages
package::msg::dds_::MessageName_

# Services
package::srv::dds_::ServiceName_

The trailing underscore and dds_ infix match ROS 2's internal naming scheme.


Resources

Protobuf Serialization

Use Protocol Buffers as an alternative serialization format for ros-z messages. While CDR is the default ROS 2-compatible format, protobuf offers schema evolution, cross-language compatibility, and familiar tooling for teams already using the protobuf ecosystem.

Info

Protobuf support in ros-z enables two powerful use cases:

  1. ROS messages with protobuf encoding - Use standard ROS message types serialized via protobuf
  2. Pure protobuf messages - Send custom .proto messages directly through ros-z

When to Use Protobuf

Use CaseRecommendation
ROS 2 interoperabilityUse CDR (default)
Schema evolutionUse Protobuf
Cross-language data exchangeUse Protobuf
Existing protobuf infrastructureUse Protobuf
Performance criticalBenchmark both (typically similar)

Warning

Protobuf-serialized messages are not compatible with standard ROS 2 nodes using CDR. Use protobuf when you control both ends of the communication or need its specific features.

Enabling Protobuf Support

Feature Flags

Enable protobuf in your Cargo.toml:

[dependencies]
ros-z = { version = "0.1", features = ["protobuf"] }
ros-z-msgs = { version = "0.1", features = ["geometry_msgs", "protobuf"] }
prost = "0.13"

[build-dependencies]
prost-build = "0.13"

Build Configuration

For custom .proto files, add a build.rs:

fn main() -> Result<(), Box<dyn std::error::Error>> {
    let mut config = prost_build::Config::new();
    // Enable serde support for ros-z compatibility
    config.type_attribute(".", "#[derive(serde::Serialize, serde::Deserialize)]");
    config.compile_protos(&["proto/sensor_data.proto"], &["proto/"])?;
    println!("cargo:rerun-if-changed=proto/sensor_data.proto");
    Ok(())
}

Approach 1: ROS Messages with Protobuf

Use auto-generated ROS message types with protobuf serialization:

use ros_z::msg::ProtobufSerdes;
use ros_z_msgs::proto::geometry_msgs::Vector3 as Vector3Proto;

let ctx = ros_z::context::ZContextBuilder::default().build()?;
let node = ctx.create_node("protobuf_node").build()?;

// Create publisher with protobuf serialization
let pub = node
    .create_pub::<Vector3Proto>("/vector_proto")
    .with_serdes::<ProtobufSerdes<Vector3Proto>>()
    .build()?;

// Publish messages
let msg = Vector3Proto {
    x: 1.0,
    y: 2.0,
    z: 3.0,
};
pub.publish(&msg)?;

Key points:

  • Import from ros_z_msgs::proto::* namespace (not ros_z_msgs::ros::*)
  • Use .with_serdes::<ProtobufSerdes<T>>() to select protobuf encoding
  • Message types automatically implement MessageTypeInfo trait
  • Full type safety and compile-time checking

Approach 2: Custom Protobuf Messages

Send arbitrary protobuf messages defined in .proto files:

Step 1: Define Your Message

Create proto/sensor_data.proto:

syntax = "proto3";

package examples;

message SensorData {
    string sensor_id = 1;
    double temperature = 2;
    double humidity = 3;
    int64 timestamp = 4;
}

Step 2: Generate Rust Code

Configure build.rs as shown above. The build script generates Rust structs at compile time.

Step 3: Include Generated Code

pub mod sensor_data {
    include!(concat!(env!("OUT_DIR"), "/examples.rs"));
}

use sensor_data::SensorData;

Step 4: Implement Required Traits

use ros_z::{MessageTypeInfo, WithTypeInfo, entity::TypeHash};

impl MessageTypeInfo for SensorData {
    fn type_name() -> &'static str {
        "examples::msg::dds_::SensorData_"
    }

    fn type_hash() -> TypeHash {
        TypeHash::zero()  // For custom protobuf messages
    }
}

impl WithTypeInfo for SensorData {}

Step 5: Use in ros-z

let pub = node
    .create_pub::<SensorData>("/sensor_data")
    .with_serdes::<ProtobufSerdes<SensorData>>()
    .build()?;

let msg = SensorData {
    sensor_id: "sensor_01".to_string(),
    temperature: 23.5,
    humidity: 45.0,
    timestamp: 1234567890,
};

pub.publish(&msg)?;

Complete Example

The protobuf_demo example demonstrates both approaches:

use clap::Parser;
use protobuf_demo::{run_pubsub_demo, run_service_client, run_service_server};
use ros_z::{Builder, Result, context::ZContextBuilder};

#[derive(Debug, Parser)]
#[command(
    name = "protobuf_demo",
    about = "Protobuf demonstration for ros-z - pub/sub and services"
)]
struct Args {
    /// Mode to run: pubsub, service-server, service-client, or combined
    #[arg(short, long, default_value = "pubsub")]
    mode: String,

    /// Service name (for service modes)
    #[arg(long, default_value = "/calculator")]
    service: String,

    /// Maximum number of messages/requests (0 for unlimited)
    #[arg(short = 'n', long, default_value = "3")]
    count: usize,

    /// Zenoh session mode (peer, client, router)
    #[arg(long, default_value = "peer")]
    zenoh_mode: String,

    /// Zenoh router endpoint to connect to
    #[arg(short, long)]
    endpoint: Option<String>,
}

fn main() -> Result<()> {
    let args = Args::parse();

    // Initialize logging
    zenoh::init_log_from_env_or("info");

    // Create the ROS-Z context
    let ctx = if let Some(ref e) = args.endpoint {
        ZContextBuilder::default()
            .with_mode(&args.zenoh_mode)
            .with_connect_endpoints([e.clone()])
            .build()?
    } else {
        ZContextBuilder::default()
            .with_mode(&args.zenoh_mode)
            .build()?
    };

    let max_count = if args.count == 0 {
        None
    } else {
        Some(args.count)
    };

    match args.mode.as_str() {
        "pubsub" => {
            run_pubsub_demo(ctx, max_count)?;
        }
        "service-server" => {
            run_service_server(ctx, &args.service, max_count)?;
        }
        "service-client" => {
            let operations = vec![
                ("add", 10.0, 5.0),
                ("subtract", 10.0, 5.0),
                ("multiply", 10.0, 5.0),
                ("divide", 10.0, 5.0),
                ("divide", 10.0, 0.0), // This will fail
            ];
            run_service_client(ctx, &args.service, operations)?;
        }
        "combined" => {
            println!("\n=== Running Combined Demo ===\n");

            // Create separate contexts for server and client
            let server_ctx = if let Some(e) = args.endpoint.clone() {
                ZContextBuilder::default()
                    .with_mode(&args.zenoh_mode)
                    .with_connect_endpoints([e])
                    .build()?
            } else {
                ZContextBuilder::default()
                    .with_mode(&args.zenoh_mode)
                    .build()?
            };

            let service_name = args.service.clone();

            // Run server in background thread
            let _server_handle =
                std::thread::spawn(move || run_service_server(server_ctx, &service_name, Some(5)));

            // Give server time to start
            std::thread::sleep(std::time::Duration::from_millis(500));

            // Run client
            let operations = vec![
                ("add", 10.0, 5.0),
                ("subtract", 10.0, 5.0),
                ("multiply", 10.0, 5.0),
                ("divide", 10.0, 5.0),
                ("divide", 10.0, 0.0),
            ];
            run_service_client(ctx, &args.service, operations)?;
        }
        _ => {
            eprintln!("Unknown mode: {}", args.mode);
            eprintln!("Valid modes: pubsub, service-server, service-client, combined");
            std::process::exit(1);
        }
    }

    Ok(())
}

Running the Demo

# Navigate to the demo directory
cd ros-z/examples/protobuf_demo

# Run the example
cargo run

Expected output:

=== Protobuf Serialization Demo ===
This demonstrates two ways to use protobuf with ros-z:
1. ROS messages with protobuf serialization (from ros-z-msgs)
2. Custom protobuf messages (from .proto files)
=====================================================

--- Part 1: ROS geometry_msgs/Vector3 with Protobuf ---
Publishing ROS Vector3 messages...

  Published Vector3: x=0, y=0, z=0
  Published Vector3: x=1, y=2, z=3
  Published Vector3: x=2, y=4, z=6

--- Part 2: Custom SensorData message (pure protobuf) ---
Publishing custom SensorData messages...

  Published SensorData: id=sensor_0, temp=20.0°C, humidity=45.0%, ts=1234567890
  Published SensorData: id=sensor_1, temp=20.5°C, humidity=47.0%, ts=1234567891
  Published SensorData: id=sensor_2, temp=21.0°C, humidity=49.0%, ts=1234567892

Successfully demonstrated both protobuf approaches!

Subscribers with Protobuf

Receive protobuf-encoded messages:

use ros_z::msg::ProtobufSerdes;

let sub = node
    .create_sub::<Vector3Proto>("/vector_proto")
    .with_serdes::<ProtobufSerdes<Vector3Proto>>()
    .build()?;

loop {
    let msg = sub.recv()?;
    println!("Received: x={}, y={}, z={}", msg.x, msg.y, msg.z);
}

Important

Publishers and subscribers must use the same serialization format. A protobuf publisher requires a protobuf subscriber.

Services with Protobuf

Both request and response use protobuf encoding:

Server

let service = node
    .create_service::<MyService>("/my_service")
    .with_serdes::<ProtobufSerdes<MyServiceRequest>, ProtobufSerdes<MyServiceResponse>>()
    .build()?;

loop {
    let (key, request) = service.take_request()?;
    let response = process_request(&request);
    service.send_response(&response, &key)?;
}

Client

let client = node
    .create_client::<MyService>("/my_service")
    .with_serdes::<ProtobufSerdes<MyServiceRequest>, ProtobufSerdes<MyServiceResponse>>()
    .build()?;

client.send_request(&request)?;
let response = client.take_response()?;

Available ROS Messages

When ros-z-msgs is built with protobuf feature, it generates protobuf versions of ROS messages:

// Import from proto namespace
use ros_z_msgs::proto::std_msgs::String as StringProto;
use ros_z_msgs::proto::geometry_msgs::{Point, Pose, Twist};
use ros_z_msgs::proto::sensor_msgs::{LaserScan, Image};

Namespace mapping:

FormatNamespaceUse
CDRros_z_msgs::ros::*ROS 2 interop
Protobufros_z_msgs::proto::*Protobuf encoding

Type Information

ROS Messages

Auto-generated messages from ros-z-msgs include MessageTypeInfo:

// No manual implementation needed
use ros_z_msgs::proto::geometry_msgs::Vector3;
// Vector3 already implements MessageTypeInfo

Custom Protobuf Messages

Manual implementation required:

impl MessageTypeInfo for MyProtoMessage {
    fn type_name() -> &'static str {
        // Follow ROS naming convention
        "my_package::msg::dds_::MyProtoMessage_"
    }

    fn type_hash() -> TypeHash {
        // Use zero for custom protobuf messages
        TypeHash::zero()
    }
}

impl WithTypeInfo for MyProtoMessage {}

Note

TypeHash::zero() indicates the message doesn't have ROS 2 type compatibility. This is fine for ros-z-to-ros-z communication.

Protobuf vs CDR Comparison

AspectCDRProtobuf
ROS 2 Compatibility✅ Full❌ None
Schema Evolution❌ Limited✅ Excellent
Cross-languageROS 2 only✅ Universal
ToolingROS ecosystem✅ Protobuf ecosystem
Message SizeEfficientEfficient
Setup ComplexitySimpleModerate
ros-z SupportDefaultRequires feature flag

Common Patterns

Mixed Serialization

Different topics can use different formats:

// CDR for ROS 2 compatibility
let ros_pub = node
    .create_pub::<RosString>("/ros_topic")
    .build()?;  // CDR is default

// Protobuf for schema evolution
let proto_pub = node
    .create_pub::<ProtoString>("/proto_topic")
    .with_serdes::<ProtobufSerdes<ProtoString>>()
    .build()?;

Migration Strategy

Gradual migration from CDR to protobuf:

  1. Add protobuf feature to dependencies
  2. Create protobuf topics with new names
  3. Run both CDR and protobuf publishers temporarily
  4. Migrate subscribers to protobuf
  5. Deprecate CDR topics

Build Integration

Project Structure

my_ros_project/
├── proto/
│   ├── sensor_data.proto
│   └── robot_status.proto
├── src/
│   └── main.rs
├── build.rs
└── Cargo.toml

Cargo.toml

[package]
name = "my_ros_project"
version = "0.1.0"
edition = "2021"

[dependencies]
ros-z = { version = "0.1", features = ["protobuf"] }
ros-z-msgs = { version = "0.1", features = ["geometry_msgs", "protobuf"] }
prost = "0.13"
serde = { version = "1.0", features = ["derive"] }

[build-dependencies]
prost-build = "0.13"

build.rs

use std::io::Result;

fn main() -> Result<()> {
    let mut config = prost_build::Config::new();

    // Enable serde for ros-z compatibility
    config.type_attribute(".", "#[derive(serde::Serialize, serde::Deserialize)]");

    // Compile all proto files
    config.compile_protos(
        &[
            "proto/sensor_data.proto",
            "proto/robot_status.proto",
        ],
        &["proto/"]
    )?;

    // Rebuild if proto files change
    println!("cargo:rerun-if-changed=proto/");

    Ok(())
}

Troubleshooting

Error: protobuf feature not enabled

This error occurs when you try to use protobuf serialization without enabling the feature flag.

Solution:

Enable the protobuf feature in your Cargo.toml:

[dependencies]
ros-z = { version = "0.1", features = ["protobuf"] }
ros-z-msgs = { version = "0.1", features = ["geometry_msgs", "protobuf"] }

Error: MessageTypeInfo not implemented

Custom protobuf messages need to implement required ros-z traits.

Solution:

Implement the required traits for your custom message:

use ros_z::{MessageTypeInfo, WithTypeInfo, entity::TypeHash};

impl MessageTypeInfo for MyMessage {
    fn type_name() -> &'static str {
        "package::msg::dds_::MyMessage_"
    }

    fn type_hash() -> TypeHash {
        TypeHash::zero()
    }
}

impl WithTypeInfo for MyMessage {}

Build fails with prost errors

Version mismatches between prost dependencies can cause build failures.

Solution:

Ensure prost versions match in your Cargo.toml:

[dependencies]
prost = "0.13"

[build-dependencies]
prost-build = "0.13"

If issues persist, try:

cargo clean
cargo build

Messages not receiving

Publisher and subscriber must use the same serialization format.

Solution:

Verify both sides use protobuf serialization:

// Publisher
let pub = node
    .create_pub::<MyMessage>("/topic")
    .with_serdes::<ProtobufSerdes<MyMessage>>()
    .build()?;

// Subscriber
let sub = node
    .create_sub::<MyMessage>("/topic")
    .with_serdes::<ProtobufSerdes<MyMessage>>()
    .build()?;

Note: A protobuf publisher cannot communicate with a CDR subscriber and vice versa.

Proto file not found during build

The build script cannot locate your .proto files.

Solution:

Verify the path in your build.rs:

config.compile_protos(
    &["proto/sensor_data.proto"],  // Check this path
    &["proto/"]                     // Check include directory
)?;

Ensure the proto directory exists:

ls proto/sensor_data.proto

Generated code not found

The build script generated code but you can't import it.

Solution:

Ensure you're including from the correct location:

pub mod sensor_data {
    include!(concat!(env!("OUT_DIR"), "/examples.rs"));
}

The filename after OUT_DIR should match your package name in the .proto file:

package examples;  // Generates examples.rs

Resources

Use protobuf when you need schema evolution or cross-language compatibility beyond the ROS 2 ecosystem. Stick with CDR for standard ROS 2 interoperability.

ros-z-console

ros-z-console is a monitoring tool for ROS 2 systems built on Zenoh. It provides real-time graph inspection, dataflow monitoring, and metrics collection through two interfaces: an interactive TUI (Terminal User Interface) and a headless JSON streaming mode.

Tip

ros-z-console uses zero-interference monitoring via pure Zenoh subscribers - it never pollutes the ROS graph with its own presence.

Network Topology

ros-z-console connects to the ROS 2 graph via a Zenoh router. All ROS 2 nodes using rmw_zenoh_cpp communicate through the same router, enabling ros-z-console to observe the entire system.

graph LR
    subgraph "ROS 2 System"
        T[talker<br/>rmw_zenoh_cpp]
        L[listener<br/>rmw_zenoh_cpp]
    end

    R[Zenoh Router<br/>rmw_zenohd]
    C[ros-z-console]

    T <--> R
    L <--> R
    C --> R

    style C fill:#2ecc71,color:#fff
    style R fill:#3498db,color:#fff

Quick Start: Monitoring demo_nodes_cpp

This example shows ros-z-console monitoring the classic talker/listener demo from demo_nodes_cpp.

Terminal 1 - Start the Zenoh router:

ros2 run rmw_zenoh_cpp rmw_zenohd

Terminal 2 - Start the talker:

export RMW_IMPLEMENTATION=rmw_zenoh_cpp
ros2 run demo_nodes_cpp talker

Terminal 3 - Start the listener:

export RMW_IMPLEMENTATION=rmw_zenoh_cpp
ros2 run demo_nodes_cpp listener

Terminal 4 - Monitor with ros-z-console:

ros-z-console tcp/127.0.0.1:7447 0

Success

You should see the /chatter topic, the talker and listener nodes, and their services appear in ros-z-console. Use the TUI to browse topics, check message rates, and inspect QoS settings.

Building and Running

# Build the console
cargo build -p ros-z-console --release

# Run with default settings (TUI mode)
ros-z-console tcp/127.0.0.1:7447 0

# Headless JSON streaming
ros-z-console --headless --json tcp/127.0.0.1:7447 0

# Echo messages from a topic
ros-z-console --headless --echo /chatter tcp/127.0.0.1:7447 0

# Echo multiple topics with JSON output
ros-z-console --headless --json --echo /chatter --echo /cmd_vel tcp/127.0.0.1:7447 0

# Export graph snapshot and exit
ros-z-console --export graph.json tcp/127.0.0.1:7447 0

Command Line Interface

ros-z-console [OPTIONS] [ROUTER] [DOMAIN]

Arguments

ArgumentDefaultDescription
ROUTERtcp/127.0.0.1:7447Zenoh router address
DOMAIN0ROS domain ID

Options

FlagDescription
--tuiEnable TUI interface (default if no other mode specified)
--headlessHeadless mode: stream events to stdout
--jsonOutput structured JSON logs
--debugEnable debug logging
--echo <TOPIC>Subscribe to and display messages from topic (can be used multiple times)
--export <PATH>Export current state and exit (supports .json, .dot, .csv)

Modes

TUI Mode (Default)

The interactive terminal interface provides:

  • Panel Navigation - Browse Topics, Services, Nodes, and Measurements
  • Filter Mode - Press / to activate type-ahead search with highlighting
  • Rate Monitoring - Quick rate check with r key (cached for 30s)
  • Measurement Panel - Press m for detailed measurements with:
    • Real-time metrics (msg/s, KB/s, average payload)
    • 60-second time-series chart
    • SQLite storage (ros-z-metrics.db)
  • Detail Drilling - Press Enter to expand sections with QoS profiles
  • Export - Press e to export metrics to CSV
  • Help Overlay - Press ? to toggle help

Note

TUI mode requires a terminal that supports ANSI escape codes. Most modern terminals work out of the box.

Headless Mode

Headless mode streams events to stdout, making it ideal for:

  • CI/CD pipelines
  • Log aggregation systems
  • AI-powered analysis
  • Scripted monitoring

Human-readable output:

ros-z-console --headless tcp/127.0.0.1:7447 0
Discovered Topics:
  /chatter (std_msgs/msg/String)
  /cmd_vel (geometry_msgs/msg/Twist)
Discovered Nodes:
  /talker
  /listener
[2026-01-21 10:30:00] Topic discovered: /rosout (rcl_interfaces/msg/Log)

JSON streaming output:

ros-z-console --headless --json tcp/127.0.0.1:7447 0
{"timestamp":"...","event":"initial_state","domain_id":0,"topics":[...],"nodes":[...],"services":[...]}
{"TopicDiscovered":{"topic":"/chatter","type_name":"std_msgs/msg/String","timestamp":"..."}}
{"NodeDiscovered":{"namespace":"/","name":"talker","timestamp":"..."}}

Dynamic Topic Echo

ros-z-console can subscribe to and display messages from any ROS 2 topic without compile-time knowledge of message types. This is powered by dynamic schema discovery using the ROS 2 Type Description service (REP-2016).

Universal Message Support

Echo works with all ROS 2 message types: primitives, nested messages, arrays, and custom types. No recompilation needed!

How It Works

When you echo a topic, ros-z-console:

  1. Discovers publishers on the topic using graph monitoring
  2. Queries the Type Description service from the publisher's node
  3. Retrieves the message schema (field names, types, and layout)
  4. Creates a dynamic subscriber using the discovered schema
  5. Deserializes and displays messages in real-time
sequenceDiagram
    participant C as ros-z-console
    participant G as Graph
    participant P as Publisher Node
    participant Z as Zenoh

    C->>G: Find publishers for /chatter
    G-->>C: Publisher: talker node
    C->>P: GetTypeDescription(std_msgs/msg/String)
    P-->>C: Schema + Type Hash
    C->>Z: Subscribe with dynamic schema
    Z-->>C: Message data (CDR)
    C->>C: Deserialize & display

Basic Usage

Echo a single topic:

ros-z-console --headless --echo /chatter

Output:

=== Subscribed to /chatter ===
Type: std_msgs/msg/String
Hash: RIHS01_df668c740482bbd48fb39d76a70dfd4bd59db1288021743503259e948f6b1a18
Fields: ["data"]

=== /chatter ===
data: "Hello World: 0"

=== /chatter ===
data: "Hello World: 1"

JSON output mode:

ros-z-console --headless --json --echo /chatter
{"event":"topic_subscribed","topic":"/chatter","type_name":"std_msgs/msg/String","type_hash":"RIHS01_df668...","fields":["data"]}
{"event":"message_received","topic":"/chatter","type":"std_msgs/msg/String","data":{"data":"Hello World: 0"}}
{"event":"message_received","topic":"/chatter","type":"std_msgs/msg/String","data":{"data":"Hello World: 1"}}

Multiple Topics

Echo multiple topics simultaneously:

ros-z-console --headless --echo /chatter --echo /cmd_vel --echo /odom

Each topic is independently discovered and subscribed with its own dynamic schema.

Supported Message Types

Primitives

# String messages
ros-z-console --headless --echo /chatter

# Numeric types
ros-z-console --headless --echo /count      # Int32
ros-z-console --headless --echo /sensor     # Float64

Nested Messages

# Twist (linear + angular vectors)
ros-z-console --headless --echo /cmd_vel

Output:

=== /cmd_vel ===
linear:
  x: 1.0
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 0.0
  z: 0.5

Arrays and Sequences

# Point cloud or array messages
ros-z-console --headless --echo /scan

Use Cases

Debugging Message Content

Quickly inspect what's actually being published:

ros-z-console --headless --echo /diagnostics

Data Analysis

Pipe JSON output to analysis tools:

ros-z-console --headless --json --echo /pose | \
  jq -r 'select(.event=="message_received") | .data.position.x'

Recording Specific Fields

Extract and log specific data:

ros-z-console --headless --json --echo /sensor_data | \
  jq '.data.temperature' >> temps.log

Message Validation

Verify message structure and content during development:

# Check if messages match expected schema
ros-z-console --headless --json --echo /my_custom_topic | \
  jq '.data | keys'

Example: Monitoring Robot Telemetry

Monitor multiple robot topics simultaneously:

#!/bin/bash
# Monitor robot state
ros-z-console --headless \
  --echo /cmd_vel \
  --echo /odom \
  --echo /battery_state \
  --echo /diagnostics \
  > robot_state.log

Integration with Standard ROS 2

ros-z-console echo works seamlessly with standard ROS 2 nodes:

# Terminal 1: Standard ROS 2 publisher
ros2 run demo_nodes_cpp talker

# Terminal 2: ros-z-console subscriber
ros-z-console --headless --echo /chatter

Type Hash Matching

ros-z-console uses RIHS01 type hashes to ensure message compatibility. If type hashes don't match, the subscription will fail with a clear error message.

Advanced Options

With Debug Logging

Enable detailed logging to troubleshoot discovery issues:

RUST_LOG=ros_z=debug ros-z-console --headless --echo /chatter

Debug output shows:

  • Publisher discovery attempts
  • Type description service queries
  • Schema parsing details
  • Type hash validation

Custom Timeout

If schema discovery is slow, you can adjust timeouts in the code (default: 5 seconds).

Troubleshooting

No publishers found:

Failed to subscribe to /my_topic: Schema discovery failed: No publishers found for topic: /my_topic

Solutions:

  • Verify the topic exists: ros2 topic list
  • Check the topic is being published: ros2 topic hz /my_topic
  • Ensure rmw_zenohd is running
  • Wait for publisher to fully start (may take a few seconds)

Type hash mismatch:

Failed to subscribe to /chatter: Type hash mismatch

This occurs when the publisher and subscriber have different message definitions. Ensure both are using the same ROS 2 distribution and package versions.

Comparison with ros2 topic echo

Featureros-z-consoleros2 topic echo
CompilationNo recompilation neededRequires message packages installed
Custom typesAutomatic discoveryMust have .msg files available
Multiple topicsSingle commandNeed multiple processes
JSON outputBuilt-in structured formatRequires additional parsing
PerformanceZenoh pub/sub (very fast)DDS overhead
FilteringEasy with jq on JSONManual parsing needed

Performance Notes

  • Latency: Sub-millisecond after initial discovery (~5 seconds)
  • Throughput: Handles 1000+ messages/second per topic
  • Memory: ~1KB per unique message schema (cached globally)
  • CPU: Minimal - only active when messages arrive

Schema Caching

Message schemas are cached in a global registry. Once a type is discovered, subsequent subscriptions to topics with the same type are instant.

Export Formats

Export the current graph state with the --export flag:

JSON Export

ros-z-console --export graph.json tcp/127.0.0.1:7447 0

Produces a structured JSON file with topics, nodes, services, and their relationships:

{
  "timestamp": "2026-01-21T10:30:00Z",
  "domain_id": 0,
  "topics": [
    {"name": "/chatter", "type": "std_msgs/msg/String", "publishers": 1, "subscribers": 1}
  ],
  "nodes": [
    {"name": "talker", "namespace": "/"}
  ],
  "services": []
}

GraphViz DOT Export

ros-z-console --export graph.dot tcp/127.0.0.1:7447 0
dot -Tpng graph.dot -o graph.png

Generates a visual graph representation with:

  • Nodes as blue boxes
  • Topics as green ellipses
  • Publisher edges in blue
  • Subscriber edges in green

CSV Export

ros-z-console --export metrics.csv tcp/127.0.0.1:7447 0

Exports collected metrics history:

timestamp,topic,rate_hz,bandwidth_kbps,avg_payload_bytes
2026-01-21T10:30:00Z,/chatter,10.5,2.3,220

Event Types

ros-z-console tracks these system events:

EventDescription
TopicDiscoveredNew topic detected in the graph
TopicRemovedTopic no longer present
NodeDiscoveredNew node joined the graph
NodeRemovedNode left the graph
ServiceDiscoveredNew service available
RateMeasuredRate measurement completed
MetricsSnapshotPeriodic summary of graph state

Configuration

Create a ros-z-console.json or .ros-z-console.json file:

{
  "cache_ttl_seconds": 30,
  "rate_cache_ttl_seconds": 30,
  "graph_cache_update_ms": 100
}
OptionDefaultDescription
cache_ttl_seconds30General cache time-to-live
rate_cache_ttl_seconds30How long rate measurements are cached
graph_cache_update_ms100Graph refresh interval in milliseconds

Integration Examples

Pipe to jq for filtering

# Filter for topic discovery events
ros-z-console --headless --json | jq 'select(.TopicDiscovered != null)'

# Extract specific message fields
ros-z-console --headless --json --echo /pose | \
  jq -r 'select(.event=="message_received") | .data.position'

Monitor specific topics

# Watch for messages on specific topic
ros-z-console --headless --json | grep -E '"topic":"/cmd_vel"'

# Echo and filter by field value
ros-z-console --headless --json --echo /sensor | \
  jq 'select(.data.temperature > 50)'

Continuous logging

# Log all graph events
ros-z-console --headless --json >> ros-events.jsonl &

# Log all messages from a topic
ros-z-console --headless --json --echo /diagnostics >> diagnostics.jsonl &

Real-time data extraction

# Extract velocity commands
ros-z-console --headless --json --echo /cmd_vel | \
  jq -r '.data.linear.x' | \
  tee -a velocity.log

# Monitor temperature sensor
ros-z-console --headless --json --echo /temperature | \
  jq -r '[.timestamp, .data.value] | @csv' >> temp.csv

Database analysis

# After running TUI mode with measurements
sqlite3 ros-z-metrics.db "SELECT topic, AVG(msgs_sec) FROM metrics GROUP BY topic"

Interoperability

Both ros-z and rmw_zenoh_cpp use the same Zenoh-based discovery protocol. ros-z-console subscribes to the graph liveliness tokens that rmw_zenoh_cpp nodes publish, enabling seamless interoperability without any configuration changes.

Shared Memory (SHM)

Shared Memory (SHM) enables zero-copy publishing of large messages by serializing directly into shared memory buffers, eliminating the need to copy data between processes.

Overview

When publishing large messages (e.g., point clouds, images), copying data multiple times can significantly impact performance. ROS-Z's SHM support leverages Zenoh's shared memory capabilities to achieve true zero-copy publishing.

Key Benefits

  • Zero-copy serialization: Messages are serialized directly into shared memory
  • Automatic activation: Configurable threshold-based switching
  • Accurate buffer sizing: Auto-generated size estimation prevents waste
  • High performance: Sub-millisecond serialization for 1MB messages
  • Full compatibility: Works seamlessly with rmw_zenoh_cpp

How SHM Works in ROS 2

The following diagram illustrates how a PointCloud2 message is published using shared memory in ROS-Z:

sequenceDiagram
    participant App as Application
    participant Pub as ROS-Z Publisher
    participant SHM as SHM Provider
    participant Zenoh as Zenoh Network
    participant Sub as ROS-Z Subscriber
    participant RemoteApp as Remote Application

    Note over App,RemoteApp: Publishing Large PointCloud2 (1MB)

    App->>App: Generate PointCloud2 data
    App->>SHM: Allocate SHM buffer (1MB)
    SHM-->>App: SHM buffer reference

    App->>App: Write point data directly to SHM
    Note over App: Zero-copy: data stays in SHM

    App->>Pub: publish(pointcloud2)
    Pub->>Pub: Estimate serialized size
    Pub->>SHM: Allocate buffer for metadata
    Pub->>Pub: Serialize header + metadata to SHM
    Note over Pub: Data field already in SHM!

    Pub->>Zenoh: Publish SHM-backed ZBuf
    Note over Zenoh: Network transfer (zero-copy)

    Zenoh->>Sub: Receive SHM reference
    Sub->>Sub: Deserialize metadata
    Sub->>RemoteApp: PointCloud2 with SHM data

    Note over RemoteApp: Direct access to SHM data
    RemoteApp->>RemoteApp: Process points (zero-copy read)

Key Points:

  • Point data is written once directly into shared memory
  • No intermediate copies between publisher and subscriber
  • Both processes access the same physical memory
  • Network only transfers SHM references, not actual data (on same machine)
  • Automatic fallback to regular serialization for remote nodes

Quick Start

Default Behavior: SHM is OFF

By default, SHM is disabled. Messages are serialized using regular memory allocation. You must explicitly enable SHM to use zero-copy publishing.

Enable SHM Globally

The simplest way to enable SHM is at the context level:

use ros_z::context::ZContextBuilder;
use ros_z::Builder;
use ros_z_msgs::sensor_msgs::PointCloud2;

fn main() -> zenoh::Result<()> {
    let ctx = ZContextBuilder::default()
        .with_shm_enabled()?  // Enable with defaults: 10MB pool, 512B threshold
        .build()?;

    // All publishers automatically use SHM for messages >= 512 bytes
    let node = ctx.create_node("my_node").build()?;
    let publisher = node.create_pub::<PointCloud2>("cloud").build()?;

    // Zero-copy publishing for large messages!
    let large_pointcloud = PointCloud2::default();
    publisher.publish(&large_pointcloud)?;
    Ok(())
}

Custom Configuration

Adjust pool size and threshold based on your needs:

use ros_z::context::ZContextBuilder;
use ros_z::Builder;

fn main() -> zenoh::Result<()> {
    let ctx = ZContextBuilder::default()
        .with_shm_pool_size(100 * 1024 * 1024)?  // 100MB pool
        .with_shm_threshold(50_000)?              // 50KB threshold
        .build()?;
    Ok(())
}

Per-Publisher Control

Override SHM settings for specific publishers:

use ros_z::context::ZContextBuilder;
use ros_z::shm::{ShmConfig, ShmProviderBuilder};
use ros_z::Builder;
use ros_z_msgs::sensor_msgs::PointCloud2;
use std::sync::Arc;

fn main() -> zenoh::Result<()> {
    let ctx = ZContextBuilder::default().build()?;
    let node = ctx.create_node("test").build()?;
    let provider = Arc::new(ShmProviderBuilder::new(10_000_000).build()?);
    let custom_config = ShmConfig::new(provider);

    // Custom configuration for this publisher
    let publisher = node.create_pub::<PointCloud2>("cloud")
        .with_shm_config(custom_config)
        .build()?;

    // Explicitly disable SHM (even if context has it enabled)
    let text_pub = node.create_pub::<ros_z_msgs::std_msgs::String>("text")
        .without_shm()
        .build()?;
    Ok(())
}

Toggle SHM On/Off

ActionMethod
Enable (default config).with_shm_enabled()
Enable (custom pool).with_shm_pool_size(bytes)
Adjust threshold.with_shm_threshold(bytes)
Disable (default)Don't call any SHM methods
Disable per-publisher.without_shm()

Configuration

Default: SHM Disabled

SHM is disabled by default. To enable it, you must explicitly configure it at the context, node, or publisher level.

Hierarchical Configuration

SHM configuration follows a three-level hierarchy:

  1. Context level: Default for all nodes/publishers
  2. Node level: Override for node's publishers (inherits from context if not set)
  3. Publisher level: Most specific override (can disable even if context has SHM)
use ros_z::context::ZContextBuilder;
use ros_z::shm::{ShmConfig, ShmProviderBuilder};
use ros_z::Builder;
use ros_z_msgs::sensor_msgs::{Image, PointCloud2};
use std::sync::Arc;

fn main() -> zenoh::Result<()> {
    // Context: 10MB pool, 512B threshold
    let ctx = ZContextBuilder::default()
        .with_shm_enabled()?
        .build()?;

    // Node: inherit from context
    let node = ctx.create_node("my_node").build()?;

    // Publisher 1: use context defaults
    let pub1 = node.create_pub::<Image>("camera/image").build()?;

    // Publisher 2: custom threshold
    let provider = Arc::new(ShmProviderBuilder::new(10 * 1024 * 1024).build()?);
    let config = ShmConfig::new(provider).with_threshold(100_000);
    let pub2 = node.create_pub::<PointCloud2>("lidar/cloud")
        .with_shm_config(config)
        .build()?;

    // Publisher 3: disable SHM
    let pub3 = node.create_pub::<ros_z_msgs::std_msgs::String>("status")
        .without_shm()
        .build()?;
    Ok(())
}

Environment Variables

For compatibility with rmw_zenoh_cpp, you can enable and configure SHM via environment variables:

export ZENOH_SHM_ALLOC_SIZE=52428800        # Enable SHM with 50MB pool
export ZENOH_SHM_MESSAGE_SIZE_THRESHOLD=10000  # Set 10KB threshold

Note: Setting either environment variable will enable SHM. If only one is set, the other uses the default value (10MB pool or 512B threshold).

To use environment variables in your code:

use ros_z::shm::ShmConfig;
use ros_z::context::ZContextBuilder;
use ros_z::Builder;

fn main() -> zenoh::Result<()> {
    let ctx = if let Some(shm_config) = ShmConfig::from_env()? {
        // SHM configured from environment variables
        ZContextBuilder::default()
            .with_shm_config(shm_config)
            .build()?
    } else {
        // No SHM (default)
        ZContextBuilder::default().build()?
    };
    Ok(())
}

Configuration Defaults (When Enabled)

When you enable SHM using .with_shm_enabled() or .with_shm_pool_size(), the following defaults apply:

ParameterDefaultDescription
SHM StateDisabledSHM must be explicitly enabled
Pool Size10 MBTotal SHM pool size (when enabled)
Threshold512 bytesMin message size for SHM usage
PolicyBlockOn<GarbageCollect>Wait for GC if pool exhausted

How It Works

Architecture

Message with dynamic fields
    ↓
estimated_serialized_size() [auto-generated by codegen]
    ↓
Pre-allocate SHM buffer (exact size)
    ↓
Serialize directly to SHM (zero-copy!)
    ↓
ZBuf (SHM-backed)
    ↓
Zenoh publish

Size Estimation

ROS-Z automatically generates accurate size estimation for all message types during code generation:

// Auto-generated implementation for PointCloud2
impl SizeEstimation for PointCloud2 {
    fn estimated_serialized_size(&self) -> usize {
        4 + // encapsulation header
        self.header.estimated_cdr_size() +
        4 + // height
        4 + // width
        4 + self.fields.iter().map(|f| f.estimated_cdr_size()).sum::<usize>() +
        1 + // is_bigendian
        4 + // point_step
        4 + // row_step
        4 + self.data.len() +  // data buffer
        1   // is_dense
    }
}

This ensures:

  • No buffer overflows
  • Minimal memory waste (<1% over-allocation)
  • Single allocation per message

Complete Example

The following complete example demonstrates three patterns for using SHM with PointCloud2 messages. This code is from ros-z/examples/shm_pointcloud2.rs:

//! PointCloud2 example demonstrating user-managed SHM for zero-copy point clouds.
//!
//! This example shows how to create large sensor messages with data stored directly
//! in shared memory, avoiding any intermediate copies.
//!
//! # Three SHM Patterns Demonstrated:
//!
//! 1. **User-Managed SHM** (Primary): Allocate SHM buffer, write points, create message
//! 2. **Automatic SHM** (Context-level): Enable SHM globally, automatic threshold-based usage
//! 3. **Per-Publisher SHM**: Override SHM config for specific publisher
//!
//! # Usage:
//! ```bash
//! cargo run --example shm_pointcloud2
//! ```

use std::{sync::Arc, time::Instant};

use ros_z::{
    Builder,
    context::ZContextBuilder,
    shm::{ShmConfig, ShmProviderBuilder},
};
use ros_z_msgs::{
    sensor_msgs::{PointCloud2, PointField},
    std_msgs::Header,
};
use zenoh::{
    Wait,
    shm::{BlockOn, GarbageCollect, ShmProvider},
};
use zenoh_buffers::{ZBuf, buffer::Buffer};

fn main() -> zenoh::Result<()> {
    println!("=== PointCloud2 with SHM Example ===\n");

    // Pattern 1: User-managed SHM (maximum performance, full control)
    println!("1. User-Managed SHM Pattern:");
    demo_user_managed_shm()?;

    println!("\n2. Automatic SHM Pattern (Context-level):");
    demo_automatic_shm()?;

    println!("\n3. Per-Publisher SHM Override:");
    demo_publisher_shm_override()?;

    println!("\n=== All patterns completed successfully ===");
    Ok(())
}

/// Pattern 1: User creates SHM buffer, writes points, constructs PointCloud2
fn demo_user_managed_shm() -> zenoh::Result<()> {
    // Step 1: Initialize SHM provider
    let provider = ShmProviderBuilder::new(50 * 1024 * 1024).build()?;
    println!("  ✓ Created SHM provider with 50MB pool");

    // Step 2: Generate point cloud with SHM-backed data
    let start = Instant::now();
    let cloud = generate_pointcloud_with_shm(100_000, &provider)?;
    let gen_time = start.elapsed();

    println!(
        "  ✓ Generated 100k point cloud ({} KB) in {:?}",
        cloud.data.len() / 1024,
        gen_time
    );
    println!("    Points stored directly in SHM (zero-copy!)");

    // Step 3: Create node and publisher
    let ctx = ZContextBuilder::default().build()?;
    let node = ctx.create_node("pointcloud_publisher").build()?;
    let publisher = node
        .create_pub::<PointCloud2>("cloud/user_managed")
        .build()?;

    // Step 4: Publish (data field is already in SHM)
    let start = Instant::now();
    publisher.publish(&cloud)?;
    let pub_time = start.elapsed();

    println!(
        "  ✓ Published in {:?} (data already in SHM, only metadata serialized)",
        pub_time
    );

    Ok(())
}

/// Pattern 2: Enable SHM at context level, automatic for large messages
fn demo_automatic_shm() -> zenoh::Result<()> {
    // Enable SHM globally
    let ctx = ZContextBuilder::default()
        .with_shm_pool_size(50 * 1024 * 1024)?
        .with_shm_threshold(10_000) // 10KB threshold
        .build()?;
    println!("  ✓ Context configured with automatic SHM (threshold: 10KB)");

    let node = ctx.create_node("pointcloud_publisher").build()?;
    let publisher = node.create_pub::<PointCloud2>("cloud/automatic").build()?;

    // Generate point cloud normally (using Vec<u8>)
    let start = Instant::now();
    let cloud = generate_pointcloud_normal(50_000);
    let gen_time = start.elapsed();

    println!(
        "  ✓ Generated 50k point cloud ({} KB) in {:?}",
        cloud.data.len() / 1024,
        gen_time
    );

    // Publish - automatically uses SHM because message > threshold
    let start = Instant::now();
    publisher.publish(&cloud)?;
    let pub_time = start.elapsed();

    println!(
        "  ✓ Published in {:?} (serialized ~600KB > 10KB, automatically used SHM)",
        pub_time
    );

    Ok(())
}

/// Pattern 3: Per-publisher SHM configuration
fn demo_publisher_shm_override() -> zenoh::Result<()> {
    // Context has no SHM, but publisher has its own config
    let ctx = ZContextBuilder::default().build()?;
    let node = ctx.create_node("pointcloud_publisher").build()?;

    // Create SHM provider for this publisher only
    let provider = Arc::new(ShmProviderBuilder::new(30 * 1024 * 1024).build()?);
    let shm_config = ShmConfig::new(provider).with_threshold(5_000); // 5KB threshold

    let publisher = node
        .create_pub::<PointCloud2>("cloud/per_publisher")
        .with_shm_config(shm_config)
        .build()?;

    println!("  ✓ Publisher configured with custom SHM (threshold: 5KB)");

    let cloud = generate_pointcloud_normal(30_000);
    println!(
        "  ✓ Generated 30k point cloud ({} KB)",
        cloud.data.len() / 1024
    );

    let start = Instant::now();
    publisher.publish(&cloud)?;
    let pub_time = start.elapsed();

    println!(
        "  ✓ Published in {:?} (used publisher's SHM config)",
        pub_time
    );

    Ok(())
}

/// Generate point cloud with user-managed SHM (Pattern 1: zero-copy)
fn generate_pointcloud_with_shm(
    num_points: usize,
    provider: &ShmProvider<zenoh::shm::PosixShmProviderBackend>,
) -> zenoh::Result<PointCloud2> {
    let point_step = 12; // x, y, z as f32 (4 bytes each)
    let data_size = num_points * point_step;

    // Allocate SHM buffer for point data
    let mut shm_buf = provider
        .alloc(data_size)
        .with_policy::<BlockOn<GarbageCollect>>()
        .wait()?;

    // Write point coordinates directly into SHM buffer
    for i in 0..num_points {
        let offset = i * point_step;
        let angle = (i as f32) * 0.01;
        let radius = 5.0 + (angle * 0.1).sin();

        // Calculate x, y, z
        let x = radius * angle.cos();
        let y = radius * angle.sin();
        let z = (i as f32) * 0.001;

        // Write directly to SHM (no intermediate Vec<u8>)
        shm_buf[offset..offset + 4].copy_from_slice(&x.to_le_bytes());
        shm_buf[offset + 4..offset + 8].copy_from_slice(&y.to_le_bytes());
        shm_buf[offset + 8..offset + 12].copy_from_slice(&z.to_le_bytes());
    }

    // Create ZBuf from SHM buffer (zero-copy conversion!)
    let data_zbuf = ZBuf::from(shm_buf);

    // Construct PointCloud2 with SHM-backed ZBuf
    Ok(PointCloud2 {
        header: Header {
            frame_id: "map".into(),
            ..Default::default()
        },
        height: 1,
        width: num_points as u32,
        fields: vec![
            PointField {
                name: "x".into(),
                offset: 0,
                datatype: 7, // FLOAT32
                count: 1,
            },
            PointField {
                name: "y".into(),
                offset: 4,
                datatype: 7,
                count: 1,
            },
            PointField {
                name: "z".into(),
                offset: 8,
                datatype: 7,
                count: 1,
            },
        ],
        is_bigendian: false,
        point_step: point_step as u32,
        row_step: (num_points * point_step) as u32,
        data: data_zbuf, // SHM-backed data!
        is_dense: true,
    })
}

/// Generate point cloud normally (Pattern 2 & 3: uses Vec<u8>, then automatic SHM)
fn generate_pointcloud_normal(num_points: usize) -> PointCloud2 {
    let point_step = 12;
    let mut data = Vec::with_capacity(num_points * point_step);

    for i in 0..num_points {
        let angle = (i as f32) * 0.01;
        let radius = 5.0 + (angle * 0.1).sin();

        let x = radius * angle.cos();
        let y = radius * angle.sin();
        let z = (i as f32) * 0.001;

        data.extend_from_slice(&x.to_le_bytes());
        data.extend_from_slice(&y.to_le_bytes());
        data.extend_from_slice(&z.to_le_bytes());
    }

    PointCloud2 {
        header: Header {
            frame_id: "map".into(),
            ..Default::default()
        },
        height: 1,
        width: num_points as u32,
        fields: vec![
            PointField {
                name: "x".into(),
                offset: 0,
                datatype: 7,
                count: 1,
            },
            PointField {
                name: "y".into(),
                offset: 4,
                datatype: 7,
                count: 1,
            },
            PointField {
                name: "z".into(),
                offset: 8,
                datatype: 7,
                count: 1,
            },
        ],
        is_bigendian: false,
        point_step: point_step as u32,
        row_step: (num_points * point_step) as u32,
        data: ZBuf::from(data),
        is_dense: true,
    }
}

Run the example:

cargo run --example shm_pointcloud2

Expected Output:

=== PointCloud2 with SHM Example ===

1. User-Managed SHM Pattern:
  ✓ Created SHM provider with 50MB pool
  ✓ Generated 100k point cloud (1171 KB) in 22ms
    Points stored directly in SHM (zero-copy!)
  ✓ Published in 851µs (data already in SHM, only metadata serialized)

2. Automatic SHM Pattern (Context-level):
  ✓ Context configured with automatic SHM (threshold: 10KB)
  ✓ Generated 50k point cloud (585 KB) in 11ms
  ✓ Published in 450µs (serialized ~600KB > 10KB, automatically used SHM)

3. Per-Publisher SHM Override:
  ✓ Publisher configured with custom SHM (threshold: 5KB)
  ✓ Generated 30k point cloud (351 KB)
  ✓ Published in 320µs (used publisher's SHM config)

=== All patterns completed successfully ===

Testing

Run SHM Tests

# SHM integration tests
cargo test -p ros-z --lib shm
cargo test -p ros-z --test shm

# Size estimation tests
cargo test -p ros-z-msgs --test shm_size_estimation

# Performance tests
cargo test -p ros-z-msgs --test size_estimation_performance

Test Coverage

  • 16 total tests covering:
    • SHM allocation and serialization
    • Size estimation accuracy
    • Performance benchmarks
    • Multi-message scenarios
    • Error handling

Troubleshooting

Buffer Overflow Panic

Symptom: SHM buffer overflow panic during serialization

Cause: Message's estimated_serialized_size() is inaccurate

Solution: This should not occur with auto-generated implementations. If it does, please report as a bug with the specific message type and data.

SHM Allocation Fails

Symptom: Falls back to regular memory allocation

Possible Causes:

  1. SHM pool exhausted
  2. System SHM limits reached
  3. Message below threshold

Solutions:

# Check pool usage
ipcs -m

# Increase pool size
let ctx = ZContextBuilder::default()
    .with_shm_pool_size(100 * 1024 * 1024)?
    .build()?;

# Lower threshold
let ctx = ZContextBuilder::default()
    .with_shm_threshold(256)?
    .build()?;

Poor Performance

Symptom: Serialization slower than expected

Diagnosis:

// Check if message uses SHM
println!("Message size: {}", msg.estimated_serialized_size());
println!("SHM threshold: {}", ctx.shm_threshold());

Solutions:

  • Ensure message size exceeds threshold
  • Verify SHM is enabled
  • Check for buffer reallocations (use performance tests)

System SHM Limits

On Linux, check and adjust system limits:

# Current limits
cat /proc/sys/kernel/shmmax  # Max segment size
cat /proc/sys/kernel/shmall  # Total pages

# Increase limits (requires root)
sudo sysctl -w kernel.shmmax=134217728   # 128MB
sudo sysctl -w kernel.shmall=32768       # 128MB in pages

Best Practices

When to Use SHM

Good candidates for SHM:

  • Point clouds (sensor_msgs/PointCloud2)
  • Camera images (sensor_msgs/Image)
  • Large arrays (std_msgs/ByteMultiArray)
  • Laser scans (sensor_msgs/LaserScan)

Not beneficial for SHM:

  • Small messages (<512 bytes)
  • High-frequency, small updates
  • Messages with mostly fixed-size fields

Configuration Guidelines

  1. Start with defaults: 10MB pool, 512B threshold work well for most applications
  2. Adjust pool size: Based on maximum concurrent large messages
  3. Tune threshold: Balance between SHM overhead and copy cost
  4. Monitor usage: Use ipcs -m to check pool utilization

Performance Tips

  1. Pre-calculate sizes: Use estimated_serialized_size() to validate messages
  2. Reuse publishers: Creating publishers is expensive; reuse them
  3. Batch small messages: Don't use SHM for messages below threshold
  4. Profile first: Measure before optimizing SHM configuration

Advanced Topics

Custom Size Estimation

For custom message types, implement SizeEstimation:

use ros_z_msgs::size_estimation::SizeEstimation;

impl SizeEstimation for MyCustomMessage {
    fn estimated_serialized_size(&self) -> usize {
        4 + // encapsulation header
        self.field1.estimated_cdr_size() +
        self.field2.estimated_cdr_size() +
        4 + self.dynamic_array.len() * std::mem::size_of::<ElementType>()
    }
}

Allocation Policies

Zenoh SHM supports different allocation policies:

use zenoh::shm::{BlockOn, GarbageCollect};

// Block until memory available (default)
let policy = BlockOn::<GarbageCollect>;

// Fail immediately if pool full
// (use different policy with provider.alloc().with_policy())

Integration with rmw_zenoh_cpp

ROS-Z's SHM implementation is fully compatible with rmw_zenoh_cpp. Messages published from ROS-Z using SHM can be received zero-copy by C++/Python nodes using rmw_zenoh_cpp, and vice versa.

# ROS-Z publisher (Rust)
cargo run --example shm_pointcloud2

# Standard ROS 2 subscriber (C++ with rmw_zenoh_cpp)
ros2 run my_package cloud_subscriber

Implementation Details

For detailed implementation information, see the branch documentation:

  • Branch: dev/shm
  • Documentation: .claude/ros-z/branches/shm/CLAUDE.md
  • Status: Production ready

Key files:

  • ros-z/src/shm.rs - Core SHM module
  • ros-z/src/msg.rs - Serialization with size estimation
  • ros-z-codegen/src/generator/rust.rs - Size estimation codegen
  • ros-z-msgs/src/size_estimation.rs - Trait definition

Key Expression Formats

ros-z uses key expression formats to map ROS 2 entities (topics, services, actions) to Zenoh key expressions. The format is provided by the independent ros-z-protocol crate and determines how ROS 2 names are translated for Zenoh routing and discovery.

Note

Key expression format is a runtime choice that affects how ros-z maps ROS 2 entities to Zenoh key expressions. Choose the format that matches your infrastructure for proper message routing.

Available Formats

ros-z supports multiple key expression formats for interoperability with different Zenoh-ROS bridges:

FormatCompatibilityUse Case
RmwZenoh (default)rmw_zenoh_cppStandard ROS 2 Zenoh middleware
Ros2Ddszenoh-bridge-ros2ddsDDS bridge compatibility

RmwZenoh Format (Default)

The RmwZenoh format is designed for compatibility with ROS 2's official Zenoh middleware implementation (rmw_zenoh_cpp).

Key Expression Patterns:

Topic keys:      <domain_id>/<topic>/<type>/<hash>
Liveliness:      @ros2_lv/<domain_id>/<entity_kind>/<namespace>/<name>/...

Example Topic Keys:

0/chatter/std_msgs::msg::dds_::String_/RIHS01_...
5/robot/sensors/camera/sensor_msgs::msg::dds_::Image_/RIHS01_...

Use this format when:

  • Using rmw_zenoh_cpp as your ROS 2 middleware
  • Running pure ros-z deployments
  • Requiring domain isolation via Zenoh

Ros2Dds Format

The Ros2Dds format is designed for compatibility with zenoh-bridge-ros2dds, which bridges standard DDS-based ROS 2 nodes to Zenoh.

Key Expression Format:

<topic>/**

Example:

chatter/**                    # Topic /chatter (no domain prefix)
robot/sensors/camera/**       # Topic /robot/sensors/camera

Use this format when:

  • Bridging existing DDS-based ROS 2 systems to Zenoh
  • Using zenoh-bridge-ros2dds
  • Integrating with CycloneDDS or FastDDS nodes via Zenoh

Key Expression Behavior (IMPORTANT)

Understanding how topic names are converted to key expressions is critical for debugging:

Topic Key Expressions (For Data Routing)

ALL entity types (publishers, subscriptions, services, clients, actions) use strip_slashes() behavior:

  • Removes leading and trailing slashes only
  • Preserves internal slashes for hierarchical routing
  • Enables multi-segment topic names

Examples:

ROS 2 Topic NameTopic Key Expression✓/✗
/chatter0/chatter/...✅ Correct
/robot/sensors0/robot/sensors/...✅ Correct
/a/b/c0/a/b/c/...✅ Correct
/talker/service0/talker/service/...✅ Correct

Why preserve slashes?

  • Zenoh uses / for hierarchical routing
  • Enables wildcard subscriptions: 0/robot/**
  • Human-readable key expressions

Liveliness Tokens (For Discovery)

ALL fields in liveliness tokens use mangle_name() behavior:

  • Replaces all / with %
  • Ensures unambiguous parsing of entity metadata
  • Machine-parsable format for discovery protocol

Examples:

ROS 2 NameLiveliness Field✓/✗
/chatter%chatter✅ Correct
/robot/sensors%robot%sensors✅ Correct
/my_node%my_node✅ Correct

Why mangle slashes?

  • Liveliness tokens have fixed structure: @ros2_lv/<domain>/<kind>/<ns>/<name>/...
  • Prevents ambiguity when parsing fields
  • Ensures reliable entity discovery

Why Two Different Behaviors?

This is intentional design in rmw_zenoh_cpp, not an inconsistency:

  • Topic keys: Human-readable, hierarchical (optimized for Zenoh routing)
  • Liveliness: Machine-parsable, unambiguous (optimized for discovery protocol)

Tip

If multi-segment topics like /robot/sensors/camera don't receive messages, check your ros-z version. Versions before 0.1.0 had a bug where publishers incorrectly mangled topic key expressions.

API Usage

Specifying Format at Context Creation

use ros_z::context::ZContextBuilder;
use ros_z_protocol::KeyExprFormat;

// Default (RmwZenoh)
let ctx = ZContextBuilder::default().build()?;

// Explicit format selection
let ctx = ZContextBuilder::default()
    .keyexpr_format(KeyExprFormat::RmwZenoh)
    .build()?;

// Ros2Dds format for DDS bridge compatibility
let ctx = ZContextBuilder::default()
    .keyexpr_format(KeyExprFormat::Ros2Dds)
    .build()?;

Key points:

  • Format is set at context creation time
  • All nodes and entities created from the context use the same format
  • Default format is KeyExprFormat::RmwZenoh
  • Format choice is type-safe and explicit

Creating Entities

Once the context is created with a format, all entities inherit it:

use ros_z_msgs::std_msgs::String as RosString;
use ros_z::Builder;

// Create context with RmwZenoh format (default)
let ctx = ZContextBuilder::default().build()?;
let node = ctx.create_node("my_node").build()?;

// Publisher uses context's format
let pub_rmw = node
    .create_pub::<RosString>("chatter")
    .build()?;

// Subscriber uses same format
let sub_rmw = node
    .create_sub::<RosString>("chatter")
    .build()?;

Mixing Formats (Advanced)

To communicate with both RmwZenoh and Ros2Dds systems, create separate contexts:

// Context for rmw_zenoh_cpp nodes
let ctx_rmw = ZContextBuilder::default()
    .keyexpr_format(KeyExprFormat::RmwZenoh)
    .build()?;

// Context for zenoh-bridge-ros2dds nodes
let ctx_dds = ZContextBuilder::default()
    .keyexpr_format(KeyExprFormat::Ros2Dds)
    .build()?;

// Create nodes from each context
let node_rmw = ctx_rmw.create_node("rmw_node").build()?;
let node_dds = ctx_dds.create_node("dds_node").build()?;

Architecture Diagrams

RmwZenoh Format Architecture

graph LR
    A[ros-z Node<br/>RmwZenoh Format] -->|"0/chatter/**"| B[Zenoh Router<br/>rmw_zenoh]
    B -->|"0/chatter/**"| C[ROS 2 Node<br/>rmw_zenoh_cpp]

Use case: Native Zenoh-based ROS 2 deployment

  • All nodes use rmw_zenoh or ros-z
  • Direct Zenoh communication
  • Domain isolation via key expression prefix

Ros2Dds Format Architecture

graph LR
    A[ros-z Node<br/>Ros2Dds Format] -->|"chatter/**"| B[zenoh-bridge-ros2dds<br/>Router + Bridge]
    B -->|DDS| C[ROS 2 Node<br/>CycloneDDS/FastDDS]

Use case: Bridge existing DDS systems to Zenoh

  • ROS 2 nodes use standard DDS middleware
  • zenoh-bridge-ros2dds translates DDS ↔ Zenoh
  • ros-z communicates via Zenoh side of bridge

Key Expression Generation Details

Understanding how ros-z-protocol generates key expressions helps with debugging and monitoring.

Topic Key Expression Structure

<domain_id>/<topic_stripped>/<type>/<hash>

Components:

  1. Domain ID: ROS 2 domain (e.g., 0, 5)
  2. Topic (stripped): Topic name with leading/trailing slashes removed, internal slashes preserved
  3. Type: Mangled message type (e.g., std_msgs::msg::dds_::String_)
  4. Hash: Type hash for compatibility (e.g., RIHS01_...)

Example:

Topic: /robot/sensors/camera
Type:  sensor_msgs/msg/Image
Hash:  RIHS01_abc123...

Key Expression:
0/robot/sensors/camera/sensor_msgs::msg::dds_::Image_/RIHS01_abc123...

Liveliness Token Structure

@ros2_lv/<domain>/<entity_kind>/<zid>/<id>/<namespace>/<name>/<type>/<hash>/<qos>

All name fields are mangled (/ → %):

Namespace: /robot/arm  →  %robot%arm
Name:      /gripper    →  %gripper

Example:

@ros2_lv/0/MP/01234567890abcdef/1/%robot%arm/%gripper/std_msgs::msg::String_/RIHS01_.../qos_string

ros-z-protocol Crate

The key expression logic is provided by the independent ros-z-protocol crate:

Features:

  • no_std compatible (with alloc)
  • Language-agnostic protocol layer (FFI-ready)
  • Feature-gated format implementations
  • Comprehensive unit tests
  • Type-safe API

Cargo features:

[dependencies]
ros-z-protocol = { version = "0.1", features = ["rmw-zenoh", "ros2dds"] }

Using ros-z-protocol directly:

use ros_z_protocol::{KeyExprFormat, entity::*};

let format = KeyExprFormat::default(); // RmwZenoh

// Generate topic key expression
let topic_ke = format.topic_key_expr(&entity)?;

// Generate liveliness token
let lv_ke = format.liveliness_key_expr(&entity, &zid)?;

// Parse liveliness token back to entity
let parsed_entity = format.parse_liveliness(&lv_ke)?;

See the ros-z-protocol documentation for details.

Troubleshooting

Multi-Segment Topics Not Working?

Symptom: Publisher publishes to /robot/sensors/camera but subscriber never receives messages.

Cause: Old versions of ros-z (before 0.1.0) incorrectly mangled slashes in topic key expressions.

Fix: Update to ros-z 0.1.0+ which correctly uses strip_slashes() for all topic key expressions.

Verify: Enable debug logging to check key expressions:

RUST_LOG=ros_z=debug cargo run --example z_pubsub

Look for key expressions like:

✅ Correct:  0/robot/sensors/camera/sensor_msgs::msg::Image_/...
❌ Wrong:    0/robot%sensors%camera/sensor_msgs::msg::Image_/...

No Messages Between ros-z and rmw_zenoh_cpp?

Check format: Ensure ros-z uses KeyExprFormat::RmwZenoh (the default).

Check type hash: Enable debug logging and compare type hashes:

RUST_LOG=ros_z=debug cargo run

Type hashes must match between ros-z and rmw_zenoh_cpp. If they don't, you may have:

  • Different message definitions
  • Different ROS 2 distros
  • Outdated generated messages

No Messages Through zenoh-bridge-ros2dds?

Check format: Ensure ros-z uses KeyExprFormat::Ros2Dds:

let ctx = ZContextBuilder::default()
    .keyexpr_format(KeyExprFormat::Ros2Dds)
    .build()?;

Check bridge configuration: Verify zenoh-bridge-ros2dds is running and connected to the same Zenoh router as ros-z.

Format Comparison

When to Use RmwZenoh Format

Use RmwZenoh when:

  • Building pure Zenoh-based ROS 2 systems
  • Using rmw_zenoh_cpp middleware
  • Requiring domain isolation
  • Deploying new systems with native Zenoh support
  • Maximizing Zenoh performance benefits

When to Use Ros2Dds Format

Use Ros2Dds when:

  • Bridging existing DDS-based ROS 2 systems
  • Using zenoh-bridge-ros2dds
  • Integrating with legacy ROS 2 infrastructure
  • Gradual migration from DDS to Zenoh
  • Heterogeneous deployments (DDS + Zenoh)

rmw_zenoh_rs

rmw_zenoh_rs is a Rust-based ROS Middleware (RMW) implementation that enables standard ROS 2 C++/Python nodes to communicate via Zenoh. It allows you to use Zenoh as the transport layer for your existing ROS 2 applications without modifying your code. It is fully interoperable with rmw_zenoh_cpp, allowing seamless communication between nodes using either implementation.

What is an RMW?

ROS 2 uses a middleware abstraction layer called RMW (ROS Middleware) that allows you to choose different transport implementations. By default, ROS 2 uses DDS-based middleware like Fast-DDS or CycloneDDS. With rmw_zenoh_rs, you can use Zenoh instead.

┌─────────────────────────────────────────────────┐
│              ROS 2 Application                  │
│         (C++ node using rclcpp)                 │
├─────────────────────────────────────────────────┤
│                    RCL                          │
│         (ROS Client Library - C)                │
├─────────────────────────────────────────────────┤
│                    RMW                          │
│      (ROS Middleware Interface - C)             │
├─────────────────────────────────────────────────┤
│              rmw_zenoh_rs                       │  ← This package
│         (Rust implementation)                   │
│  ┌──────────────────────────────────────────┐   │
│  │  FFI Layer (bindgen + cxx)               │   │
│  ├──────────────────────────────────────────┤   │
│  │  ros-z primitives                        │   │
│  │  (pubsub, service, guard_condition)      │   │
│  ├──────────────────────────────────────────┤   │
│  │  Zenoh                                   │   │
│  └──────────────────────────────────────────┘   │
└─────────────────────────────────────────────────┘

Requirements

System Requirements

  • ROS 2 Jazzy
  • Rust toolchain (1.91 or later)
  • Cargo (comes with Rust)
  • CMake (3.16 or later)
  • Clang (for bindgen)

ROS 2 Dependencies

The following ROS 2 packages are required:

  • rmw - RMW interface definitions
  • rcutils - ROS C utilities
  • rcpputils - ROS C++ utilities
  • fastcdr - Fast CDR serialization
  • rosidl_typesupport_fastrtps_c - Type support for C
  • rosidl_typesupport_fastrtps_cpp - Type support for C++

These are typically installed with ROS 2:

# Ubuntu/Debian with ROS 2 Jazzy
sudo apt install ros-jazzy-rmw ros-jazzy-rcutils ros-jazzy-rcpputils \
  ros-jazzy-fastcdr ros-jazzy-rosidl-typesupport-fastrtps-c \
  ros-jazzy-rosidl-typesupport-fastrtps-cpp

Building rmw_zenoh_rs

# Source your ROS 2 installation
source /opt/ros/jazzy/setup.bash

# Create a workspace
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src

# Clone ros-z repository
git clone https://github.com/ZettaScaleLabs/ros-z.git

# Build rmw_zenoh_rs
cd ~/ros2_ws
colcon build --packages-select rmw_zenoh_rs --symlink-install

Build Output

After building, you'll have:

  • librmw_zenoh_rs.so - The RMW library (Linux)
  • RMW plugin registration - Allows ROS 2 to discover rmw_zenoh_rs

Using rmw_zenoh_rs

Setting the RMW Implementation

To use rmw_zenoh_rs, set the RMW_IMPLEMENTATION environment variable:

export RMW_IMPLEMENTATION=rmw_zenoh_rs

This tells ROS 2 to use rmw_zenoh_rs instead of the default DDS implementation.

Example: Running ROS 2 Nodes

Start a Zenoh router first, then run your nodes with the RMW implementation set:

# Terminal 1: Start Zenoh router (required)
zenohd

# Terminal 2: Talker
source ~/ros2_ws/install/setup.bash
export RMW_IMPLEMENTATION=rmw_zenoh_rs
ros2 run demo_nodes_cpp talker

# Terminal 3: Listener
source ~/ros2_ws/install/setup.bash
export RMW_IMPLEMENTATION=rmw_zenoh_rs
ros2 run demo_nodes_cpp listener

Your nodes will now communicate via Zenoh instead of DDS!

Warning

Unlike multicast-based discovery, router-based architecture is required by default. Both rmw_zenoh_rs and rmw_zenoh_cpp expect a router at tcp/localhost:7447. Without a router, nodes will not discover each other.

Why a Zenoh router?

ros-z, rmw_zenoh_rs, and rmw_zenoh_cpp all use router-based discovery by default, which provides:

  • Better scalability - Handles large deployments with many nodes
  • Lower network overhead - More efficient than multicast discovery
  • Cross-network communication - Nodes can discover each other across network boundaries
  • Production-ready architecture - Standard approach used in real ROS 2 systems
  • Interoperability - Required for ros-z nodes to work with rmw_zenoh_cpp nodes

Info

The router runs as a separate process and manages discovery and routing between all Zenoh-based nodes. You only need one router per network, regardless of how many nodes you run.

rmw_zenoh_rs vs rmw_zenoh_cpp

Both rmw_zenoh_rs and rmw_zenoh_cpp are RMW implementations using Zenoh, but with different design goals:

Featurermw_zenoh_rsrmw_zenoh_cpp
Implementation LanguageRust (using ros-z)C++
Primary Use CaseIntegration with ros-z ecosystemStandalone Zenoh RMW
ROS 2 CompatibilityJazzyHumble, Iron, ..., Rolling
StatusExperimentalProduction-ready
Dependenciesros-z, Zenoh RustZenoh C++ binding
PerformanceOptimized for Rust stackOptimized for C++ stack
Interoperability✅ Works with rmw_zenoh_cpp✅ Works with rmw_zenoh_rs

Configuration

rmw_zenoh_rs uses the same Zenoh configuration as rmw_zenoh_cpp. See Configuration Options for details.

See Also

Python Bindings

ros-z provides Python bindings via ros-z-py, enabling Python applications to communicate with Rust and ROS 2 nodes using the same Zenoh transport. The bindings use PyO3 for Rust-Python interop and msgspec for efficient message serialization.

Note

Python bindings provide the same pub/sub and service patterns as Rust, with Pythonic APIs. Messages are automatically serialized/deserialized between Python objects and CDR format for ROS 2 compatibility.

Visual Flow

graph TD
    A[Python Code] -->|import| B[ros_z_py]
    B -->|PyO3| C[Rust ros-z]
    C -->|Zenoh| D[Network]
    D -->|Zenoh| E[ROS 2 / Rust Nodes]

    F[Python Message] -->|msgspec| G[Struct]
    G -->|serialize| H[CDR Bytes]
    H -->|deserialize| I[Rust Struct]

Installation

Prerequisites

  • Python 3.8+
  • Rust toolchain
  • maturin (pip install maturin)

Setup

# Create and activate virtual environment
cd ros-z-py
python -m venv .venv
source .venv/bin/activate

# Install message types
pip install -e ../crates/ros-z-msgs/python/

# Build and install ros-z-py
maturin develop

Tip

Use maturin develop --release for optimized builds when benchmarking or running in production.

Quick Start

Here's a complete publisher and subscriber example from ros-z-py/examples/topic_demo.py:

Publisher (Talker)

def run_talker(ctx, topic: str, count: int, interval: float):
    """Run the talker (publisher)."""
    node = ctx.create_node("talker").build()
    pub = node.create_publisher(topic, std_msgs.String)

    print(f"Talker started. Publishing to {topic}...")

    i = 0
    while count == 0 or i < count:
        message = f"Hello from Python {i}"
        msg = std_msgs.String(data=message)
        pub.publish(msg)
        print(f"PUB:{i}", flush=True)
        i += 1
        time.sleep(interval)

    print("PUB:DONE", flush=True)


Subscriber (Listener)

def run_listener(ctx, topic: str, timeout: float):
    """Run the listener (subscriber)."""
    node = ctx.create_node("listener").build()
    sub = node.create_subscriber(topic, std_msgs.String)

    print("SUB:READY", flush=True)

    start = time.time()
    received = 0

    while timeout == 0 or (time.time() - start) < timeout:
        msg = sub.recv(timeout=1.0)
        if msg is not None:
            print(f"SUB:{msg.data}", flush=True)
            received += 1

    print(f"SUB:TOTAL:{received}", flush=True)


Key Components

ComponentPurposePython API
ZContextBuilderConfigure ros-z environmentZContextBuilder().with_domain_id(0).build()
ZContextManages ROS 2 connectionsEntry point for creating nodes
NodeLogical unit of computationctx.create_node("name").build()
PublisherSends messages to topicsnode.create_publisher(topic, type)
SubscriberReceives messages from topicsnode.create_subscriber(topic, type)
ClientSends service requestsnode.create_client(service, type)
ServerHandles service requestsnode.create_server(service, type)

Service Patterns

Examples from ros-z-py/examples/service_demo.py:

Service Server

def run_server(ctx, service: str, max_requests: int):
    """Run the AddTwoInts service server."""
    node = ctx.create_node("add_two_ints_server").build()
    server = node.create_server(service, example_interfaces.AddTwoIntsRequest)

    print("SERVER:READY", flush=True)

    handled = 0
    while max_requests == 0 or handled < max_requests:
        request_id, req = server.take_request()
        result = req.a + req.b
        print(f"SERVER:{req.a}+{req.b}={result}", flush=True)

        resp = example_interfaces.AddTwoIntsResponse(sum=result)
        server.send_response(resp, request_id)
        handled += 1

    print("SERVER:DONE", flush=True)


Service Client

def run_client(ctx, service: str, a: int, b: int, timeout: float):
    """Run the AddTwoInts service client."""
    node = ctx.create_node("add_two_ints_client").build()
    client = node.create_client(service, example_interfaces.AddTwoIntsRequest)

    # Wait for service discovery
    time.sleep(1.0)

    print(f"CLIENT:REQUEST:{a}+{b}", flush=True)

    req = example_interfaces.AddTwoIntsRequest(a=a, b=b)
    client.send_request(req)

    resp = client.take_response(timeout=timeout)

    if resp is not None:
        print(f"CLIENT:RESPONSE:{resp.sum}", flush=True)
    else:
        print("CLIENT:ERROR:no response", flush=True)
        sys.exit(1)


Tip

Service servers use a pull model: take_request() blocks until a request arrives. This gives you explicit control over when to process requests.

Complex Messages

Python bindings support nested message types like geometry_msgs/Twist:

from ros_z_py import geometry_msgs

# Create a Twist message with nested Vector3
twist = geometry_msgs.Twist(
    linear=geometry_msgs.Vector3(x=1.0, y=0.0, z=0.0),
    angular=geometry_msgs.Vector3(x=0.0, y=0.0, z=0.5)
)

pub = node.create_publisher("/cmd_vel", "geometry_msgs/msg/Twist")
pub.publish(twist)

Context Configuration

Connect to Specific Endpoint

ctx = (
    ros_z_py.ZContextBuilder()
    .with_connect_endpoints(["tcp/192.168.1.100:7447"])
    .build()
)

Disable Multicast Scouting

ctx = (
    ros_z_py.ZContextBuilder()
    .with_domain_id(0)
    .disable_multicast_scouting()
    .build()
)

Custom Namespace

node = ctx.create_node("my_node").with_namespace("/robot1").build()

Performance: Zero-Copy Large Payloads

When working with large byte arrays (sensor data, images, point clouds), ros-z-py minimizes memory copies using a zero-copy optimization for uint8[] and byte[] fields.

ZBufView

When a subscriber receives a message, byte array fields are exposed as a ZBufView — a zero-copy view into the received network buffer. ZBufView implements Python's buffer protocol:

msg = sub.recv(timeout=1.0)
# msg.data is a ZBufView — no copy has occurred

# Zero-copy access via buffer protocol
mv = memoryview(msg.data)
header = mv[:8]  # Slice without copying the entire payload

# Only copies when explicitly converted
data = bytes(msg.data)

Echo Without Copying

For relay and echo patterns, pass ZBufView fields directly to a new message. The derive macro detects ZBufView and extracts the inner buffer via reference counting — no data copy occurs:

# Receive and re-publish — zero-copy for byte array fields
msg = sub.recv(timeout=1.0)
echo = std_msgs.ByteMultiArray(data=msg.data)  # No copy!
pub.publish(echo)

ZBufView API

MethodDescription
len(view)Number of bytes
bool(view)True if not empty
view[i]Single byte access
view[start:stop]Slice (returns bytes)
memoryview(view)Zero-copy buffer protocol access
bytes(view)Convert to bytes (copies)
view.is_zero_copyWhether the view avoids internal copying

Tip

For best performance with large payloads, avoid calling bytes() on ZBufView fields. Use memoryview() for read access, or pass the ZBufView directly when re-publishing.

How It Works

The optimization operates at three layers:

  1. Deserialization bypass: When the Python subscriber receives a message, the raw network buffer (ZBuf) is stored in a thread-local. During CDR deserialization, byte array fields create sub-views into this buffer instead of copying (ZSlice::subslice()).

  2. Buffer protocol: ZBufView wraps the ZBuf and exposes its bytes to Python via __getbuffer__/__releasebuffer__. For contiguous buffers (the common case), this is a direct pointer — no copy at all.

  3. Pass-through re-publish: The FromPyMessage derive macro recognizes ZBufView inputs and extracts the inner ZBuf via clone(), which only increments a reference count on the underlying memory.

ROS 2 Interoperability

Python nodes work seamlessly with Rust and ROS 2 nodes:

# Terminal 1: Start Zenoh router
cargo run --example zenoh_router

# Terminal 2: Run Python publisher (using topic_demo.py)
cd ros-z-py
source .venv/bin/activate
python examples/topic_demo.py -r talker

# Terminal 3: Listen with ROS 2 CLI
ros2 topic echo /chatter std_msgs/msg/String

Success

Messages published from Python are received by ROS 2 CLI, Rust nodes, and any other ROS 2-compatible system connected via Zenoh.

Running Tests

# Python unit tests
cd ros-z-py
source .venv/bin/activate
python -m pytest tests/ -v

# Python-Rust interop tests
cargo test --features python-interop -p ros-z-tests --test python_interop -- --test-threads=1

Troubleshooting

Import errors when using ros_z_py

This error occurs when the package hasn't been built or installed correctly.

Solution:

Rebuild and install the package:

cd ros-z-py
source .venv/bin/activate
pip install -e ../crates/ros-z-msgs/python/
maturin develop

Message type not found

This error occurs when trying to use a message type that isn't registered.

Solution:

Check which message types are available:

from ros_z_py import ros_z_msgs
print(ros_z_msgs.list_registered_types())

Ensure the message package is enabled in ros-z-msgs/Cargo.toml features.

recv() always returns None

This happens when no messages are being received within the timeout period.

Solution:

  • Check the topic name matches exactly (including leading /)
  • Verify the publisher is running and connected to the same Zenoh network
  • Increase the timeout value
  • Use --nocapture with pytest to see debug output: python -m pytest tests/ -v --capture=no

Resources

Start with the pub/sub example to understand the basics, then explore services for request-response patterns.

Python Code Generation Internals

This chapter explains how ros-z generates Python bindings for ROS 2 messages, including the architecture, generated code structure, and design rationale.

Architecture Overview

ros-z uses a hybrid approach: Python classes for ergonomics, Rust for serialization performance. The architecture uses derive macros for automatic Python-Rust conversion of arbitrarily nested message types.

graph TB
    subgraph "Build Time (cargo build)"
        ROS[".msg/.srv files"] --> Parser["ros-z-codegen<br/>Parser"]
        Parser --> Resolver["Dependency<br/>Resolver"]
        Resolver --> PyGen["Python Generator"]
        Resolver --> RsGen["Rust Generator"]
        PyGen --> PyFiles["*.py files<br/>(msgspec structs)"]
        RsGen --> RsFile["Rust structs with<br/>derive macros"]
        RsGen --> PyO3File["python_bindings.rs<br/>(serialize/deserialize)"]
    end

    subgraph "Derive Macros (ros-z-derive)"
        Derive["FromPyMessage<br/>IntoPyMessage"]
        Derive -->|"generates"| Extract["Field extraction code"]
        Derive -->|"generates"| Construct["Object construction code"]
    end

    subgraph "Runtime"
        PyFiles --> PyObj["Python Object"]
        PyObj -->|"FromPyMessage::from_py()"| RsStruct["Rust Struct"]
        RsStruct -->|"ros-z-cdr::to_vec()"| CDR["CDR Bytes"]
        CDR -->|"Zenoh"| Network["Network"]
    end

Key Components

ComponentLocationPurpose
Python Generatorros-z-codegen/src/generator/python.rsGenerates msgspec struct classes
Rust Generatorros-z-codegen/src/generator/rust.rsGenerates Rust structs with derive attributes
PyO3 Generatorros-z-codegen/src/python_msgspec_generator.rsGenerates serialize/deserialize wrapper functions
Derive Macrosros-z-derive/src/lib.rsFromPyMessage and IntoPyMessage derive macros
Bridge Traitsros-z/src/python_bridge.rsCore traits for Python-Rust conversion
Build Scriptros-z-msgs/build.rsOrchestrates code generation at build time
Generated Pythonros-z-msgs/python/ros_z_msgs_py/types/*.pyOne file per ROS package
Generated Rust$OUT_DIR/python_bindings.rsCompiled into ros-z-msgs crate

Generated Code Examples

Python: msgspec Structs

For each ROS message, a frozen msgspec.Struct is generated:

# Generated from std_msgs/msg/String.msg
class String(msgspec.Struct, frozen=True, kw_only=True):
    data: str = ""

    __msgtype__: ClassVar[str] = 'std_msgs/msg/String'
    __hash__: ClassVar[str] = 'RIHS01_df668c740482bbd48fb39d76a70dfd4bd59db1288021743503259e948f6b1a18'

Nested messages use forward references:

# Generated from geometry_msgs/msg/Twist.msg
class Twist(msgspec.Struct, frozen=True, kw_only=True):
    linear: "geometry_msgs.Vector3 | None" = None
    angular: "geometry_msgs.Vector3 | None" = None

    __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Twist'
    __hash__: ClassVar[str] = 'RIHS01_9c45bf16fe0983d80e3cfe750d6835843d265a9a6c46bd2e609fcddde6fb8d2a'

Service request/response types use the service type hash in __hash__:

# Generated from example_interfaces/srv/AddTwoInts.srv
class AddTwoIntsRequest(msgspec.Struct, frozen=True, kw_only=True):
    a: int = 0
    b: int = 0

    __msgtype__: ClassVar[str] = 'example_interfaces/msg/AddTwoIntsRequest'
    __hash__: ClassVar[str] = 'RIHS01_e118de6bf5eeb66a2491b5bda11202e7b68f198d6f67922cf30364858239c81a'

class AddTwoIntsResponse(msgspec.Struct, frozen=True, kw_only=True):
    sum: int = 0

    __msgtype__: ClassVar[str] = 'example_interfaces/msg/AddTwoIntsResponse'
    __hash__: ClassVar[str] = 'RIHS01_e118de6bf5eeb66a2491b5bda11202e7b68f198d6f67922cf30364858239c81a'

For service types, __hash__ contains the service type hash (computed from the combined request/response definition). Both request and response share the same hash since they belong to the same service. This differs from regular messages where __hash__ contains the individual message type hash.

Rust: Generated Structs with Derive Macros

The Rust code generator adds derive attributes to message structs:

// Generated from std_msgs/msg/String.msg
#[derive(Debug, Clone, Default, ::serde::Serialize, ::serde::Deserialize)]
#[cfg_attr(feature = "python_registry", derive(::ros_z_derive::FromPyMessage, ::ros_z_derive::IntoPyMessage))]
#[cfg_attr(feature = "python_registry", ros_msg(module = "ros_z_msgs_py.types.std_msgs"))]
pub struct String {
    pub data: std::string::String,
}

For nested messages with optional fields:

// Generated from geometry_msgs/msg/Twist.msg
#[derive(Debug, Clone, Default, ::serde::Serialize, ::serde::Deserialize)]
#[cfg_attr(feature = "python_registry", derive(::ros_z_derive::FromPyMessage, ::ros_z_derive::IntoPyMessage))]
#[cfg_attr(feature = "python_registry", ros_msg(module = "ros_z_msgs_py.types.geometry_msgs"))]
pub struct Twist {
    pub linear: Vector3,
    pub angular: Vector3,
}

Derive Macros: Zero-Copy Byte Array Handling

Fields annotated with #[ros_msg(zbuf)] (applied automatically by the code generator for uint8[]/byte[] fields) get special treatment in the derive macros:

FromPyMessage (Python → Rust) tries three paths in order:

  1. ZBufView — extracts the inner ZBuf via clone() (reference-counted, zero-copy)
  2. bytes/bytearray — copies into a new ZBuf
  3. list[int] — fallback extraction
// Generated by FromPyMessage derive macro for #[ros_msg(zbuf)] fields
let py_attr = obj.getattr("data")?;
if let Ok(view) = py_attr.downcast::<ZBufView>() {
    view.borrow().zbuf().clone()     // Arc clone — no data copy
} else if let Ok(bytes) = py_attr.downcast::<PyBytes>() {
    ZBuf::from(bytes.as_bytes().to_vec())
} else if let Ok(bytearray) = py_attr.downcast::<PyByteArray>() {
    ZBuf::from(unsafe { bytearray.as_bytes() }.to_vec())
} else {
    let bytes: Vec<u8> = py_attr.extract()?;
    ZBuf::from(bytes)
}

IntoPyMessage (Rust → Python) creates a ZBufView instead of copying into PyBytes:

// Generated by IntoPyMessage derive macro for #[ros_msg(zbuf)] fields
let zbuf_view = ZBufView::new(self.data.clone());
let py_view = Py::new(py, zbuf_view)?;
kwargs.set_item("data", py_view)?;

This means a received message's byte array fields can be passed directly to a new message for re-publishing without any data copy.

Rust: PyO3 Serialize/Deserialize Functions

The serialize/deserialize functions use the derive macro traits:

// Generated serialize function - uses FromPyMessage trait
#[pyfunction]
pub fn serialize_string(py: Python, msg: &Bound<'_, PyAny>) -> PyResult<Vec<u8>> {
    use ::pyo3::types::PyAnyMethods;
    use ::ros_z::python_bridge::FromPyMessage;

    // Derive macro handles all field extraction recursively
    let rust_msg = <ros::std_msgs::String>::from_py(msg)?;

    // CDR serialization with 4-byte encapsulation header
    let mut cdr_data = ros_z_cdr::to_vec::<_, ros_z_cdr::LittleEndian>(&rust_msg, 256)
        .map_err(|e| pyo3::exceptions::PyValueError::new_err(e.to_string()))?;
    let mut result = vec![0x00, 0x01, 0x00, 0x00]; // CDR encapsulation header
    result.append(&mut cdr_data);
    Ok(result)
}

// Generated deserialize function - uses IntoPyMessage trait
#[pyfunction]
pub fn deserialize_string(py: Python, bytes: &[u8]) -> PyResult<PyObject> {
    use ::ros_z::python_bridge::IntoPyMessage;

    // Skip 4-byte CDR encapsulation header
    let cdr_data = &bytes[4..];
    let (rust_msg, _): (ros::std_msgs::String, _) = ros_z_cdr::from_bytes::<_, ros_z_cdr::LittleEndian>(cdr_data)
        .map_err(|e| pyo3::exceptions::PyValueError::new_err(e.to_string()))?;

    // Derive macro handles all field construction recursively
    rust_msg.into_py_message(py)
}

Data Flow

Publishing (Python to Wire)

sequenceDiagram
    participant App as Python App
    participant Msg as msgspec.Struct
    participant PyO3 as PyO3 Layer
    participant Rust as Rust Struct
    participant CDR as CDR Encoder
    participant Net as Zenoh Network

    App->>Msg: Create message
    App->>PyO3: publish(msg)
    PyO3->>PyO3: getattr() each field
    PyO3->>Rust: Construct Rust struct
    Rust->>CDR: cdr::serialize()
    CDR->>Net: Send bytes

Subscribing (Wire to Python)

sequenceDiagram
    participant Net as Zenoh Network
    participant CDR as CDR Decoder
    participant Rust as Rust Struct
    participant PyO3 as PyO3 Layer
    participant Msg as msgspec.Struct
    participant App as Python App

    Net->>CDR: Receive bytes
    Note over CDR: Store ZBuf in thread-local<br/>for zero-copy deser
    CDR->>Rust: cdr::deserialize()
    Note over CDR,Rust: byte[] fields → ZSlice sub-view<br/>(zero-copy)
    Rust->>PyO3: Build PyDict kwargs
    Note over PyO3: byte[] → ZBufView<br/>(buffer protocol)
    PyO3->>Msg: Call class(**kwargs)
    Msg->>App: Return message

Type Mapping

ROS to Python Type Mapping

ROS TypePython TypeNotes
boolbool
byte, uint8, int8, int16, uint16, int32, uint32, int64, uint64intPython has arbitrary precision
float32, float64float
stringstr
T[] (unbounded array)list[T]
T[N] (fixed array)list[T]Size not enforced in Python
uint8[] / byte[]ZBufViewZero-copy buffer protocol (on receive); accepts bytes, bytearray, or ZBufView on publish
Nested message"pkg.MsgName | None"Forward reference string

Design: Hybrid Python + Rust with Derive Macros

┌─────────────────────────────────────────────────────────────┐
│                    Current Architecture                      │
├─────────────────────────────────────────────────────────────┤
│  Python Layer          │  Rust Layer (via PyO3)             │
│  ─────────────         │  ──────────────────────            │
│  • msgspec structs     │  • Derive macros                   │
│  • Type annotations    │  • Trait-based conversion          │
│  • IDE support         │  • CDR serialization               │
│  • User-facing API     │  • Zenoh transport                 │
│                        │  • Memory management               │
└─────────────────────────────────────────────────────────────┘

Features:

  • Fast serialization (Rust CDR implementation)
  • Type-safe Python classes with IDE support
  • Immutable messages (frozen=True)
  • Automatic type hash validation
  • Zero-copy byte array handling: ZBufView exposes received data via buffer protocol without copying; FromPyMessage detects ZBufView inputs and extracts the inner buffer via reference counting
  • Derive macros handle arbitrary nesting depth automatically
  • None handling for optional nested fields
  • Minimal generated code (traits do the work)

Build Process

Step-by-step Flow

flowchart TD
    A["cargo build ros-z-msgs<br/>--features python_registry"] --> B["build.rs executes"]
    B --> C["Discover ROS packages<br/>(AMENT_PREFIX_PATH or bundled)"]
    C --> D["Parse .msg/.srv files"]
    D --> E["Resolve dependencies<br/>(type hashes, nested types)"]
    E --> F["Generate Python files"]
    E --> G["Generate Rust PyO3 module"]
    F --> H["ros-z-msgs/python/<br/>ros_z_msgs_py/types/*.py"]
    G --> I["$OUT_DIR/python_bindings.rs"]
    I --> J["include!() in lib.rs"]
    J --> K["Compiled into ros-z-msgs"]

Output Locations

OutputPathCommitted?
Python msgspec classesros-z-msgs/python/ros_z_msgs_py/types/*.pyYes
Rust PyO3 bindingstarget/.../ros-z-msgs-.../out/python_bindings.rsNo (generated)

Feature Flags

The Python codegen is gated behind the python_registry feature:

#![allow(unused)]
fn main() {
// lib.rs
#[cfg(feature = "python_registry")]
include!(concat!(env!("OUT_DIR"), "/python_bindings.rs"));
}

The ros-z-derive crate provides the derive macros, and ros-z/python enables the FromPyMessage and IntoPyMessage traits.

Reproducible Development with Nix

Warning

This is an advanced topic for users familiar with Nix. If you're new to Nix, you can safely skip this chapter and use the standard Building instructions instead.

ros-z provides Nix flakes for reproducible development environments with all dependencies pre-configured.

Why Use Nix?

Reproducible Builds: Nix ensures every developer and CI system uses the exact same dependencies, eliminating "works on my machine" issues. All dependencies—from compilers to ROS 2 packages—are pinned to specific versions and cached immutably.

Uniform CI/CD: The same Nix configuration that runs locally is used in continuous integration, ensuring build consistency across development, testing, and deployment environments. No more divergence between local builds and CI failures.

Zero Setup: New team members can start developing with a single nix develop command—no manual ROS installation, no dependency hunting, no environment configuration.

Available Environments

# Default: ROS 2 Jazzy with full tooling
nix develop

# Specific ROS distros
nix develop .#ros-jazzy      # ROS 2 Jazzy
nix develop .#ros-rolling    # ROS 2 Rolling

# Pure Rust (no ROS)
nix develop .#pureRust       # Minimal Rust toolchain only

Use Cases

Use CaseEnvironmentBenefit
Team DevelopmentAll developersEveryone has identical toolchains and dependencies
CI/CD PipelinesGitHub Actions, GitLab CISame environment locally and in automation
Cross-PlatformLinux, macOS, WSLConsistent builds regardless of host OS
Multiple ROS VersionsSwitch environments easilyTest against different ROS distros without conflicts

Tip

Use Nix for consistent development environments across team members and CI/CD pipelines. The reproducibility guarantees catch integration issues early.

Learning More

Feature Flags

Fine-grained control over dependencies and functionality through Cargo feature flags. Build exactly what you need, from zero-dependency core to full ROS 2 integration, without carrying unused code.

Success

Feature flags enable pay-per-use dependencies. Start minimal and enable features incrementally as requirements grow.

Feature Categories

CategoryPurposeExample Features
DistributionTarget specific ROS 2 versionshumble, jazzy, rolling
Message PackagesEnable ROS 2 message typesstd_msgs, geometry_msgs
SerializationAdditional encoding formatsprotobuf
IntegrationExternal system bindingsrcl-z

ros-z Core Features

protobuf

Enables Protocol Buffers serialization using prost.

cargo build -p ros-z --features protobuf

Use cases:

  • Schema evolution support
  • Language-agnostic data exchange
  • Efficient binary encoding
  • Familiar protobuf ecosystem

Dependencies: prost, prost-types

Info

Protobuf is optional. CDR serialization (default) provides full ROS 2 compatibility without additional dependencies.

Distribution Compatibility Features

ros-z defaults to ROS 2 Jazzy. Use distribution features to target other ROS 2 versions.

jazzy (default)

Targets ROS 2 Jazzy Jalisco with modern type hash support.

# Automatically enabled (default)
cargo build

# Explicitly enable
cargo build --features jazzy

Features:

  • ✅ Type hash support (RIHS01)
  • ✅ Shared memory optimization
  • ✅ Modern ROS 2 protocol

humble

Targets ROS 2 Humble Hawksbill (LTS) with legacy compatibility.

# Disable defaults and enable humble
cargo build --no-default-features --features humble

Features:

  • ❌ No type hash (uses placeholder)
  • ❌ No shared memory support
  • ✅ LTS support until 2027
  • ✅ Compatible with rmw_zenoh_cpp v0.1.8

Important: Humble requires --no-default-features to avoid conflicts with the jazzy default.

rolling and iron

Target newer distributions:

# Rolling
cargo build --features rolling

# Iron
cargo build --features iron

See also: ROS 2 Distribution Compatibility for detailed documentation.

rcl-z

Enables RCL (ROS Client Library) integration for C/C++ interoperability.

cargo build -p ros-z --features rcl-z

Use cases:

  • Integrating with existing RCL-based code
  • Leveraging C/C++ ROS 2 libraries
  • Hybrid Rust/C++ applications

Requirements: ROS 2 installation with RCL libraries

Warning

This feature requires ROS 2 to be sourced before building. See Building Guide for setup instructions.

ros-z-msgs Features

Default Features

The default build includes commonly used message types via core_msgs:

cargo build -p ros-z-msgs

Includes:

  • std_msgs - Basic types (String, Int32, etc.)
  • geometry_msgs - Spatial types (Point, Pose, Transform)
  • sensor_msgs - Sensor data (LaserScan, Image, Imu)
  • nav_msgs - Navigation (Path, Odometry, OccupancyGrid)
  • example_interfaces - Tutorial services (AddTwoInts)
  • action_tutorials_interfaces - Tutorial actions (Fibonacci)

Tip

All messages are vendored in assets - no ROS 2 installation required. Feature flags simply control which packages to include in your build.

Individual Package Features

All packages are bundled in assets and work without ROS 2:

FeaturePackageUse Case
std_msgsStandard messagesStrings, numbers, arrays
geometry_msgsGeometric primitivesPoints, poses, transforms
sensor_msgsSensor dataCameras, lidars, IMUs
nav_msgsNavigationPaths, maps, odometry
example_interfacesTutorial servicesAddTwoInts, Fibonacci
action_tutorials_interfacesTutorial actionsFibonacci action
test_msgsTest typesTesting and validation

Usage:

# Single package
cargo build -p ros-z-msgs --no-default-features --features std_msgs

# Multiple packages
cargo build -p ros-z-msgs --no-default-features --features "std_msgs,geometry_msgs"

# Default (core_msgs)
cargo build -p ros-z-msgs

Convenience Aliases

core_msgs (default):

The most commonly used packages for ROS 2 development.

cargo build -p ros-z-msgs  # Uses core_msgs by default

Enables: std_msgs, geometry_msgs, sensor_msgs, nav_msgs, example_interfaces, action_tutorials_interfaces

common_interfaces:

cargo build -p ros-z-msgs --features common_interfaces

Enables: std_msgs, geometry_msgs, sensor_msgs

bundled_msgs:

cargo build -p ros-z-msgs --features bundled_msgs

Enables: std_msgs, geometry_msgs, sensor_msgs, nav_msgs

robotics:

Alias for core_msgs.

all_msgs:

cargo build -p ros-z-msgs --features all_msgs

Enables: All available packages including test_msgs

Protobuf Types

Generate protobuf types alongside ROS messages:

cargo build -p ros-z-msgs --features protobuf

Note: Requires ros-z/protobuf feature enabled as well.

ros-z-codegen Features

Protobuf Code Generation

Enable protobuf code generation support:

cargo build -p ros-z-codegen --features protobuf

Use case: Building tools that generate protobuf code from ROS messages

Feature Dependency Graph

graph TD
    A[all_msgs] --> B[bundled_msgs]
    A --> C[example_interfaces]
    A --> D[action_tutorials_interfaces]
    A --> E[test_msgs]

    B --> F[std_msgs]
    B --> G[geometry_msgs]
    B --> H[sensor_msgs]
    B --> I[nav_msgs]

    J[core_msgs] --> F
    J --> G
    J --> H
    J --> I
    J --> C
    J --> D

Common Feature Combinations

Minimal Development

Core library only, no messages:

cargo build -p ros-z

Dependencies: Rust, Cargo Use case: Custom messages only

Standard Development

Core with common message types:

cargo build -p ros-z-msgs  # Uses default common_interfaces
cargo build -p ros-z

Dependencies: Rust, Cargo Use case: Most applications

Full Message Set

All available message packages:

cargo build -p ros-z-msgs --features all_msgs

Dependencies: Rust, Cargo Use case: Access to all bundled message types including test_msgs

RCL Integration

For C/C++ ROS 2 interoperability:

source /opt/ros/jazzy/setup.bash
cargo build -p rcl-z

Dependencies: Rust, Cargo, ROS 2 Use case: Hybrid Rust/C++ applications

Protobuf Development

Core with protobuf serialization:

cargo build -p ros-z-codegen --features protobuf
cargo build -p ros-z-msgs --features protobuf
cargo build -p ros-z --features protobuf

Dependencies: Rust, Cargo, Protobuf compiler Use case: Cross-language data exchange

Feature Matrix

PackageFeatureRequires ROS 2Adds Dependencies
ros-z(none)NoNone
ros-zjazzy (default)NoNone
ros-zhumbleNoNone
ros-zrollingNoNone
ros-zprotobufNoprost, prost-types
ros-zrcl-zYesRCL libraries
ros-z-msgscore_msgs (default)NoNone (bundled)
ros-z-msgsbundled_msgsNoNone (bundled)
ros-z-msgsall_msgsNoNone (bundled)
ros-z-msgsprotobufNoprost, prost-types
ros-z-msgsjazzy (default)NoNone
ros-z-msgshumbleNoNone
ros-z-codegenprotobufNoprost-build

Checking Active Features

View enabled features for a package:

# Show features for ros-z-msgs
cargo tree -p ros-z-msgs -e features

# Show all workspace features
cargo tree -e features

# Build with specific features and verify
cargo build -p ros-z-msgs --features std_msgs,geometry_msgs -v

Tip

Use cargo tree to debug feature resolution issues. It shows exactly which features are active and why.

Feature Selection Strategy

flowchart TD
    A[Start Project] --> B{Need ROS messages?}
    B -->|No| C[Zero features<br/>Custom messages]
    B -->|Yes| D{Which messages?}

    D -->|Common| E[core_msgs<br/>default]
    D -->|Minimal| F[bundled_msgs or<br/>individual packages]
    D -->|All| G[all_msgs]

    C --> H[Minimal dependencies]
    E --> I[Standard dependencies]
    F --> I
    G --> I

Decision guide:

  1. Most projects? → Use defaults (core_msgs) - includes common packages
  2. Minimal build? → Use --no-default-features with specific packages
  3. Custom messages only? → No message features
  4. Cross-language data? → Add protobuf feature
  5. C++ integration? → Add rcl-z feature (requires ROS 2)

Note

All message packages are vendored - no ROS 2 installation required for any message feature.

Info

First build with message generation is slow. Incremental builds are fast. Choose the minimal feature set that meets your needs.

Examples by Feature

Bundled Messages (Default)

cargo run --example z_pubsub          # std_msgs
cargo run --example twist_pub         # geometry_msgs
cargo run --example battery_state_sub # sensor_msgs
cargo run --example z_pingpong        # std_msgs
cargo run --example z_srvcli          # example_interfaces (now bundled)

Custom Messages

cargo run --example z_custom_message  # No features needed

Resources

Start with default features and add more as your project evolves. Feature flags provide flexibility without forcing early architectural decisions.

Troubleshooting

Quick solutions to common ros-z build and runtime issues. Click on any question to expand the answer.

Tip

Most issues fall into three categories: build configuration, runtime connectivity, or ROS 2 integration.

Build Issues

Build fails with 'Cannot find ROS packages' or package discovery errors

Root Cause: ROS 2 environment not sourced or packages not installed.

Solutions:

  1. Source ROS 2 environment:

    source /opt/ros/jazzy/setup.bash
    # or for rolling:
    source /opt/ros/rolling/setup.bash
    
  2. Verify environment variables:

    echo $AMENT_PREFIX_PATH
    echo $CMAKE_PREFIX_PATH
    
  3. Check package installation:

    ros2 pkg prefix example_interfaces
    # If fails, install:
    sudo apt install ros-jazzy-example-interfaces
    
  4. Clean and rebuild:

    cargo clean -p ros-z-msgs
    cargo build -p ros-z-msgs
    

Common Error Messages:

ErrorSolution
"Package X not found"Source ROS 2 environment
"Cannot find ament_index"Install ROS 2 or use bundled msgs
"AMENT_PREFIX_PATH not set"Run source /opt/ros/jazzy/setup.bash

Compiler error: cannot find crate ros_z_msgs

Root Cause: ros-z-msgs is not part of default workspace members.

Solution:

# Build ros-z-msgs explicitly
cargo build -p ros-z-msgs

# Then build your example
cargo build --example z_srvcli

Note: ros-z-msgs is excluded from default builds to avoid requiring ROS 2 for core development. Build it explicitly when needed.

Build takes too long to complete

Solutions:

# Use parallel builds (automatic on most systems)
cargo build -j $(nproc)

# Build only what you need
cargo build -p ros-z-msgs --features std_msgs,geometry_msgs

Linker errors during build (especially with rcl-z)

Solution:

# Clear cache and rebuild
cargo clean
source /opt/ros/jazzy/setup.bash
cargo build -p rcl-z

Warning: After changing feature flags or updating ROS 2, run cargo clean -p ros-z-msgs to force message regeneration.

Runtime Issues

Publishers and subscribers on different processes don't communicate

Root Cause: Zenoh router not running or nodes not configured correctly.

Solution:

  1. Ensure the router is running:

    cargo run --example zenoh_router
    
  2. Verify endpoint matches in your code:

    let ctx = ZContextBuilder::default()
        .with_router_endpoint("tcp/localhost:7447")  // Must match router
        .build()?;

Router fails to start with 'Address already in use' error

Root Cause: Another process is using port 7447.

Solutions:

  1. Stop the conflicting process

  2. Use a custom port:

    // Custom router port
    let router_config = RouterConfigBuilder::new()
        .with_listen_port(7448)
        .build()?;
    
    // Connect sessions to custom port
    let ctx = ZContextBuilder::default()
        .with_router_endpoint("tcp/localhost:7448")
        .build()?;

Don't want to manage a router for simple local testing

Solution: Use peer mode with multicast discovery:

let ctx = ZContextBuilder::default()
    .with_zenoh_config(zenoh::Config::default())
    .build()?;

Warning: Peer mode won't interoperate with ROS 2 nodes using rmw_zenoh_cpp in router mode.

Multi-segment topics like /robot/sensors/camera don't receive messages

Symptom: Publisher publishes to /robot/sensors/camera but subscriber never receives messages.

Root Cause: Old versions of ros-z (before 0.1.0) incorrectly mangled slashes in topic key expressions, breaking multi-segment topic routing.

Solution: Update to ros-z 0.1.0+ which correctly preserves internal slashes in topic key expressions.

Verify the fix:

# Enable debug logging to see key expressions
RUST_LOG=ros_z=debug cargo run --example z_pubsub

Look for key expressions in the output:

Key ExpressionStatus
0/robot/sensors/camera/...✅ Correct (slashes preserved)
0/robot%sensors%camera/...❌ Wrong (slashes mangled)

Technical Details:

  • Topic key expressions should use strip_slashes(): removes leading/trailing slashes, preserves internal slashes
  • Liveliness tokens should use mangle_name(): replaces all / with %
  • This matches the behavior of rmw_zenoh_cpp

See Key Expression Formats for details.

Resources

Most issues are environmental. Verify your setup matches the build scenario requirements before diving deeper.