Skip to main content

Overview

Cerulion uses ROS2-compatible message definitions for type-safe communication between nodes. Whether you need to send sensor readings, camera frames, or robot state, these messages work seamlessly with both local (zero-copy) and network transport. Message definitions are automatically parsed from .msg files and compiled into zero-copy Rust types at build time.
use cerulion_core_v2::prelude::*;

// Create a timestamped pose
let mut pose_stamped = PoseStamped::new();
pose_stamped.set_header(header);
pose_stamped.set_pose(pose);

Primitive Types

ROS2 TypeRust TypeSize
boolbool1 byte
int8 / bytei81 byte
uint8 / charu81 byte
int16i162 bytes
uint16u162 bytes
int32i324 bytes
uint32u324 bytes
int64i648 bytes
uint64u648 bytes
float32f324 bytes
float64f648 bytes

Nested Types

Any message type can reference another message type:
SyntaxDescriptionExample
pkg/MsgTypeMessage from another packagegeometry_msgs/Point
MsgTypeMessage in same packageQuaternion

Available Message Packages

builtin_interfaces

Core time primitives used throughout the system.
MessageFieldsDescription
Timeint32 sec, uint32 nanosecPoint in time relative to clock epoch
Durationint32 sec, uint32 nanosecTime duration (can be negative)
let mut stamp = Time::new();
stamp.set_sec(1704067200);
stamp.set_nanosec(500_000_000);
Standard message types and building blocks.
MessageKey FieldsDescription
Headerstamp: Time, frame_id: stringStandard metadata for stamped data
Booldata: boolSingle boolean value
Stringdata: stringString wrapper
Int8/16/32/64data: intNSigned integer wrappers
UInt8/16/32/64data: uintNUnsigned integer wrappers
Float32/64data: floatNFloat wrappers
ColorRGBAr, g, b, a: float32RGBA color
Empty(none)Empty message for signals
let mut header = Header::new();
header.set_stamp(stamp);
header.set_frame_id("base_link");
Geometric primitives for robotics.
MessageFieldsDescription
Pointx, y, z: float643D point position
Point32x, y, z: float323D point (single precision)
Vector3x, y, z: float643D vector
Quaternionx, y, z, w: float64Orientation quaternion
Poseposition: Point, orientation: QuaternionPosition + orientation
Pose2Dx, y, theta: float642D pose
PoseStampedheader: Header, pose: PoseTimestamped pose
PoseArrayheader: Header, poses: Pose[]Array of poses
PoseWithCovariancepose: Pose, covariance: float64[36]Pose with 6x6 uncertainty
Transformtranslation: Vector3, rotation: Quaternion3D transform
TransformStampedheader, child_frame_id, transformStamped transform
Twistlinear: Vector3, angular: Vector3Linear + angular velocity
TwistStampedheader: Header, twist: TwistTimestamped velocity
TwistWithCovariancetwist: Twist, covariance: float64[36]Velocity with uncertainty
Accellinear: Vector3, angular: Vector3Linear + angular acceleration
Wrenchforce: Vector3, torque: Vector3Force + torque
Inertiam: float64, com: Vector3, ixx,ixy,...Mass + inertia tensor
Polygonpoints: Point32[]2D polygon
// Simple point
let mut point = Point::new();
point.set_x(1.0);
point.set_y(2.0);
point.set_z(3.0);

// Velocity command
let mut twist = Twist::new();
let mut linear = Vector3::new();
linear.set_x(1.0);
twist.set_linear(linear);
Sensor data types.
MessageKey FieldsDescription
Imageheader, height, width, encoding, data[]Uncompressed image
CompressedImageheader, format, data[]Compressed image (JPEG/PNG)
CameraInfoheader, height, width, K/D/R/P matricesCamera calibration
Imuheader, orientation, angular_velocity, linear_accelerationIMU data
LaserScanheader, angles, ranges, ranges[], intensities[]2D lidar scan
PointCloud2header, height, width, fields[], data[]3D point cloud
PointFieldname, offset, datatype, countPoint cloud field descriptor
JointStateheader, name[], position[], velocity[], effort[]Robot joint states
NavSatFixheader, status, latitude, longitude, altitudeGPS fix
Rangeheader, radiation_type, field_of_view, rangeDistance sensor
Temperatureheader, temperature, varianceTemperature reading
BatteryStateheader, voltage, current, charge, percentageBattery status
Joyheader, axes[], buttons[]Joystick input
// Create an RGB image
let pixel_data = vec![0u8; 640 * 480 * 3];

let mut image = Image::new();
image.set_height(480);
image.set_width(640);
image.set_encoding("rgb8");
image.set_step(640 * 3);
image.set_data(pixel_data);
Shape primitives.
MessageFieldsDescription
Meshtriangles[], vertices[]Triangle mesh
MeshTrianglevertex_indices: uint32[3]Single triangle
Planecoef: float64[4]Plane equation (ax+by+cz+d=0)
SolidPrimitivetype, dimensions[], polygonBox/sphere/cylinder/cone
System diagnostics.
MessageFieldsDescription
DiagnosticArrayheader, status[]Array of diagnostic statuses
DiagnosticStatuslevel, name, message, hardware_id, values[]Single diagnostic
KeyValuekey, valueKey-value pair

Usage Examples

Creating and Populating Messages

use cerulion_core_v2::prelude::*;

// Simple fixed-size message
let mut point = Point::new();
point.set_x(1.0);
point.set_y(2.0);
point.set_z(3.0);

// Direct field access (for fixed types)
assert_eq!(point.x, 1.0);

// Nested messages
let mut stamp = Time::new();
stamp.set_sec(1704067200);
stamp.set_nanosec(500_000_000);

let mut header = Header::new();
header.set_stamp(stamp);
header.set_frame_id("base_link");

// Composing complex messages
let mut orientation = Quaternion::new();
orientation.set_w(1.0); // Identity quaternion

let mut pose = Pose::new();
pose.set_position(point);
pose.set_orientation(orientation);

let mut pose_stamped = PoseStamped::new();
pose_stamped.set_header(header);
pose_stamped.set_pose(pose);

Working with Arrays

use cerulion_core_v2::prelude::*;

// Dynamic array of nested types
let mut poses = Vec::new();
for i in 0..10 {
    let mut p = Pose::new();
    let mut pos = Point::new();
    pos.set_x(i as f64);
    p.set_position(pos);
    poses.push(p);
}

let mut pose_array = PoseArray::new();
pose_array.set_poses(poses);

// Fixed-size arrays (covariance matrices)
let mut imu = Imu::new();
// 3x3 covariance matrix stored as row-major array
let orientation_cov = [
    0.01, 0.0, 0.0,  // row 1
    0.0, 0.01, 0.0,  // row 2
    0.0, 0.0, 0.01,  // row 3
];
imu.set_orientation_covariance(orientation_cov);

Building Custom Message Types

Workspace Structure

my-workspace
msg
custom_msgs
RobotState.msg
SensorData.msg
Cargo.toml

Step 1: Create a .msg File

# msg/custom_msgs/RobotState.msg

# Custom robot state message
std_msgs/Header header
string robot_name
geometry_msgs/Pose pose
geometry_msgs/Twist velocity
float64[6] joint_positions
float64[] sensor_readings
uint8 status
bool is_active

Step 2: Message Syntax Rules

# Comments start with #
fieldtype fieldname [default_value]

# Examples:
float64 x                    # Simple primitive
string name                  # Variable-length string
uint8[] data                 # Dynamic array
float64[9] covariance        # Fixed array (9 elements)
geometry_msgs/Pose pose      # Nested type from another package
Header header                # Nested type (std_msgs implied)
uint8 STATUS_OK=1            # Constants

Step 3: Build Process

Step 4: Use Your Custom Message

use your_workspace::custom_msgs::RobotState;

let mut state = RobotState::new();
state.set_robot_name("arm_01");
state.set_status(1);
state.set_is_active(true);
state.set_joint_positions([0.0, 0.5, 1.0, 0.0, -0.5, 0.0]);
state.set_sensor_readings(vec![1.2, 3.4, 5.6]);

Generated Type Patterns

Messages with only primitive fields:
// Generated from Point.msg
#[repr(C)]
#[derive(Debug, Clone, Copy, PartialEq, Default)]
pub struct Point {
    pub x: f64,
    pub y: f64,
    pub z: f64,
}

impl Point {
    pub fn new() -> Self {
        Self::default()
    }
    pub fn set_x(&mut self, value: f64) -> &mut Self { ... }
}

// View is just a reference (zero-copy)
pub type PointView<'a> = &'a Point;
Zero-copy transport enabled

Wire Format

All primitives use little-endian byte order.

Variable-Length Encoding

Strings and dynamic arrays include a 4-byte length prefix:

Array Encoding

Fixed arrays (T[N]) have no length prefix — size is known at compile time.

Primitive Sizes

TypeWire Size
bool1 byte
int8/uint81 byte
int16/uint162 bytes
int32/uint32/float324 bytes
int64/uint64/float648 bytes

Message Traits

All generated messages implement these traits:
pub trait Message {
    const SCHEMA_HASH: u64;
    fn wire_size(&self) -> usize;
    fn write_to_buffer(&self, buffer: &mut [u8]);
}

// Additional trait for fixed-size messages
pub trait FixedMessage: Message {
    const WIRE_SIZE: usize;
}
Fixed-size messages implementing FixedMessage can use zero-copy shared memory transport, achieving sub-microsecond latency.

Best Practices

Use fixed arrays for known sizes

float64[9] is more efficient than float64[]. Fixed arrays are stored inline and enable zero-copy transport.
Compose from existing messages rather than duplicating fields. This ensures consistency and enables better tooling support.
Most sensor data should include a std_msgs/Header for timing and frame information.
Include 6x6 covariance for pose (float64[36]) or 3x3 for orientation (float64[9]) when uncertainty information is available.
Put dynamic arrays and strings at the end of message definitions for better serialization performance.

Next Steps