This decoder is intended as an alternative the ouster-ros decoder. It publishes things like LidarScans in a different formats which may be better for things like Lidar Odometry, while things like point clouds, signal, range and IMU remain in the same format. It also has very low latency (<0.2ms) compared to ouster_ros (>1.5ms), tested on Intel i9 13th gen cpu. This will also notify you when packets are dropped. The decoder is up to date with the v0.10 of the ouster SDK.
The decoder only supports LEGACY and single return profile. Currently there's no plan for dual return profile.
The timestamp of both the cloud and image message is the time of the last column, not the first column. This is different from the official driver, which uses timestamp of the first column.
Clone this repo in you catkin workspace along with ouster-ros and catkin build. We use thier custom service and messages and thier ouster sdk submodule.
The following parameters may differ from the defaults that we use. They can be set in the launch file or passed as an argument.
replayset totrueif you are using a bag, default:false.sensor_hostnamehostname or IP in dotted decimal format of the ouster.udp_desthostname or IP in dotted decimal format of where the sensor will send data. Most likely the computer the ouster is connected to.lidar_portthe port to which the ouster will send lidar packets, default:7502imu_portthe port to which the ouster will send imu packets, default:7503lidar_moderesolution and rate of the lidar: either512x10,512x20,1024x10,1024x20, or2048x10, defualt comes from lidar.timestamp_modemethod used to timestamp measurements: eitherIME_FROM_INTERNAL_OSC,TIME_FROM_SYNC_PULSE_IN,TIME_FROM_PTP_1588, default comes from lidar.metadataspecifiy a metadata file to write to, default:ouster_decoder/metadata.json. This must be specified if you are using a bag without the/metadatatopic.tf_preficnamespace for tf transforms.driver_nsnamespace for driver node.
To start everything at once on hardware:
roslaunch ouster_decoder ouster.launch sensor_hostname:=<sensor-ip> udp_dest:=<destination-ip>
Run just the driver (if you want to bag the packets for later decoding)
roslaunch ouster_decoder driver.launch
To run with a bag file run:
roslaunch ouster_decoder ouster.launch replay:=true
and start your bag in another terminal. If your bag does not have the /metadata topic you'll need to specify a json file with metadata:=/path/to/json at launch.
The driver node is the same (logically) as the one from ouster_example, but cleaned up and it publishes a string message to topic /os_node/metadata that you should also record. When in replay mode, there's no need to specify a metadata file. The metadata file will still be saved in case one forgot to record the metadata message.
The decoder allocates storge for a range image and a point cloud on startup. When receiving a packet, it fills the range image and the point cloud instead of doing all computations at the end of a sweep. This drastically redueces latency when publishing the cloud/image.
Each pixel in the range image has the following fields:
struct Data {
float x;
float y;
float z;
uint16_t r16u; // range
uint16_t s16u; // signal
};
The corresponding point cloud has point type XYZI.
During each callback, we process the incoming packet and immediately decode and convert to 3d points. When we reach the end of a sweep, the data is directly published without any extra computations.
Therefore, the publish latency of our decoder is typically less than 0.2ms, while the ouster os_cloud_node takes more than 1.5ms to publish a point cloud.
Our decoder also checks for missing data. This is very useful for debugging purposes. The decoder tracks the frame and column id of each packet and reports any jumps (both forward and backward) if detected. The decoder then makes sure that missing data is zeroed out in the message.
Therefore, one can safely stop and replay a recorded rosbag without restarting the driver and decoder.