Class OusterDirectInput
Defined in File OusterDirectInput.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public RawDataSourceBase
Class Documentation
-
class OusterDirectInput : public RawDataSourceBase
RawDataSource from an Ouster LiDAR sensor using the native Ouster C++ SDK.
This module connects directly to an Ouster sensor (or replays a .pcap file) without requiring any ROS middleware. It produces mrpt::obs::CObservationPointCloud (LiDAR) and mrpt::obs::CObservationIMU observations and pushes them into the MOLA pipeline.
Coordinate frames and sensorPose
Point cloud coordinates are in the Ouster Sensor Coordinate Frame (the SDK’s
make_xyz_lut(info)bakeslidar_to_sensor_transforminto the lookup table). IMU readings are in the IMU frame.Each observation’s
sensorPoseis set to the full transform frombase_linkto the respective sensor frame, matching the convention used bymrpt::ros2bridgeandmola::BridgeROS2:lidar sensorPose = sensor_mounting_pose (+) lidar_to_sensor_transform IMU sensorPose = sensor_mounting_pose (+) imu_to_sensor_transform
Both intrinsic transforms are read automatically from the sensor firmware metadata (
sensor_info). The user only needs to providesensor_mounting_pose(pose of the Ouster housing on the vehicle).
Live mode
Set
sensor_hostnameto connect to a live sensor.
PCAP replay mode
Set
pcap_fileandmetadata_jsonto replay a recorded capture.
OSF replay mode
Set
osf_fileto replay an Ouster.osfrecording. Sensor metadata and scan geometry are read directly from the OSF file; no separate metadata JSON is required.
YAML parameters
params: # --- Live mode (exclusive with pcap_file / osf_file) --- sensor_hostname: "os-122xxxxxxxxx.local" udp_dest: "" # empty = auto-detect lidar_port: 0 # 0 = auto imu_port: 0 # 0 = auto # --- PCAP replay mode --- pcap_file: "/path/to/capture.pcap" metadata_json: "/path/to/metadata.json" time_warp_scale: 1.0 # --- OSF replay mode --- osf_file: "/path/to/recording.osf" time_warp_scale: 1.0 # --- Sensor configuration (live mode only) --- lidar_mode: "MODE_1024x10" timestamp_mode: "TIME_FROM_PTP_1588" # --- Observation labeling --- lidar_sensor_label: "lidar" imu_sensor_label: "imu" # --- Sensor housing pose on the vehicle (base_link → os_sensor) --- # The factory-calibrated lidar-to-sensor and imu-to-sensor # intrinsic transforms are read from the sensor metadata and # composed automatically: # lidar sensorPose = mounting (+) lidar_to_sensor # IMU sensorPose = mounting (+) imu_to_sensor sensor_mounting_pose: "0 0 0 0 0 0" # x y z yaw_deg pitch_deg roll_deg # --- (Optional) Manual overrides for individual sensor poses --- # When set, these bypass the automatic composition and set the # observation sensorPose directly (base_link → sensor frame). # lidar_sensor_pose: "0 0 0 0 0 0" # imu_sensor_pose: "0 0 0 0 0 0"
Public Functions
-
OusterDirectInput()
-
~OusterDirectInput() override
-
OusterDirectInput(const OusterDirectInput&) = delete
-
OusterDirectInput &operator=(const OusterDirectInput&) = delete
-
OusterDirectInput(OusterDirectInput&&) = delete
-
OusterDirectInput &operator=(OusterDirectInput&&) = delete
-
void spinOnce() override
-
void onQuit() override
Protected Functions
-
void initialize_rds(const Yaml &cfg) override
-
OusterDirectInput()