Skip to main content
A channel manifest describes a robot’s control and state interface. It defines the named, typed, bounded channels that a WASM controller reads from and writes to on every tick. The safety filter uses these same definitions to clamp values before they reach actuators. Manifests follow the ros2_control / MuJoCo / Drake pattern: each robot exposes N command channels (written by the controller) and M state channels (read by the controller). The WASM controller accesses channels by index. The safety filter enforces per-channel limits.

Built-In Manifests

roz ships with factory methods for common robot types. Each method returns a ChannelManifest with the correct channels, limits, and rates preconfigured.

UR5 Manipulator

ChannelManifest::ur5()
6-DOF arm with velocity control and full joint state feedback. 6 command channels, 12 state channels (6 position + 6 velocity). Command Channels (6)
IndexNameTypeUnitLimitsRate Limit
0shoulder_pan_joint/velocityVelocityrad/s-3.14, 3.140.5
1shoulder_lift_joint/velocityVelocityrad/s-3.14, 3.140.5
2elbow_joint/velocityVelocityrad/s-3.14, 3.140.5
3wrist_1_joint/velocityVelocityrad/s-3.14, 3.140.5
4wrist_2_joint/velocityVelocityrad/s-3.14, 3.140.5
5wrist_3_joint/velocityVelocityrad/s-3.14, 3.140.5
Each command channel is paired with its corresponding position state channel (via position_state_index) for position limit enforcement. State Channels (12)
IndexNameTypeUnitLimits
0shoulder_pan_joint/positionPositionrad-6.28, 6.28
1shoulder_lift_joint/positionPositionrad-6.28, 6.28
2elbow_joint/positionPositionrad-6.28, 6.28
3wrist_1_joint/positionPositionrad-6.28, 6.28
4wrist_2_joint/positionPositionrad-6.28, 6.28
5wrist_3_joint/positionPositionrad-6.28, 6.28
6shoulder_pan_joint/velocityVelocityrad/s-3.14, 3.14
7shoulder_lift_joint/velocityVelocityrad/s-3.14, 3.14
8elbow_joint/velocityVelocityrad/s-3.14, 3.14
9wrist_1_joint/velocityVelocityrad/s-3.14, 3.14
10wrist_2_joint/velocityVelocityrad/s-3.14, 3.14
11wrist_3_joint/velocityVelocityrad/s-3.14, 3.14

Quadcopter

ChannelManifest::quadcopter()
Body-frame velocity control for drones. 4 command channels, 4 state channels. Command Channels (4)
IndexNameTypeUnitLimitsRate Limit
0body/velocity.xVelocitym/s-5.0, 5.02.0
1body/velocity.yVelocitym/s-5.0, 5.02.0
2body/velocity.zVelocitym/s-3.0, 3.01.5
3body/yaw_rateVelocityrad/s-1.57, 1.571.0
State Channels (4)
IndexNameTypeUnitLimits
0body/position.xPositionm-1000.0, 1000.0
1body/position.yPositionm-1000.0, 1000.0
2body/position.zPositionm0.0, 500.0
3body/yawPositionrad-3.14, 3.14

Differential Drive

ChannelManifest::diff_drive()
Twist-based control for wheeled mobile robots. 2 command channels, 3 state channels. Command Channels (2)
IndexNameTypeUnitLimitsRate Limit
0base/linear.xVelocitym/s-1.0, 1.00.5
1base/angular.zVelocityrad/s-2.0, 2.01.0
State Channels (3)
IndexNameTypeUnitLimits
0base/odom.xPositionm-1000.0, 1000.0
1base/odom.yPositionm-1000.0, 1000.0
2base/odom.yawPositionrad-3.14, 3.14

Generic Velocity

ChannelManifest::generic_velocity(n_joints, max_velocity)
Creates n_joints velocity command channels with symmetric limits (-max_velocity, max_velocity) and no state channels. Useful for quick prototyping or when you know the joint count and velocity limit but not the full robot specification.
// 4-joint arm with 2.0 rad/s limit
let manifest = ChannelManifest::generic_velocity(4, 2.0);
// Creates: joint0/velocity, joint1/velocity, joint2/velocity, joint3/velocity

Channel Descriptor Fields

Each channel is described by a ChannelDescriptor with these fields:
FieldTypeDescription
nameStringChannel name following ros2_control convention: "joint_name/interface_type"
interface_typeInterfaceTypePosition, Velocity, or Effort
unitStringPhysical unit: "rad", "rad/s", "m", "m/s", "Nm", "N"
limits(f64, f64)(min, max) value limits enforced by the safety filter
defaultf64Safe default value, usually 0.0
max_rate_of_changeOption<f64>Max change per tick for acceleration limiting. None = no rate limiting.
position_state_indexOption<usize>Index of the corresponding position state channel for position limit checks.

Custom Manifests

You can define custom manifests by constructing a ChannelManifest directly:
use roz_core::channels::{ChannelManifest, ChannelDescriptor, InterfaceType};

let manifest = ChannelManifest {
    robot_id: "my_robot".into(),
    robot_class: "manipulator".into(),
    control_rate_hz: 100,
    commands: vec![
        ChannelDescriptor {
            name: "joint0/velocity".into(),
            interface_type: InterfaceType::Velocity,
            unit: "rad/s".into(),
            limits: (-2.0, 2.0),
            default: 0.0,
            max_rate_of_change: Some(0.3),
            position_state_index: Some(0),
        },
    ],
    states: vec![
        ChannelDescriptor {
            name: "joint0/position".into(),
            interface_type: InterfaceType::Position,
            unit: "rad".into(),
            limits: (-6.28, 6.28),
            default: 0.0,
            max_rate_of_change: None,
            position_state_index: None,
        },
    ],
};

robot.toml

When using roz sim start, the sim container provides its channel manifest automatically. For custom robots, you can define the manifest in a robot.toml file:
[manifest]
robot_id = "my_robot"
robot_class = "manipulator"
control_rate_hz = 100

[[manifest.commands]]
name = "joint0/velocity"
interface_type = "velocity"
unit = "rad/s"
limits = [-2.0, 2.0]
default = 0.0
max_rate_of_change = 0.3
position_state_index = 0

[[manifest.states]]
name = "joint0/position"
interface_type = "position"
unit = "rad"
limits = [-6.28, 6.28]
default = 0.0

Source Code

Channel manifest definitions: crates/roz-core/src/channels.rs