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.
Primitive Types
- Numeric Types
- Variable-Length Types
- Array Types
| ROS2 Type | Rust Type | Size |
|---|---|---|
bool | bool | 1 byte |
int8 / byte | i8 | 1 byte |
uint8 / char | u8 | 1 byte |
int16 | i16 | 2 bytes |
uint16 | u16 | 2 bytes |
int32 | i32 | 4 bytes |
uint32 | u32 | 4 bytes |
int64 | i64 | 8 bytes |
uint64 | u64 | 8 bytes |
float32 | f32 | 4 bytes |
float64 | f64 | 8 bytes |
Nested Types
Any message type can reference another message type:| Syntax | Description | Example |
|---|---|---|
pkg/MsgType | Message from another package | geometry_msgs/Point |
MsgType | Message in same package | Quaternion |
Available Message Packages
builtin_interfaces
builtin_interfaces
Core time primitives used throughout the system.
| Message | Fields | Description |
|---|---|---|
| Time | int32 sec, uint32 nanosec | Point in time relative to clock epoch |
| Duration | int32 sec, uint32 nanosec | Time duration (can be negative) |
std_msgs
std_msgs
Standard message types and building blocks.
| Message | Key Fields | Description |
|---|---|---|
| Header | stamp: Time, frame_id: string | Standard metadata for stamped data |
| Bool | data: bool | Single boolean value |
| String | data: string | String wrapper |
| Int8/16/32/64 | data: intN | Signed integer wrappers |
| UInt8/16/32/64 | data: uintN | Unsigned integer wrappers |
| Float32/64 | data: floatN | Float wrappers |
| ColorRGBA | r, g, b, a: float32 | RGBA color |
| Empty | (none) | Empty message for signals |
geometry_msgs
geometry_msgs
Geometric primitives for robotics.
| Message | Fields | Description |
|---|---|---|
| Point | x, y, z: float64 | 3D point position |
| Point32 | x, y, z: float32 | 3D point (single precision) |
| Vector3 | x, y, z: float64 | 3D vector |
| Quaternion | x, y, z, w: float64 | Orientation quaternion |
| Pose | position: Point, orientation: Quaternion | Position + orientation |
| Pose2D | x, y, theta: float64 | 2D pose |
| PoseStamped | header: Header, pose: Pose | Timestamped pose |
| PoseArray | header: Header, poses: Pose[] | Array of poses |
| PoseWithCovariance | pose: Pose, covariance: float64[36] | Pose with 6x6 uncertainty |
| Transform | translation: Vector3, rotation: Quaternion | 3D transform |
| TransformStamped | header, child_frame_id, transform | Stamped transform |
| Twist | linear: Vector3, angular: Vector3 | Linear + angular velocity |
| TwistStamped | header: Header, twist: Twist | Timestamped velocity |
| TwistWithCovariance | twist: Twist, covariance: float64[36] | Velocity with uncertainty |
| Accel | linear: Vector3, angular: Vector3 | Linear + angular acceleration |
| Wrench | force: Vector3, torque: Vector3 | Force + torque |
| Inertia | m: float64, com: Vector3, ixx,ixy,... | Mass + inertia tensor |
| Polygon | points: Point32[] | 2D polygon |
sensor_msgs
sensor_msgs
Sensor data types.
| Message | Key Fields | Description |
|---|---|---|
| Image | header, height, width, encoding, data[] | Uncompressed image |
| CompressedImage | header, format, data[] | Compressed image (JPEG/PNG) |
| CameraInfo | header, height, width, K/D/R/P matrices | Camera calibration |
| Imu | header, orientation, angular_velocity, linear_acceleration | IMU data |
| LaserScan | header, angles, ranges, ranges[], intensities[] | 2D lidar scan |
| PointCloud2 | header, height, width, fields[], data[] | 3D point cloud |
| PointField | name, offset, datatype, count | Point cloud field descriptor |
| JointState | header, name[], position[], velocity[], effort[] | Robot joint states |
| NavSatFix | header, status, latitude, longitude, altitude | GPS fix |
| Range | header, radiation_type, field_of_view, range | Distance sensor |
| Temperature | header, temperature, variance | Temperature reading |
| BatteryState | header, voltage, current, charge, percentage | Battery status |
| Joy | header, axes[], buttons[] | Joystick input |
nav_msgs
nav_msgs
shape_msgs
shape_msgs
Shape primitives.
| Message | Fields | Description |
|---|---|---|
| Mesh | triangles[], vertices[] | Triangle mesh |
| MeshTriangle | vertex_indices: uint32[3] | Single triangle |
| Plane | coef: float64[4] | Plane equation (ax+by+cz+d=0) |
| SolidPrimitive | type, dimensions[], polygon | Box/sphere/cylinder/cone |
diagnostic_msgs
diagnostic_msgs
System diagnostics.
| Message | Fields | Description |
|---|---|---|
| DiagnosticArray | header, status[] | Array of diagnostic statuses |
| DiagnosticStatus | level, name, message, hardware_id, values[] | Single diagnostic |
| KeyValue | key, value | Key-value pair |
Usage Examples
Creating and Populating Messages
Working with Arrays
Building Custom Message Types
Workspace Structure
my-workspace
msg
custom_msgs
RobotState.msg
SensorData.msg
nodes
Cargo.toml
Step 1: Create a .msg File
Step 2: Message Syntax Rules
Step 3: Build Process
Step 4: Use Your Custom Message
Generated Type Patterns
- Fixed-Size Messages
- Variable-Size Messages
Messages with only primitive fields:
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
Primitive Sizes
| Type | Wire Size |
|---|---|
bool | 1 byte |
int8/uint8 | 1 byte |
int16/uint16 | 2 bytes |
int32/uint32/float32 | 4 bytes |
int64/uint64/float64 | 8 bytes |
Message Traits
All generated messages implement these traits:Fixed-size messages implementing
FixedMessage can use zero-copy shared memory transport, achieving sub-microsecond latency.Best Practices
Use fixed arrays for known sizes
Use fixed arrays for known sizes
float64[9] is more efficient than float64[]. Fixed arrays are stored inline and enable zero-copy transport.Prefer nested types over duplicating fields
Prefer nested types over duplicating fields
Compose from existing messages rather than duplicating fields. This ensures consistency and enables better tooling support.
Include Header for timestamps
Include Header for timestamps
Most sensor data should include a
std_msgs/Header for timing and frame information.Use covariance matrices for uncertainty
Use covariance matrices for uncertainty
Include 6x6 covariance for pose (
float64[36]) or 3x3 for orientation (float64[9]) when uncertainty information is available.Place variable data last
Place variable data last
Put dynamic arrays and strings at the end of message definitions for better serialization performance.