HORUS C Bindings

** Under Development**: C bindings are currently in alpha and under active development.

  • Basic pub/sub operations work
  • Limited API coverage (minimal operations only)
  • Missing advanced features
  • API may change before v1.0

For production use, we recommend Rust or Python bindings.

See Roadmap for C bindings timeline.

Simple & Efficient C API for hardware driver integration - perfect for embedded systems, legacy code, and direct hardware access.

Why HORUS C?

  • Hardware-First: Direct sensor/actuator integration
  • Ultra-Low Latency: ~400ns IPC (same shared memory as Rust)
  • Simple API: Just init(), publisher(), send(), ok()
  • Zero Dependencies: Standard C99, works everywhere
  • Legacy-Friendly: Integrate existing C drivers seamlessly

Quick Start

Requirements

  • C99 compiler (GCC, Clang)
  • HORUS installed (cargo install horus)
  • Linux (for shared memory support)

Minimal Example

#include <horus.h>
#include <stdio.h>

int main() {
    // Initialize HORUS node
    if (!init("sensor_node")) {
        return 1;
    }

    // Create publisher
    Pub data_pub = publisher("temperature", MSG_CUSTOM);

    // Main loop
    while (ok()) {
        float temp = 25.5;
        send(data_pub, &temp);
        sleep_ms(1000);  // 1 Hz
    }

    shutdown();
    return 0;
}

Compile and run:

# HORUS automatically compiles and runs C files
horus run sensor.c

That's it! No manual compilation, no build system needed.


Core API Reference

Initialization & Lifecycle

init(node_name)

Initialize a HORUS node.

bool init(const char* node_name);

Parameters:

  • node_name: Unique name for this node

Returns: true on success, false on failure

Example:

if (!init("lidar_driver")) {
    fprintf(stderr, "Failed to initialize HORUS\n");
    return 1;
}

Must call before using any other HORUS functions.

ok()

Check if the node should continue running.

bool ok(void);

Returns: true if running, false if shutdown requested (e.g., Ctrl+C)

Example:

while (ok()) {
    // Main loop - exits cleanly on Ctrl+C
}

shutdown()

Clean up and shutdown the node.

void shutdown(void);

Example:

shutdown();
return 0;

Call before exiting - ensures proper cleanup of shared memory.


Publishing

publisher(topic, type)

Create a publisher for standard message types.

Pub publisher(const char* topic, MessageType type);

Parameters:

  • topic: Topic name (string)
  • type: Message type (see Message Types)

Returns: Publisher handle (Pub)

Example:

Pub cmd_pub = publisher("cmd_vel", MSG_TWIST);
Pub imu_pub = publisher("imu", MSG_IMU);

publisher_custom(topic, msg_size)

Create a publisher for custom data types.

Pub publisher_custom(const char* topic, size_t msg_size);

Parameters:

  • topic: Topic name
  • msg_size: Size of message in bytes

Returns: Publisher handle (Pub)

Example:

typedef struct {
    float voltage;
    float current;
} BatteryState;

Pub battery_pub = publisher_custom("battery", sizeof(BatteryState));

BatteryState state = {12.4, 2.3};
send(battery_pub, &state);

send(pub, data)

Publish a message.

bool send(Pub pub, const void* data);

Parameters:

  • pub: Publisher handle
  • data: Pointer to message data

Returns: true on success, false on failure

Performance: 296ns-2.8μs depending on message size

Example:

Twist cmd = {
    .linear = {1.0, 0.0, 0.0},
    .angular = {0.0, 0.0, 0.5}
};

if (send(cmd_pub, &cmd)) {
    log_debug("Published velocity command");
}

Subscribing

subscriber(topic, type)

Create a subscriber for standard message types.

Sub subscriber(const char* topic, MessageType type);

Parameters:

  • topic: Topic name
  • type: Message type

Returns: Subscriber handle (Sub)

Example:

Sub cmd_sub = subscriber("cmd_vel", MSG_TWIST);

subscriber_custom(topic, msg_size)

Create a subscriber for custom data types.

Sub subscriber_custom(const char* topic, size_t msg_size);

Parameters:

  • topic: Topic name
  • msg_size: Size of message in bytes

Returns: Subscriber handle (Sub)

Example:

typedef struct { float x, y; } Position;
Sub pos_sub = subscriber_custom("position", sizeof(Position));

recv(sub, data)

Receive a message (blocking until message available).

bool recv(Sub sub, void* data);

Parameters:

  • sub: Subscriber handle
  • data: Pointer to buffer for received data

Returns: true if message received, false on error

Blocks until a message is available. Use try_recv() for non-blocking.

Example:

Twist cmd;
if (recv(cmd_sub, &cmd)) {
    printf("Linear: %.2f, Angular: %.2f\n",
           cmd.linear.x, cmd.angular.z);
}

try_recv(sub, data)

Receive a message (non-blocking).

bool try_recv(Sub sub, void* data);

Parameters:

  • sub: Subscriber handle
  • data: Pointer to buffer for received data

Returns: true if message received, false if no message available

Non-blocking - returns immediately.

Example:

Pose pose;
while (ok()) {
    if (try_recv(pose_sub, &pose)) {
        process_pose(&pose);
    }

    // Do other work
    sleep_ms(10);
}

Timing & Control

sleep_ms(ms)

Sleep for specified milliseconds.

void sleep_ms(uint32_t ms);

Parameters:

  • ms: Milliseconds to sleep

Example:

while (ok()) {
    send(data_pub, &data);
    sleep_ms(100);  // 10 Hz
}

time_now_ms()

Get current time in milliseconds.

uint64_t time_now_ms(void);

Returns: Milliseconds since epoch

Example:

uint64_t start = time_now_ms();
process_data();
uint64_t elapsed = time_now_ms() - start;
printf("Processing took %llu ms\n", elapsed);

spin_once()

Process one cycle of callbacks (for subscriber-based nodes).

void spin_once(void);

Use when: Node only receives messages (no publishing loop)

spin()

Process callbacks indefinitely.

void spin(void);

Equivalent to: while(ok()) { spin_once(); sleep_ms(10); }


Logging

Log Functions

void log_info(const char* msg);
void log_warn(const char* msg);
void log_error(const char* msg);
void log_debug(const char* msg);

Example:

log_info("LiDAR driver initialized");
log_warn("Temperature high: 85C");
log_error("Failed to read sensor");
log_debug("Scan complete: 360 points");

Message Types

Standard Types

typedef enum {
    MSG_CUSTOM = 0,      // Custom user-defined type
    MSG_TWIST,           // Velocity (linear + angular)
    MSG_POSE,            // Position + orientation
    MSG_LASER_SCAN,      // LiDAR scan
    MSG_IMAGE,           // Camera image
    MSG_IMU,             // Inertial measurement
    MSG_JOINT_STATE,     // Robot joint positions
    MSG_POINT_CLOUD,     // 3D point cloud
} MessageType;

Common Structs

Vector3

typedef struct {
    float x, y, z;
} Vector3;

Example:

Vector3 velocity = {1.0, 0.0, 0.0};  // 1 m/s forward

Quaternion

typedef struct {
    float x, y, z, w;
} Quaternion;

Example:

Quaternion identity = {0.0, 0.0, 0.0, 1.0};  // No rotation

Twist (Velocity)

typedef struct {
    Vector3 linear;   // m/s
    Vector3 angular;  // rad/s
} Twist;

Example:

Twist cmd = {
    .linear = {1.0, 0.0, 0.0},   // Forward 1 m/s
    .angular = {0.0, 0.0, 0.5}   // Turn 0.5 rad/s
};

Pose (Position + Orientation)

typedef struct {
    Vector3 position;
    Quaternion orientation;
} Pose;

Example:

Pose robot_pose = {
    .position = {5.0, 3.0, 0.0},
    .orientation = {0.0, 0.0, 0.0, 1.0}
};

IMU

typedef struct {
    Vector3 linear_acceleration;  // m/s²
    Vector3 angular_velocity;     // rad/s
    Quaternion orientation;
    float covariance[9];          // 3x3 covariance matrix
} IMU;

Example:

IMU imu_data = {
    .linear_acceleration = {0.0, 0.0, 9.81},
    .angular_velocity = {0.01, -0.02, 0.0},
    .orientation = {0.0, 0.0, 0.0, 1.0},
    .covariance = {0.1, 0, 0, 0, 0.1, 0, 0, 0, 0.1}
};

LaserScan

typedef struct {
    float* ranges;           // Distance measurements (m)
    float* intensities;      // Reflection intensities
    uint32_t count;          // Number of measurements
    float angle_min;         // Start angle (rad)
    float angle_max;         // End angle (rad)
    float angle_increment;   // Angular resolution (rad)
    float range_min;         // Minimum range (m)
    float range_max;         // Maximum range (m)
    float scan_time;         // Time for full scan (s)
} LaserScan;

Example:

float ranges[360];
LaserScan scan = {
    .ranges = ranges,
    .intensities = NULL,
    .count = 360,
    .angle_min = 0.0,
    .angle_max = 2 * M_PI,
    .angle_increment = (2 * M_PI) / 360,
    .range_min = 0.1,
    .range_max = 10.0,
    .scan_time = 0.1
};

Image

typedef struct {
    uint8_t* data;       // Image pixel data
    uint32_t width;      // Image width (pixels)
    uint32_t height;     // Image height (pixels)
    uint32_t step;       // Bytes per row
    uint8_t channels;    // Color channels (1=gray, 3=RGB)
} Image;

Example:

uint8_t pixels[640 * 480 * 3];  // RGB image
Image img = {
    .data = pixels,
    .width = 640,
    .height = 480,
    .step = 640 * 3,
    .channels = 3
};

JointState

typedef struct {
    float* positions;    // Joint angles (rad)
    float* velocities;   // Joint velocities (rad/s)
    float* efforts;      // Joint torques (Nm)
    char** names;        // Joint names
    uint32_t count;      // Number of joints
} JointState;

Example:

float positions[] = {0.0, 1.57, -1.57, 0.0};
char* names[] = {"shoulder", "elbow", "wrist", "gripper"};

JointState state = {
    .positions = positions,
    .velocities = NULL,
    .efforts = NULL,
    .names = names,
    .count = 4
};

PointCloud

typedef struct {
    float* points;   // x,y,z packed array
    uint32_t count;  // Number of points
    uint32_t stride; // Bytes between points
} PointCloud;

Example:

float points[100 * 3];  // 100 points (x,y,z)
PointCloud cloud = {
    .points = points,
    .count = 100,
    .stride = sizeof(float) * 3
};

Complete Examples

1. Simple Publisher (Temperature Sensor)

#include <horus.h>
#include <stdio.h>

int main() {
    if (!init("temp_sensor")) {
        fprintf(stderr, "Failed to initialize\n");
        return 1;
    }

    Pub temp_pub = publisher_custom("temperature", sizeof(float));
    log_info("Temperature sensor started");

    float temperature = 20.0;

    while (ok()) {
        // Simulate temperature reading
        temperature += 0.1;

        if (send(temp_pub, &temperature)) {
            printf("Published: %.1f°C\n", temperature);
        }

        sleep_ms(1000);  // 1 Hz
    }

    shutdown();
    return 0;
}

2. Simple Subscriber (Display)

#include <horus.h>
#include <stdio.h>

int main() {
    if (!init("display")) {
        return 1;
    }

    Sub temp_sub = subscriber_custom("temperature", sizeof(float));
    log_info("Display started");

    while (ok()) {
        float temperature;
        if (try_recv(temp_sub, &temperature)) {
            printf("Temperature: %.1f°C\n", temperature);
        }
        sleep_ms(100);
    }

    shutdown();
    return 0;
}

3. LiDAR Driver

#include <horus.h>
#include <stdio.h>
#include <math.h>

int main() {
    if (!init("lidar_driver")) {
        return 1;
    }

    Pub scan_pub = publisher("laser_scan", MSG_LASER_SCAN);
    log_info("LiDAR driver started");

    // Allocate scan data
    float ranges[360];

    LaserScan scan = {
        .ranges = ranges,
        .intensities = NULL,
        .count = 360,
        .angle_min = 0.0,
        .angle_max = 2.0 * M_PI,
        .angle_increment = (2.0 * M_PI) / 360.0,
        .range_min = 0.1,
        .range_max = 10.0,
        .scan_time = 0.1
    };

    while (ok()) {
        // Read from hardware (simulated here)
        for (int i = 0; i < 360; i++) {
            float angle = (i * M_PI * 2.0) / 360.0;
            ranges[i] = 2.0 + sin(angle) * 0.5;
        }

        // Publish scan
        if (send(scan_pub, &scan)) {
            log_debug("Published scan");
        }

        sleep_ms(100);  // 10Hz
    }

    shutdown();
    return 0;
}

4. Motor Controller (Subscriber + Publisher)

#include <horus.h>
#include <stdio.h>

// Hardware abstraction
void set_motor_speed(float left, float right) {
    // Write to motor controller hardware
    printf("Motors: L=%.2f R=%.2f\n", left, right);
}

int main() {
    if (!init("motor_controller")) {
        return 1;
    }

    // Subscribe to velocity commands
    Sub cmd_sub = subscriber("cmd_vel", MSG_TWIST);

    // Publish motor status
    Pub status_pub = publisher_custom("motor_status", sizeof(int));

    log_info("Motor controller started");

    while (ok()) {
        Twist cmd;
        if (try_recv(cmd_sub, &cmd)) {
            // Convert Twist to wheel speeds
            float linear = cmd.linear.x;
            float angular = cmd.angular.z;

            float left = linear - angular;
            float right = linear + angular;

            set_motor_speed(left, right);

            int status = 1;  // Running
            send(status_pub, &status);
        }

        sleep_ms(10);  // 100Hz control loop
    }

    shutdown();
    return 0;
}

5. IMU Driver

#include <horus.h>
#include <stdio.h>
#include <math.h>

// Simulated hardware read
void read_imu_hardware(IMU* imu) {
    // In real code, read from I2C/SPI device
    imu->linear_acceleration = (Vector3){0.0, 0.0, 9.81};
    imu->angular_velocity = (Vector3){0.01, -0.02, 0.0};
    imu->orientation = (Quaternion){0.0, 0.0, 0.0, 1.0};
}

int main() {
    if (!init("imu_driver")) {
        return 1;
    }

    Pub imu_pub = publisher("imu", MSG_IMU);
    log_info("IMU driver started");

    IMU imu_data = {
        .covariance = {0.1, 0, 0, 0, 0.1, 0, 0, 0, 0.1}
    };

    while (ok()) {
        read_imu_hardware(&imu_data);

        if (send(imu_pub, &imu_data)) {
            log_debug("Published IMU data");
        }

        sleep_ms(10);  // 100Hz
    }

    shutdown();
    return 0;
}

6. Custom Message Type

#include <horus.h>
#include <stdio.h>

// Define custom message
typedef struct {
    float voltage;
    float current;
    float temperature;
    uint8_t status;
} BatteryState;

int main() {
    if (!init("battery_monitor")) {
        return 1;
    }

    Pub battery_pub = publisher_custom("battery", sizeof(BatteryState));
    log_info("Battery monitor started");

    while (ok()) {
        BatteryState state = {
            .voltage = 12.4,
            .current = 2.3,
            .temperature = 35.0,
            .status = 1  // OK
        };

        if (send(battery_pub, &state)) {
            printf("Battery: %.1fV, %.1fA, %.0f°C\n",
                   state.voltage, state.current, state.temperature);
        }

        sleep_ms(1000);  // 1Hz
    }

    shutdown();
    return 0;
}

Compilation & Deployment

HORUS CLI automatically compiles and runs C files:

# Just run it - HORUS handles compilation
horus run sensor_driver.c

# With command-line arguments
horus run motor_controller.c --device /dev/ttyUSB0

Features:

  • Automatic dependency detection
  • Shared library linking
  • Incremental compilation (caching)
  • Debug and release modes

Manual Compilation

If you need manual control:

# Compile with HORUS library
gcc -o driver sensor_driver.c \
    -I.horus/include \
    -L/path/to/horus/target/release \
    -lhorus_c -lpthread -lm

# Run normally
./driver

Include path: HORUS creates .horus/include/horus.h automatically when you run horus init

Build Flags

# Debug build (faster compile, slower runtime)
horus run sensor.c

# Release build (optimized)
horus run sensor.c --release

# With math library
horus run lidar.c --libs m

# Custom flags
horus run driver.c --cflags "-O3 -march=native"

Integration Patterns

Hardware Abstraction Layer

#include <horus.h>

// HAL interface
typedef struct {
    void (*init)(void);
    float (*read)(void);
    void (*shutdown)(void);
} SensorHAL;

// LiDAR HAL implementation
void lidar_init(void) { /* hardware init */ }
float lidar_read(void) { /* read range */ return 2.5; }
void lidar_shutdown(void) { /* cleanup */ }

SensorHAL lidar_hal = {
    .init = lidar_init,
    .read = lidar_read,
    .shutdown = lidar_shutdown
};

int main() {
    init("lidar_node");
    lidar_hal.init();

    Pub range_pub = publisher_custom("range", sizeof(float));

    while (ok()) {
        float range = lidar_hal.read();
        send(range_pub, &range);
        sleep_ms(100);
    }

    lidar_hal.shutdown();
    shutdown();
    return 0;
}

Multi-Sensor Fusion

#include <horus.h>

typedef struct {
    float range;
    float bearing;
    uint64_t timestamp;
} SensorReading;

int main() {
    init("fusion_node");

    Sub lidar_sub = subscriber_custom("lidar", sizeof(float));
    Sub radar_sub = subscriber_custom("radar", sizeof(float));
    Pub fused_pub = publisher_custom("fused", sizeof(SensorReading));

    while (ok()) {
        float lidar_range, radar_range;

        if (try_recv(lidar_sub, &lidar_range) &&
            try_recv(radar_sub, &radar_range)) {

            // Sensor fusion algorithm
            SensorReading fused = {
                .range = (lidar_range + radar_range) / 2.0,
                .bearing = 0.0,
                .timestamp = time_now_ms()
            };

            send(fused_pub, &fused);
        }

        sleep_ms(10);
    }

    shutdown();
    return 0;
}

Periodic Task Pattern

#include <horus.h>

int main() {
    init("periodic_task");

    Pub heartbeat_pub = publisher_custom("heartbeat", sizeof(uint64_t));

    uint64_t last_publish = time_now_ms();
    uint64_t interval_ms = 1000;  // 1 second

    while (ok()) {
        uint64_t now = time_now_ms();

        if (now - last_publish >= interval_ms) {
            send(heartbeat_pub, &now);
            last_publish = now;
        }

        sleep_ms(10);  // Check every 10ms
    }

    shutdown();
    return 0;
}

Performance Tips

1. Minimize Message Size

// Good - fixed size
typedef struct {
    float x, y;
    uint16_t status;
} CompactMsg;  // 10 bytes

// Less ideal - larger message
typedef struct {
    double x, y, z;
    char description[256];
} LargeMsg;  // 280 bytes

2. Batch Processing

// Process multiple readings before publishing
float readings[10];
int count = 0;

while (ok()) {
    readings[count++] = read_sensor();

    if (count == 10) {
        // Send batch
        send(batch_pub, readings);
        count = 0;
    }
}

3. Use Stack Allocation

// Good - stack allocated
float ranges[360];
LaserScan scan = {.ranges = ranges, .count = 360};

// Avoid - heap allocation (slower)
float* ranges = malloc(360 * sizeof(float));

4. Efficient Loops

// Keep tick functions fast
while (ok()) {
    // Fast operations only
    if (try_recv(sub, &data)) {
        quick_process(data);
        send(pub, &result);
    }
    sleep_ms(10);
}

Error Handling

Robust Initialization

#include <horus.h>
#include <stdio.h>

int main() {
    if (!init("my_node")) {
        fprintf(stderr, "ERROR: Failed to initialize HORUS\n");
        fprintf(stderr, "Is HORUS installed? Run: cargo install horus\n");
        return 1;
    }

    Pub pub = publisher("topic", MSG_CUSTOM);
    if (pub == 0) {  // Invalid handle
        log_error("Failed to create publisher");
        shutdown();
        return 1;
    }

    log_info("Node started successfully");

    // Main loop...

    shutdown();
    return 0;
}

Send Error Handling

int retry_count = 0;
const int MAX_RETRIES = 3;

while (ok()) {
    if (!send(pub, &data)) {
        retry_count++;
        log_warn("Send failed, retrying...");

        if (retry_count >= MAX_RETRIES) {
            log_error("Send failed after retries");
            break;
        }

        sleep_ms(100);
        continue;
    }

    retry_count = 0;  // Reset on success
    sleep_ms(1000);
}

Troubleshooting

Compilation Errors

Problem: horus.h: No such file or directory

Solution: Run horus init in your project directory to generate .horus/include/horus.h

horus init
horus run sensor.c

Problem: undefined reference to 'init'

Solution: Use horus run instead of direct compilation, or link against -lhorus_c

# Correct
horus run sensor.c

# Manual (if needed)
gcc sensor.c -I.horus/include -lhorus_c -lpthread

Runtime Errors

Problem: init() returns false

Causes:

  • HORUS not installed
  • Shared memory permissions
  • Node name conflicts

Solution:

# Check HORUS installation
horus --version

# Check shared memory
ls -la /dev/shm/horus_*

# Use unique node name
if (!init("unique_node_name_123")) {
    // ...
}

Problem: Messages not received

Debug checklist:

  1. Publisher and subscriber use same topic name
  2. Message types match
  3. Publisher actually sending (send() returns true)
  4. Subscriber checking frequently enough
// Add debug logging
if (send(pub, &data)) {
    log_debug("Sent successfully");
} else {
    log_error("Send failed!");
}

if (try_recv(sub, &data)) {
    log_debug("Received message");
}

Interoperability

With Rust Nodes

C and Rust nodes communicate seamlessly:

// C publisher
Twist cmd = {.linear = {1.0, 0.0, 0.0}, .angular = {0.0, 0.0, 0.5}};
send(cmd_pub, &cmd);
// Rust subscriber
let cmd: Twist = hub.recv(ctx);

With Python Nodes

// C hardware driver
float temperature = read_sensor();
send(temp_pub, &temperature);
# Python processing
if node.has_msg("temperature"):
    temp = node.get("temperature")
    print(f"Temperature: {temp}°C")

All languages use the same shared memory - no serialization overhead!


Best Practices

1. Initialization Order

int main() {
    // 1. Init HORUS first
    if (!init("node")) return 1;

    // 2. Create publishers/subscribers
    Pub pub = publisher("topic", MSG_CUSTOM);
    Sub sub = subscriber("input", MSG_CUSTOM);

    // 3. Initialize hardware
    hardware_init();

    // 4. Main loop
    while (ok()) {
        // ...
    }

    // 5. Cleanup
    hardware_shutdown();
    shutdown();
    return 0;
}

2. Use Meaningful Names

// Good
init("lidar_front");
publisher("scan/front", MSG_LASER_SCAN);

// Bad
init("node1");
publisher("data", MSG_CUSTOM);

3. Check Return Values

// Always check critical operations
if (!init("node")) return 1;
if (!send(pub, &data)) log_error("Send failed");

4. Clean Shutdown

// Handle Ctrl+C gracefully
while (ok()) {  // ok() returns false on SIGINT
    // Work...
}

// Cleanup runs automatically
shutdown();

See Also


Remember: HORUS C API is designed for hardware integration - simple, fast, and direct!