|
| 1 | +# Native Modules |
| 2 | + |
| 3 | +Native modules let you wrap **any executable** as a first-class DimOS module, given it speaks LCM. |
| 4 | + |
| 5 | +Python handles blueprint wiring, lifecycle, and logging. Native binary handles the actual computation, publishing and subscribing directly on LCM. |
| 6 | + |
| 7 | +Python module **never touches the pubsub data**. It just passes configuration and LCM topic to use via CLI args to your executable. |
| 8 | + |
| 9 | +## Supported languages |
| 10 | + |
| 11 | +We have examples of LCM integrations for **C++**, **TypeScript**, and **Lua** here in the repo - see [/examples/language-interop/](/examples/language-interop/README.md) |
| 12 | + |
| 13 | +We have our msg types generated for **C#** and **Java** as well — see [dimos-lcm/generated](https://github.com/dimensionalOS/dimos-lcm/tree/main/generated). For pubsub client implementation, look into the [LCM Project](https://github.com/lcm-proj/lcm). |
| 14 | + |
| 15 | +LCM is a very simple protocol that's easy to implement with any language, and our types are simple and automatically generated, so you can theoretically add support for anything. |
| 16 | + |
| 17 | +## Defining a native module |
| 18 | + |
| 19 | +Python side native module is just a definition of a **config** dataclass and **module** class specifying pubsub I/O. |
| 20 | + |
| 21 | +Both the config dataclass and pubsub topics get converted to CLI args passed down to your executable once the module is started. |
| 22 | + |
| 23 | +```python no-result session=nativemodule |
| 24 | +from dataclasses import dataclass |
| 25 | +from dimos.core import Out, LCMTransport |
| 26 | +from dimos.core.native_module import NativeModule, NativeModuleConfig |
| 27 | +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 |
| 28 | +from dimos.msgs.sensor_msgs.Imu import Imu |
| 29 | +import time |
| 30 | + |
| 31 | +@dataclass(kw_only=True) |
| 32 | +class MyLidarConfig(NativeModuleConfig): |
| 33 | + executable: str = "./build/my_lidar" |
| 34 | + host_ip: str = "192.168.1.5" |
| 35 | + frequency: float = 10.0 |
| 36 | + |
| 37 | +class MyLidar(NativeModule): |
| 38 | + default_config = MyLidarConfig |
| 39 | + pointcloud: Out[PointCloud2] |
| 40 | + imu: Out[Imu] |
| 41 | + |
| 42 | + |
| 43 | +``` |
| 44 | + |
| 45 | +That's it. `MyLidar` is a full DimOS module. You can use it with `autoconnect`, blueprints, transport overrides, and specs. Once this module is started, your `./build/my_lidar` will get called with specific CLI args. |
| 46 | + |
| 47 | + |
| 48 | +## How it works |
| 49 | + |
| 50 | +When `start()` is called, NativeModule: |
| 51 | + |
| 52 | +1. **Collects topics** from blueprint-assigned transports on each declared port. |
| 53 | +2. **Builds the command line**: `<executable> --<port> <topic> ... --<config_field> <value> ...` |
| 54 | +3. **Launches the subprocess** with `Popen`, piping stdout/stderr. |
| 55 | +4. **Starts a watchdog** thread that calls `stop()` if the process crashes. |
| 56 | + |
| 57 | +For the example above, the launched command would look like: |
| 58 | + |
| 59 | +```sh |
| 60 | +./build/my_lidar \ |
| 61 | + --pointcloud '/pointcloud#sensor_msgs.PointCloud2' \ |
| 62 | + --imu '/imu#sensor_msgs.Imu' \ |
| 63 | + --host_ip 192.168.1.5 \ |
| 64 | + --frequency 10.0 |
| 65 | +``` |
| 66 | + |
| 67 | +```python ansi=false session=nativemodule skip |
| 68 | +mylidar = MyLidar() |
| 69 | +mylidar.pointcloud.transport = LCMTransport("/lidar", PointCloud2) |
| 70 | +mylidar.imu.transport = LCMTransport("/imu", Imu) |
| 71 | +mylidar.start() |
| 72 | +``` |
| 73 | + |
| 74 | +<!--Result:--> |
| 75 | +``` |
| 76 | +2026-02-14T11:22:12.123963Z [info ] Starting native process [dimos/core/native_module.py] cmd='./build/my_lidar --pointcloud /lidar#sensor_msgs.PointCloud2 --imu /imu#sensor_msgs.Imu --host_ip 192.168.1.5 --frequency 10.0' cwd=/home/lesh/coding/dimos/docs/usage/build |
| 77 | +``` |
| 78 | + |
| 79 | +Topic strings use the format `/<name>#<msg_type>`, which is the LCM channel name that Python `LCMTransport` subscribers use. The native binary publishes on these exact channels. |
| 80 | + |
| 81 | +When `stop()` is called, the process receives SIGTERM. If it doesn't exit within `shutdown_timeout` seconds (default 10), it gets SIGKILL. |
| 82 | + |
| 83 | +## Config |
| 84 | + |
| 85 | +`NativeModuleConfig` extends `ModuleConfig` with subprocess fields: |
| 86 | + |
| 87 | +| Field | Type | Default | Description | |
| 88 | +|--------------------|------------------|---------------|-------------------------------------------------------------| |
| 89 | +| `executable` | `str` | *(required)* | Relative or Absolute path to the native binary | |
| 90 | +| `extra_args` | `list[str]` | `[]` | Additional CLI arguments appended after auto-generated ones | |
| 91 | +| `extra_env` | `dict[str, str]` | `{}` | Extra environment variables for the subprocess | |
| 92 | +| `cwd` | `str \| None` | `None` | Working directory (defaults to executable's parent dir) | |
| 93 | +| `shutdown_timeout` | `float` | `10.0` | Seconds to wait for SIGTERM before SIGKILL | |
| 94 | +| `log_format` | `LogFormat` | `TEXT` | How to parse subprocess output (`TEXT` or `JSON`) | |
| 95 | +| `cli_exclude` | `frozenset[str]` | `frozenset()` | Config fields to skip when generating CLI args | |
| 96 | + |
| 97 | +### Auto CLI arg generation |
| 98 | + |
| 99 | +Any field you add to your config subclass automatically becomes a `--name value` CLI arg. Fields from `NativeModuleConfig` itself (like `executable`, `extra_args`, `cwd`) are **not** passed — they're for Python-side orchestration only. |
| 100 | + |
| 101 | +```python skip |
| 102 | + |
| 103 | +class LogFormat(enum.Enum): |
| 104 | + TEXT = "text" |
| 105 | + JSON = "json" |
| 106 | + |
| 107 | +@dataclass(kw_only=True) |
| 108 | +class MyConfig(NativeModuleConfig): |
| 109 | + executable: str = "./build/my_module" # relative or absolute path to your executable |
| 110 | + host_ip: str = "192.168.1.5" # becomes --host_ip 192.168.1.5 |
| 111 | + frequency: float = 10.0 # becomes --frequency 10.0 |
| 112 | + enable_imu: bool = True # becomes --enable_imu true |
| 113 | + filters: list[str] = field(default_factory=lambda: ["a", "b"]) # becomes --filters a,b |
| 114 | +``` |
| 115 | + |
| 116 | +- `None` values are skipped. |
| 117 | +- Booleans are lowercased (`true`/`false`). |
| 118 | +- Lists are comma-joined. |
| 119 | + |
| 120 | +### Excluding fields |
| 121 | + |
| 122 | +If a config field shouldn't be a CLI arg, add it to `cli_exclude`: |
| 123 | + |
| 124 | +```python skip |
| 125 | +@dataclass(kw_only=True) |
| 126 | +class FastLio2Config(NativeModuleConfig): |
| 127 | + executable: str = "./build/fastlio2" |
| 128 | + config: str = "mid360.yaml" # human-friendly name |
| 129 | + config_path: str | None = None # resolved absolute path |
| 130 | + cli_exclude: frozenset[str] = frozenset({"config"}) # only config_path is passed |
| 131 | + |
| 132 | + def __post_init__(self) -> None: |
| 133 | + if self.config_path is None: |
| 134 | + self.config_path = str(Path(self.config).resolve()) |
| 135 | +``` |
| 136 | + |
| 137 | +## Using with blueprints |
| 138 | + |
| 139 | +Native modules work with `autoconnect` exactly like Python modules: |
| 140 | + |
| 141 | +```python skip |
| 142 | +from dimos.core.blueprints import autoconnect |
| 143 | + |
| 144 | +class PointCloudConsumer(Module): |
| 145 | + pointcloud: In[PointCloud2] |
| 146 | + imu: In[Imu] |
| 147 | + |
| 148 | +autoconnect( |
| 149 | + MyLidar.blueprint(host_ip="192.168.1.10"), |
| 150 | + PointCloudConsumer.blueprint(), |
| 151 | +).build().loop() |
| 152 | +``` |
| 153 | + |
| 154 | +`autoconnect` matches ports by `(name, type)`, assigns LCM topics, and passes them to the native binary as CLI args. You can override transports as usual: |
| 155 | + |
| 156 | +```python skip |
| 157 | +blueprint = autoconnect( |
| 158 | + MyLidar.blueprint(), |
| 159 | + PointCloudConsumer.blueprint(), |
| 160 | +).transports({ |
| 161 | + ("pointcloud", PointCloud2): LCMTransport("/my/custom/lidar", PointCloud2), |
| 162 | +}) |
| 163 | +``` |
| 164 | + |
| 165 | +## Logging |
| 166 | + |
| 167 | +NativeModule pipes subprocess stdout and stderr through structlog: |
| 168 | + |
| 169 | +- **stdout** is logged at `info` level. |
| 170 | +- **stderr** is logged at `warning` level. |
| 171 | + |
| 172 | +### JSON log format |
| 173 | + |
| 174 | +If your native binary outputs structured JSON lines, set `log_format=LogFormat.JSON`: |
| 175 | + |
| 176 | +```python skip |
| 177 | +@dataclass(kw_only=True) |
| 178 | +class MyConfig(NativeModuleConfig): |
| 179 | + executable: str = "./build/my_module" |
| 180 | + log_format: LogFormat = LogFormat.JSON |
| 181 | +``` |
| 182 | + |
| 183 | +The module will parse each line as JSON and feed the key-value pairs into structlog. The `event` key becomes the log message: |
| 184 | + |
| 185 | +```json |
| 186 | +{"event": "sensor initialized", "device": "/dev/ttyUSB0", "baud": 115200} |
| 187 | +``` |
| 188 | + |
| 189 | +Malformed lines fall back to plain text logging. |
| 190 | + |
| 191 | +## Writing the C++ side |
| 192 | + |
| 193 | +A header-only helper is provided at [`dimos/hardware/sensors/lidar/common/dimos_native_module.hpp`](/dimos/hardware/sensors/lidar/common/dimos_native_module.hpp): |
| 194 | + |
| 195 | +```cpp |
| 196 | +#include "dimos_native_module.hpp" |
| 197 | +#include "sensor_msgs/PointCloud2.hpp" |
| 198 | + |
| 199 | +int main(int argc, char** argv) { |
| 200 | + dimos::NativeModule mod(argc, argv); |
| 201 | + |
| 202 | + // Get the LCM channel for a declared port |
| 203 | + std::string pc_topic = mod.topic("pointcloud"); |
| 204 | + |
| 205 | + // Get config values |
| 206 | + float freq = mod.arg_float("frequency", 10.0); |
| 207 | + std::string ip = mod.arg("host_ip", "192.168.1.5"); |
| 208 | + |
| 209 | + // Set up LCM publisher and publish on pc_topic... |
| 210 | +} |
| 211 | +``` |
| 212 | +
|
| 213 | +The helper provides: |
| 214 | +
|
| 215 | +| Method | Description | |
| 216 | +|---------------------------|----------------------------------------------------------------| |
| 217 | +| `topic(port)` | Get the full LCM channel string (`/topic#msg_type`) for a port | |
| 218 | +| `arg(key, default)` | Get a string config value | |
| 219 | +| `arg_float(key, default)` | Get a float config value | |
| 220 | +| `arg_int(key, default)` | Get an int config value | |
| 221 | +| `has(key)` | Check if a port/arg was provided | |
| 222 | +
|
| 223 | +It also includes `make_header()` and `time_from_seconds()` for building ROS-compatible stamped messages. |
| 224 | +
|
| 225 | +## Examples |
| 226 | +
|
| 227 | +For language interop examples (subscribing to DimOS topics from C++, TypeScript, Lua), see [/examples/language-interop/](/examples/language-interop/README.md). |
| 228 | +
|
| 229 | +### Livox Mid-360 Module |
| 230 | +
|
| 231 | +The Livox Mid-360 LiDAR driver is a complete example at [`dimos/hardware/sensors/lidar/livox/module.py`](/dimos/hardware/sensors/lidar/livox/module.py): |
| 232 | +
|
| 233 | +```python skip |
| 234 | +from dimos.core import Out |
| 235 | +from dimos.core.native_module import NativeModule, NativeModuleConfig |
| 236 | +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 |
| 237 | +from dimos.msgs.sensor_msgs.Imu import Imu |
| 238 | +from dimos.spec import perception |
| 239 | +
|
| 240 | +@dataclass(kw_only=True) |
| 241 | +class Mid360Config(NativeModuleConfig): |
| 242 | + executable: str = str(Path(__file__).parent / "cpp" / "result" / "bin" / "mid360_native") |
| 243 | + host_ip: str = "192.168.1.5" |
| 244 | + lidar_ip: str = "192.168.1.155" |
| 245 | + frequency: float = 10.0 |
| 246 | + enable_imu: bool = True |
| 247 | + frame_id: str = "lidar_link" |
| 248 | + # ... SDK port configuration |
| 249 | +
|
| 250 | +class Mid360(NativeModule, perception.Lidar, perception.IMU): |
| 251 | + default_config = Mid360Config |
| 252 | + lidar: Out[PointCloud2] |
| 253 | + imu: Out[Imu] |
| 254 | +``` |
| 255 | + |
| 256 | +Usage: |
| 257 | + |
| 258 | +```python skip |
| 259 | +from dimos.hardware.sensors.lidar.livox.module import Mid360 |
| 260 | + |
| 261 | +autoconnect( |
| 262 | + Mid360.blueprint(host_ip="192.168.1.5"), |
| 263 | + SomeConsumer.blueprint(), |
| 264 | +) |
| 265 | +``` |
0 commit comments