rosz

package
v0.0.0-...-d56d283 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Feb 26, 2026 License: Apache-2.0 Imports: 10 Imported by: 0

Documentation

Overview

Package rosz provides Go bindings for ros-z, a Zenoh-native ROS 2 implementation.

The package supports pub/sub with automatic CDR serialization, builder-pattern resource creation, and idempotent cleanup.

All resource types (Context, Node, Publisher, Subscriber) must be closed after use. Each type's Close() method is idempotent and safe to call multiple times.

Callbacks registered with BuildWithCallback are invoked on C/Rust threads. Avoid long blocking operations in callbacks to prevent stalling the Zenoh runtime.

Index

Constants

This section is empty.

Variables

View Source
var (
	// ErrBuildFailed is returned when a builder's Build() call fails (FFI returned null pointer).
	// Use errors.Is(err, rosz.ErrBuildFailed) to detect construction failures.
	ErrBuildFailed = NewRoszError(ErrorCodeBuildFailed, "failed to build entity")
)

Sentinel errors for common failure modes

Functions

func DeserializeMessage

func DeserializeMessage(typeName string, cdr []byte) ([]byte, error)

DeserializeMessage deserializes CDR bytes to raw format using Rust

func SerializeMessage

func SerializeMessage(typeName string, raw []byte) ([]byte, error)

SerializeMessage serializes raw bytes to CDR using Rust

Types

type Closure

type Closure[T any] struct {
	// contains filtered or unexported fields
}

Closure wraps a direct callback function for message handling. This is the default handler type used by BuildWithCallback().

func NewClosure

func NewClosure[T any](call func(T), drop func()) *Closure[T]

NewClosure creates a callback-based handler.

func (*Closure[T]) ToCbDropHandler

func (c *Closure[T]) ToCbDropHandler() (func(T), func(), <-chan T)

ToCbDropHandler returns the callback and drop functions with no channel.

type Context

type Context struct {
	// contains filtered or unexported fields
}

Context represents a ros-z context

func (*Context) Close

func (c *Context) Close() error

Close shuts down the context

func (*Context) CreateNode

func (c *Context) CreateNode(name string) *NodeBuilder

CreateNode creates a new node builder

func (*Context) GetNodeNames

func (c *Context) GetNodeNames() ([]NodeInfo, error)

GetNodeNames returns all nodes visible in the ROS graph

func (*Context) GetTopicNamesAndTypes

func (c *Context) GetTopicNamesAndTypes() ([]TopicInfo, error)

GetTopicNamesAndTypes returns all topics visible in the ROS graph

func (*Context) NodeExists

func (c *Context) NodeExists(name, namespace string) (bool, error)

NodeExists checks if a node with the given name and namespace exists in the graph

type ContextBuilder

type ContextBuilder struct {
	// contains filtered or unexported fields
}

ContextBuilder builds a Context

func NewContext

func NewContext() *ContextBuilder

NewContext creates a new context builder

func (*ContextBuilder) Build

func (b *ContextBuilder) Build() (*Context, error)

Build creates the context

func (*ContextBuilder) ConnectToLocalZenohd

func (b *ContextBuilder) ConnectToLocalZenohd() *ContextBuilder

ConnectToLocalZenohd connects to a local zenohd on tcp/127.0.0.1:7447

func (*ContextBuilder) DisableMulticastScouting

func (b *ContextBuilder) DisableMulticastScouting() *ContextBuilder

DisableMulticastScouting disables multicast scouting (useful in Docker/cloud)

func (*ContextBuilder) WithConfigFile

func (b *ContextBuilder) WithConfigFile(path string) *ContextBuilder

WithConfigFile loads Zenoh configuration from a JSON5 file

func (*ContextBuilder) WithConnectEndpoints

func (b *ContextBuilder) WithConnectEndpoints(endpoints ...string) *ContextBuilder

WithConnectEndpoints sets Zenoh connect endpoints

func (*ContextBuilder) WithDomainID

func (b *ContextBuilder) WithDomainID(id uint32) *ContextBuilder

WithDomainID sets the ROS domain ID

func (*ContextBuilder) WithJSON

func (b *ContextBuilder) WithJSON(jsonStr string) *ContextBuilder

WithJSON passes arbitrary Zenoh configuration as a JSON string. The string must be a JSON object with dotted keys. Example: `{"scouting/multicast/enabled": false}`

func (*ContextBuilder) WithLogging

func (b *ContextBuilder) WithLogging() *ContextBuilder

WithLogging enables Zenoh logging initialization

func (*ContextBuilder) WithMode

func (b *ContextBuilder) WithMode(mode ZenohMode) *ContextBuilder

WithMode sets the Zenoh session mode

func (*ContextBuilder) WithRemapRule

func (b *ContextBuilder) WithRemapRule(rule string) *ContextBuilder

WithRemapRule adds a name remapping rule in "from:=to" format

func (*ContextBuilder) WithRemapRules

func (b *ContextBuilder) WithRemapRules(rules ...string) *ContextBuilder

WithRemapRules adds multiple name remapping rules

type Duration

type Duration struct {
	Sec  int32
	Nsec uint32
}

Duration represents a ROS 2 duration

type ErrorCode

type ErrorCode int32

ErrorCode represents FFI error codes returned from the Rust layer

const (
	// ErrorCodeSuccess indicates the operation completed successfully
	ErrorCodeSuccess ErrorCode = 0

	// ErrorCodeNullPointer indicates a null pointer was passed to FFI
	ErrorCodeNullPointer ErrorCode = -1

	// ErrorCodeInvalidUtf8 indicates invalid UTF-8 in string conversion
	ErrorCodeInvalidUtf8 ErrorCode = -2

	// ErrorCodeSessionClosed indicates the Zenoh session is closed
	ErrorCodeSessionClosed ErrorCode = -3

	// ErrorCodePublishFailed indicates message publishing failed
	ErrorCodePublishFailed ErrorCode = -4

	// ErrorCodeSerializationFailed indicates CDR serialization failed
	ErrorCodeSerializationFailed ErrorCode = -5

	// ErrorCodeSubscribeFailed indicates subscriber creation failed
	ErrorCodeSubscribeFailed ErrorCode = -6

	// ErrorCodeNodeCreationFailed indicates node creation failed
	ErrorCodeNodeCreationFailed ErrorCode = -7

	// ErrorCodeContextCreationFailed indicates context creation failed
	ErrorCodeContextCreationFailed ErrorCode = -8

	// ErrorCodeDeserializationFailed indicates CDR deserialization failed
	ErrorCodeDeserializationFailed ErrorCode = -9

	// ErrorCodeBuildFailed indicates a builder failed to construct the entity (FFI returned null)
	ErrorCodeBuildFailed ErrorCode = -10

	// ErrorCodeUnknown indicates an unknown error occurred
	ErrorCodeUnknown ErrorCode = -100
)

type FifoChannel

type FifoChannel[T any] struct {
	// contains filtered or unexported fields
}

FifoChannel delivers messages to a buffered channel. When the channel is full, Send blocks until space is available.

func NewFifoChannel

func NewFifoChannel[T any](bufferSize int) *FifoChannel[T]

NewFifoChannel creates a channel-based handler with the specified buffer size. A buffer size of 0 creates an unbuffered channel (synchronous).

func (*FifoChannel[T]) ToCbDropHandler

func (f *FifoChannel[T]) ToCbDropHandler() (func(T), func(), <-chan T)

ToCbDropHandler returns a callback that sends to the channel.

type Handler

type Handler[T any] interface {
	// ToCbDropHandler returns the callback function, optional drop function, and receive channel.
	// For callback-based handlers, the channel is nil.
	// For channel-based handlers, the callback sends to the channel.
	ToCbDropHandler() (callback func(T), drop func(), receiver <-chan T)
}

Handler provides a unified interface for callback and channel-based message handling. Implementations can use direct callbacks (Closure) or channels (FifoChannel, RingChannel).

type Message

type Message interface {
	// TypeName returns the full ROS 2 type name (e.g., "std_msgs/msg/String")
	TypeName() string

	// TypeHash returns the ROS 2 type hash (RIHS01 format)
	TypeHash() string

	// SerializeCDR serializes the message to CDR format
	SerializeCDR() ([]byte, error)

	// DeserializeCDR deserializes CDR data into the message
	DeserializeCDR(data []byte) error
}

Message is implemented by all generated message types

type MessageHandler

type MessageHandler func(data []byte)

MessageHandler is a callback function for received messages

type Node

type Node struct {
	// contains filtered or unexported fields
}

Node represents a ROS 2 node

func (*Node) Close

func (n *Node) Close() error

Close destroys the node

func (*Node) CreatePublisher

func (n *Node) CreatePublisher(topic string) *PublisherBuilder

CreatePublisher creates a new publisher builder

func (*Node) CreateSubscriber

func (n *Node) CreateSubscriber(topic string) *SubscriberBuilder

CreateSubscriber creates a new subscriber builder

type NodeBuilder

type NodeBuilder struct {
	// contains filtered or unexported fields
}

NodeBuilder builds a Node

func (*NodeBuilder) Build

func (b *NodeBuilder) Build() (*Node, error)

Build creates the node

func (*NodeBuilder) WithNamespace

func (b *NodeBuilder) WithNamespace(ns string) *NodeBuilder

WithNamespace sets the node namespace

func (*NodeBuilder) WithTypeDescriptionService

func (b *NodeBuilder) WithTypeDescriptionService() *NodeBuilder

WithTypeDescriptionService enables the type description service for this node. When enabled, `ros2 topic info --verbose` can query type descriptions from this node.

type NodeInfo

type NodeInfo struct {
	Name      string
	Namespace string
}

NodeInfo describes a discovered node

type Publisher

type Publisher struct {
	// contains filtered or unexported fields
}

Publisher publishes messages to a topic

func (*Publisher) Close

func (p *Publisher) Close() error

Close destroys the publisher

func (*Publisher) Publish

func (p *Publisher) Publish(msg Message) error

Publish publishes a message

type PublisherBuilder

type PublisherBuilder struct {
	// contains filtered or unexported fields
}

PublisherBuilder builds a Publisher

func (*PublisherBuilder) Build

func (b *PublisherBuilder) Build(msg Message) (*Publisher, error)

Build creates the publisher for the given message type

func (*PublisherBuilder) WithQoS

func (b *PublisherBuilder) WithQoS(qos QosProfile) *PublisherBuilder

WithQoS sets the QoS profile for the publisher

type QosDurability

type QosDurability int32

QosDurability controls whether late-joining subscribers see past messages

const (
	// DurabilityVolatile only delivers messages published after subscription (default)
	DurabilityVolatile QosDurability = 0
	// DurabilityTransientLocal delivers cached messages to late-joining subscribers
	DurabilityTransientLocal QosDurability = 1
)

type QosDuration

type QosDuration struct {
	Sec  uint64
	Nsec uint64
}

QosDuration represents a duration in seconds and nanoseconds for QoS settings

func QosDurationInfinite

func QosDurationInfinite() QosDuration

QosDurationInfinite returns an infinite duration (the default for QoS time constraints)

type QosHistory

type QosHistory int32

QosHistory controls how many messages are kept

const (
	// HistoryKeepLast keeps only the last N messages (default)
	HistoryKeepLast QosHistory = 0
	// HistoryKeepAll keeps all messages (limited by system resources)
	HistoryKeepAll QosHistory = 1
)

type QosLiveliness

type QosLiveliness int32

QosLiveliness controls how liveliness is asserted

const (
	// LivelinessAutomatic asserts liveliness automatically (default)
	LivelinessAutomatic QosLiveliness = 0
	// LivelinessManualByNode requires manual liveliness assertion per node
	LivelinessManualByNode QosLiveliness = 1
	// LivelinessManualByTopic requires manual liveliness assertion per topic
	LivelinessManualByTopic QosLiveliness = 2
)

type QosProfile

type QosProfile struct {
	Reliability             QosReliability
	Durability              QosDurability
	History                 QosHistory
	HistoryDepth            int
	Deadline                QosDuration
	Lifespan                QosDuration
	Liveliness              QosLiveliness
	LivelinessLeaseDuration QosDuration
}

QosProfile contains all QoS settings for a publisher or subscriber

func QosDefault

func QosDefault() QosProfile

QosDefault returns the default QoS profile (Reliable, Volatile, KeepLast(10))

func QosKeepAll

func QosKeepAll() QosProfile

QosKeepAll returns QoS that keeps all messages (Reliable, Volatile, KeepAll)

func QosParameterEvents

func QosParameterEvents() QosProfile

QosParameterEvents returns QoS for parameter events (Reliable, Volatile, KeepLast(1000))

func QosSensorData

func QosSensorData() QosProfile

QosSensorData returns QoS suitable for sensor data (BestEffort, Volatile, KeepLast(5))

func QosTransientLocal

func QosTransientLocal() QosProfile

QosTransientLocal returns QoS with transient local durability (Reliable, TransientLocal, KeepLast(1)) Suitable for /robot_description, /tf_static

type QosReliability

type QosReliability int32

QosReliability controls message delivery guarantees

const (
	// ReliabilityReliable retransmits lost messages (default)
	ReliabilityReliable QosReliability = 0
	// ReliabilityBestEffort delivers messages without retransmission
	ReliabilityBestEffort QosReliability = 1
)

type RingChannel

type RingChannel[T any] struct {
	// contains filtered or unexported fields
}

RingChannel delivers messages to a channel with ring buffer semantics. When the channel is full, the oldest message is dropped to make room for the new one.

func NewRingChannel

func NewRingChannel[T any](capacity int) *RingChannel[T]

NewRingChannel creates a ring buffer channel handler with the specified capacity. The capacity must be greater than 0.

func (*RingChannel[T]) ToCbDropHandler

func (r *RingChannel[T]) ToCbDropHandler() (func(T), func(), <-chan T)

ToCbDropHandler returns a callback that sends to the channel with ring buffer behavior.

type RoszError

type RoszError struct {
	// contains filtered or unexported fields
}

RoszError represents a structured error from the ros-z FFI layer

func NewRoszError

func NewRoszError(code ErrorCode, msg string) RoszError

NewRoszError creates a new RoszError with the given code and message

func (RoszError) Code

func (e RoszError) Code() ErrorCode

Code returns the FFI error code

func (RoszError) Error

func (e RoszError) Error() string

Error implements the error interface

func (RoszError) Is

func (e RoszError) Is(target error) bool

Is reports whether target matches this error by comparing error codes. This enables errors.Is() support for RoszError. Uses direct type assertion (not errors.As) to avoid recursive chain walking.

func (RoszError) Message

func (e RoszError) Message() string

Message returns the error message without the code

type Subscriber

type Subscriber struct {
	// contains filtered or unexported fields
}

Subscriber subscribes to messages on a topic

func BuildWithTypedCallback

func BuildWithTypedCallback[T Message](builder *SubscriberBuilder, handler TypedMessageHandler[T]) (*Subscriber, error)

BuildWithTypedCallback creates a subscriber with automatic deserialization. The callback receives the already-deserialized message.

Example:

sub, err := BuildWithTypedCallback(node.CreateSubscriber("chatter"),
    func(msg *std_msgs.String) {
        log.Printf("Received: %s", msg.Data)
    })

func SubscriberWithChannel

func SubscriberWithChannel[T Message](builder *SubscriberBuilder, bufferSize int) (*Subscriber, <-chan T, func(), error)

SubscriberWithChannel creates a subscriber that delivers to a channel with automatic deserialization. Returns the subscriber, a receive channel, and a cleanup function. Call the cleanup function to close the channel when done.

Example:

sub, ch, cleanup, err := SubscriberWithChannel[*std_msgs.String](
    node.CreateSubscriber("chatter"), 10)
defer cleanup()
defer sub.Close()

for msg := range ch {
    log.Printf("Received: %s", msg.Data)
}

func SubscriberWithHandler

func SubscriberWithHandler[T Message](builder *SubscriberBuilder, handler Handler[T]) (*Subscriber, <-chan T, func(), error)

SubscriberWithHandler integrates the Handler interface directly with the Subscriber. Returns the subscriber, receive channel, and a cleanup function. Call cleanup when done to close the handler.

Example:

handler := rosz.NewFifoChannel[*std_msgs.String](10)
sub, ch, cleanup, err := SubscriberWithHandler(
    node.CreateSubscriber("chatter"), handler)
defer cleanup()
defer sub.Close()

for msg := range ch {
    log.Printf("Received: %s", msg.Data)
}

func (*Subscriber) Close

func (s *Subscriber) Close() error

Close destroys the subscriber

type SubscriberBuilder

type SubscriberBuilder struct {
	// contains filtered or unexported fields
}

SubscriberBuilder builds a Subscriber

func (*SubscriberBuilder) BuildWithCallback

func (b *SubscriberBuilder) BuildWithCallback(msg Message, handler MessageHandler) (*Subscriber, error)

BuildWithCallback creates the subscriber with a custom callback handler. The handler is invoked on a C/Rust thread — avoid long blocking operations.

func (*SubscriberBuilder) WithQoS

WithQoS sets the QoS profile for the subscriber

type Time

type Time struct {
	Sec  int32
	Nsec uint32
}

Time represents a ROS 2 time

type TopicInfo

type TopicInfo struct {
	Name     string
	TypeName string
}

TopicInfo describes a discovered topic

type TypedMessageHandler

type TypedMessageHandler[T Message] func(msg T)

TypedMessageHandler is a callback for strongly-typed messages

type ZenohMode

type ZenohMode string

ZenohMode represents the Zenoh session mode

const (
	// ModePeer connects as a Zenoh peer (default)
	ModePeer ZenohMode = "peer"
	// ModeClient connects as a Zenoh client
	ModeClient ZenohMode = "client"
	// ModeRouter connects as a Zenoh router
	ModeRouter ZenohMode = "router"
)

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL