POD Types and Zero-Serialization

When you use Topic<T>, HORUS automatically detects whether your message type is POD (Plain Old Data). POD types bypass serialization entirely — messages are transferred as raw bytes via direct memory copy, achieving ~50ns latency instead of ~167ns with bincode serialization.

You don't need a separate API. The same Topic::new() call automatically selects the fastest path for your type.

How Auto-Detection Works

At topic creation time, HORUS checks whether your type is POD:

  • No destructor — The type has no Drop impl (no heap pointers like String, Vec, Box)
  • Non-zero size — Not a zero-sized type

If both are true, HORUS uses the zero-copy memcpy path. If not, it falls back to bincode serialization. This happens transparently — you always use the same Topic<T> API:

use horus::prelude::*;

// POD type - auto-detected, uses zero-copy memcpy (~50ns cross-process)
let cmd_topic: Topic<CmdVel> = Topic::new("cmd_vel")?;
cmd_topic.send(CmdVel::new(1.0, 0.5));

// Non-POD type - auto-detected, uses bincode serialization (~167ns cross-process)
let log_topic: Topic<String> = Topic::new("log")?;
log_topic.send("Motor started".to_string());

Performance Impact

POD detection affects cross-process performance:

TypeCross-Process LatencyNotes
POD (e.g. CmdVel, Imu)~50-85nsZero-serialization, raw memory copy
Non-POD (e.g. String, Vec)~167nsBincode serialization

Same-process communication is fast for both POD and non-POD types since no shared memory serialization is needed.

Built-in POD Messages

All standard HORUS message types implement PodMessage and automatically use the fast path:

Geometry

MessageDescription
CmdVel2D velocity command (linear + angular)
Pose2D2D position and orientation
Twist3D linear and angular velocity
TransformStamped3D transformation with timestamp
Point33D point
Vector33D vector
QuaternionRotation quaternion

Sensors

MessageDescription
ImuInertial measurement unit data
LaserScan2D laser range data
OdometryPosition/velocity estimate
RangeSingle distance measurement
BatteryStateBattery level and status
NavSatFixGPS position

Control

MessageDescription
MotorCommandIndividual motor control
DifferentialDriveCommandDifferential drive control
ServoCommandServo position/velocity
JointCommandJoint-level control
TrajectoryPointTrajectory waypoint
PidConfigPID controller parameters

Diagnostics

MessageDescription
HeartbeatLiveness signal
NodeHeartbeatPer-node health status
StatusGeneral status report
EmergencyStopEmergency stop signal
SafetyStatusSafety system state
ResourceUsageCPU/memory usage
DiagnosticValueSingle diagnostic measurement
DiagnosticReportFull diagnostic report
MessageDescription
GoalNavigation goal
GoalResultGoal completion result
WaypointNavigation waypoint
PathSequence of waypoints
PathPlanPlanned path
VelocityObstacleVelocity obstacle for avoidance
VelocityObstaclesSet of velocity obstacles

Force/Haptics

MessageDescription
WrenchStampedForce/torque measurement
ForceCommandForce control command
ImpedanceParametersImpedance control config
ContactInfoContact detection data
HapticFeedbackHaptic output command

Input

MessageDescription
JoystickInputGamepad/joystick state
KeyboardInputKeyboard key events

Tensor

MessageDescription
TensorFixed-size tensor descriptor
use horus::prelude::*;

// All built-in messages are POD — fast path is automatic
let cmd: Topic<CmdVel> = Topic::new("cmd_vel")?;
let pose: Topic<Pose2D> = Topic::new("robot_pose")?;
let imu: Topic<Imu> = Topic::new("imu_data")?;
let estop: Topic<EmergencyStop> = Topic::new("emergency_stop")?;

Custom POD Messages

To make your own types use the fast path, implement the PodMessage trait:

Requirements

  1. #[repr(C)] — C-compatible memory layout (prevents Rust from reordering fields)
  2. Copy + Clone — Bitwise copyable, no heap allocations
  3. Pod + Zeroable — Safe to cast to/from bytes (from bytemuck crate)
  4. Fixed size — Size known at compile time (no Vec, String, or other dynamic types)

Example

use horus::prelude::*;
use bytemuck::{Pod, Zeroable};

#[repr(C)]
#[derive(Clone, Copy, Debug, Default, serde::Serialize, serde::Deserialize)]
pub struct MotorFeedback {
    pub timestamp_ns: u64,    // 8 bytes
    pub motor_id: u32,        // 4 bytes
    pub velocity: f32,        // 4 bytes
    pub current_amps: f32,    // 4 bytes
    pub temperature_c: f32,   // 4 bytes
}

// bytemuck traits for safe byte casting
unsafe impl Zeroable for MotorFeedback {}
unsafe impl Pod for MotorFeedback {}

// HORUS PodMessage trait for ultra-fast IPC
unsafe impl PodMessage for MotorFeedback {}

// Now Topic<MotorFeedback> automatically uses the POD fast path
let feedback: Topic<MotorFeedback> = Topic::new("motor.feedback")?;
feedback.send(MotorFeedback {
    timestamp_ns: 0,
    motor_id: 1,
    velocity: 3.14,
    current_amps: 0.5,
    temperature_c: 45.0,
});

Important: Custom POD types also need Clone + Serialize + DeserializeOwned since Topic<T> requires these bounds. The serialization traits are used as a fallback if the type ever goes through a non-POD code path (e.g., logging).

Rules for POD Safety

The PodMessage trait is unsafe because incorrect implementations can cause data corruption. Ensure:

  • No pointers or references — Only use primitive types (u8..u64, f32, f64, bool) and fixed-size arrays of primitives
  • No enums with discriminants — Unless #[repr(C)] or #[repr(u8)] with explicit values
  • Consistent layout — The struct must have the same binary layout on all target platforms
  • No implicit padding — Use explicit padding fields (_pad: [u8; N]) if needed

When Types Are Not POD

Types containing heap-allocated data are automatically detected as non-POD:

// These are NOT POD - HORUS auto-detects and uses bincode serialization
Topic<String>        // String has Drop (heap-allocated)
Topic<Vec<f32>>      // Vec has Drop (heap-allocated)
Topic<HashMap<K,V>>  // HashMap has Drop

Non-POD types use bincode serialization through shared memory. This is still fast (~167ns cross-process) but ~3x slower than the POD path. For most applications, this difference is negligible — only optimize to POD for control loops running at 1kHz+ where every nanosecond matters.

See Also

  • Topic — The unified communication API
  • Message Types — Full message type reference
  • Architecture — How communication fits into the HORUS architecture