Sensor Data

Coordinate Frames and XYZ Calculation

Ouster defines two coordinate frames:

The Lidar Coordinate Frame follows the Right Hand Rule convention and is a point cloud-centric frame of reference that is the simplest frame in which to calculate and manipulate point clouds. The X-axis points backwards towards the external connector, which is an unintuitive orientation that was deliberately chosen to meet the following criteria:

  • data frames split at the back of the sensor i.e. the external connector

  • data frames start with the azimuth angle equal to 0°

All point cloud features including setting an azimuth window and phase locking are defined in the Lidar Coordinate Frame.

The Sensor Coordinate Frame follows the Right Hand Rule convention and is a mechanical housing-centric frame of reference that follows robotics convention with X-axis pointing forward. Ouster-provided drivers and visualizers represent data in the Sensor Coordinate Frame.

Note

All Ouster coordinate frames follow the Right Hand Rule, allowing for standard 3D transformation matrix math to convert between them. For multi-sensor systems that require calibration, this Linear Algebra-based approach can be convenient. However, customers with single-sensor systems may find it more intuitive to stay in the Lidar Coordinate Frame and take arithmetic shortcuts.

Lidar Coordinate Frame

The Lidar Coordinate Frame is defined at the intersection of the lidar axis of rotation and the lidar optical midplane (a plane parallel to Sensor Coordinate Frame XY plane and coincident with the 0° elevation beam angle of the sensor).

The Lidar Coordinate Frame axes are arranged with:
  • positive X-axis pointed at encoder angle 0° and the external connector

  • positive Y-axis pointed towards encoder angle 90°

  • positive Z-axis pointed towards the top of the sensor

The Lidar Coordinate Frame is marked in both diagrams below with XL, YL, and ZL.

Lidar Range to XYZ

Given the following information, range data may be transformed into 3D cartesian XYZ coordinates in the Lidar Coordinate Frame:

From a measurement block from the UDP packet:
  • Measurement ID value can be found on the lidar data packet

  • scan_width value of the horizontal resolution

  • r or range_mm1 value of the data block of the i-th channel

  • r' or range_to_beam_origin_mm2

From the get_beam_intrinsics TCP command:
  • lidar_origin_to_beam_origin_mm3 value

  • beam_altitude_angles array

  • beam_azimuth_angles array

The corresponding 3D point can be computed by

r &= \texttt{range\_mm} \\
|\vec{n}| &= \texttt{lidar\_origin\_to\_beam\_origin\_mm} \\
r &= |\vec{r'}| + |\vec{n}| \\
\theta_{encoder} &= 2\pi \cdot \left ( 1 - \frac{\texttt{measurement\ ID}}{\texttt{scan\_width}}\right ) \\
\theta_{azimuth} &= -2\pi \frac{\texttt{beam\_azimuth\_angles[i]}}{360} \\
\phi &= 2\pi \frac{\texttt{beam\_altitude\_angles[i]}}{360} \\
\\
x &= (r-|\vec{n}|) \cos\left(\theta_{encoder} + \theta_{azimuth}\right) \cos(\phi) + |\vec{n}| \cos\left(\theta_{encoder}\right) \\
y &= (r-|\vec{n}|) \sin\left(\theta_{encoder} + \theta_{azimuth}\right) \cos(\phi) + |\vec{n}| \sin\left(\theta_{encoder}\right) \\
z &= (r-|\vec{n}|) \sin(\phi)

../../../_images/lidar-frame-top-down.svg

Top-down view of Lidar Coordinate Frame

../../../_images/lidar-frame-side.svg

Side view of Lidar Coordinate Frame

1

r or range_mm is the magnitude of the vector sum of (r + n). This value is provided for each measurement in blocks [0-15] of the i-th channel.

2

r' or range_to_beam_origin_mm is the magnitude of the distance vector from lidar front optics to the detected object. This value is NOT provided; It is only to help illustrate the concept.

3

n or lidar_origin_to_beam_origin_mm is the magnitude of the distance vector from the center of the lidar origin coordinate frame to lidar front optics. This value is provided from the get_beam_intrinsics, please refer to the API Guide for more information.

Sensor Coordinate Frame

The Sensor Coordinate Frame is defined at the center of the sensor housing on the bottom, with the X-axis pointed forward, Y-axis pointed to the left and Z-axis pointed towards the top of the sensor. The external connector is located in the negative x direction. The Sensor Coordinate Frame is marked in the diagram below with XS, YS, ZS.

../../../_images/sensor-frame-top-down.svg

Top-down view of Sensor Coordinate Frame

../../../_images/sensor-frame-side.svg

Side view of Sensor Coordinate Frame

Combining Lidar and Sensor Coordinate Frame

The Lidar Coordinate Frame’s positive X-axis (0 encoder value) is opposite the Sensor Coordinate Frame’s positive X-axis to center lidar data about the Sensor Coordinate Frame’s positive X-axis. A single measurement frame starts at the Lidar Coordinate Frame’s 0° position and ends at the 360° position. This is convenient when viewing a “range image” of the Ouster Sensor measurements, allowing the “range image” to be centered in the Sensor Coordinate Frame’s positive X-axis, which is generally forward facing in most robotic systems.

The Ouster Sensor scans in the clockwise direction when viewed from the top, which is a negative rotational velocity about the Z-axis. Thus, as encoder ticks increase from 0 to 90,111, the actual angle about the Z-axis in the Lidar Coordinate Frame will decrease.

Lidar Intrinsic Beam Angles

The intrinsic beam angles for each beam may be queried with a TCP command get_beam_intrinsics to provide an azimuth and elevation adjustment offset to each beam. The azimuth adjustment is referenced off of the current encoder angle and the elevation adjustment is referenced from the XY plane in the Sensor and Lidar Coordinate Frames.

Lidar Range Data To Sensor XYZ Coordinate Frame

For applications that require calibration against a precision mount or use the IMU data in combination with the lidar data, the XYZ points should be adjusted to the Sensor Coordinate Frame. This requires a Z translation and a rotation of the X,Y,Z points about the Z-axis. The z translation is the height of the lidar aperture stop above the sensor origin, which varies depending on the sensor you have, and the data must be rotated 180° around the Z-axis. This information can be queried over TCP in the form of a homogeneous transformation matrix in row-major ordering.

Example JSON formatted query using the TCP command get_lidar_intrinsics:

{
  "lidar_to_sensor_transform": [-1, 0, 0, 0, 0, -1, 0, 0, 0, 0, 1, 36.180, 0, 0, 0, 1]
}

Which corresponds to the following matrix

\texttt{M\_lidar\_to\_sensor} = \begin{bmatrix}
-1 & 0 & 0 & 0\\
0 & -1 & 0 & 0\\
0 & 0 & 1 & 36.180\\
0 & 0 & 0 & 1
\end{bmatrix}

The table below lists all product lines’ distances of the aperture stop above the sensor origin for use in the z translation.

Lidar aperture stop above sensor origin

Product Line

Lidar aperture stop above sensor origin

OS0 Gen 1 & Gen 2 (All Revisions)

36.180 mm

OS1 Gen 1 & Gen 2 (All Revisions)

36.180 mm

OS2 Gen 2 (Revisions A, B, C)

74.296 mm

OS2 Gen 2 (Revisions D and higher)

78.296 mm

IMU Data To Sensor XYZ Coordinate Frame

The IMU is slightly offset in the Sensor Coordinate Frame for practical reasons. The IMU origin in the Sensor Coordinate Frame can be queried over TCP in the form of an homogeneous transformation matrix in row-major ordering.

Example 1- Expected response for TCP command get_imu_intrinsics when using Gen1 OS1 (all revisions), Gen2 OS01 (all revisions) and Gen2 OS2 (top-level revisions A, B, C)

{
  "imu_to_sensor_transform": [1, 0, 0, 6.253, 0, 1, 0, -11.775, 0, 0, 1, 7.645, 0, 0, 0, 1]
}

Which corresponds to the following matrix

\texttt{M\_imu\_to\_sensor} = \begin{bmatrix}
1 & 0 & 0 & 6.253\\
0 & 1 & 0 & -11.775\\
0 & 0 & 1 & 7.645\\
0 & 0 & 0 & 1
\end{bmatrix}

Example 2- Expected response for TCP command get_imu_intrinsics when using Gen2 OS2 (top-level revisions D and higher)

{
  "imu_to_sensor_transform": [1, 0, 0, 6.253, 0, 1, 0, -11.775, 0, 0, 1, 11.645, 0, 0, 0, 1]
}

Which corresponds to the following matrix

\texttt{M\_imu\_to\_sensor} = \begin{bmatrix}
1 & 0 & 0 & 6.253\\
0 & 1 & 0 & -11.775\\
0 & 0 & 1 & 11.645\\
0 & 0 & 0 & 1
\end{bmatrix}

Lidar Data Packet Format

With firmware version 2.3 and above, users will have the option to switch between different lidar data packet formats as shown below.

By default, the data packet format will be set to LEGACY.

Note

In order to enable dual returns the user needs to have both a Rev 06 sensor or later and an upgrade to firmware version 2.2 or later.

Configurable Data Packet Format

When setting the udp_profile_lidar to a value other than LEGACY, a new packet format will be automatically activated. This packet format, called the configurable data packet format, allows the users to choose between different options for the channel data profile depending on their usage, while maintaining a uniform packet structure across different profiles. It is described in detail below.

Lidar Data Format

When the config parameter udp_profile_lidar is set to a parameter other than LEGACY, we will be in the Configurable data packet format. Each data packet consists of Packet Header, Measurement Header, Channel Data Blocks and Packet Footer. The packet rate is dependent on the lidar mode. Words are 32 bits in length and little endian. By default, lidar UDP data is forwarded to Port 7502. Please refer to the TCP API portion of this manual for more information on setting this parameter. Alternately, this mode can also be configured via the Web Interface.

Packet layout

Packet Header [256 bits]

  • Packet type [16 bit unsigned int] - Identifies lidar data vs. other packets in stream. Packet Type is 0x1 for Lidar packets.

  • Frame ID [16 bit unsigned int] - Index of the lidar scan, increments every time the sensor completes a rotation, crossing the zero azimuth angle.

  • Init ID [24 bit unsigned int] - Initialization ID. Updates on every reinit, which may be triggered by the user or an error, and every reboot. This value may also be obtained by running the TCP command get_sensor_info.

  • Serial No [40 bit unsigned int] - Serial number of the sensor. This value is unique to each sensor and can be found on a sticker affixed to the top of the sensor. In addition, this information is also available on the Sensor Web UI and by reading the field prod_sn from get_sensor_info.

Column Header Block [96 bits]

  • Timestamp [64 bit unsigned int] - Timestamp of the measurement in nanoseconds.

  • Measurement ID [16 bit unsigned int] - Sequentially incrementing measurement counting up from 0 to 511, or 0 to 1023, or 0 to 2047 depending on lidar_mode.

  • Status [1 bit unsigned int] - Indicates validity of the measurements. Status is 0x01 for valid measurements.Status is 0x00 for dropped or disabled columns.

N Channel Data Blocks [Varies based on channel data profile] - The size and the structure of the channel data block varies based on the configurable data packet format chosen by the user. More information on each of these options are described below in the following sections.

Packet Footer [256 bits]

../../../_images/OusterDataPackets_configurable.png

Configurable Data Packet Configuration

Channel Data Profiles

This section describes the different channel data profile options that are available to the users as part of the configurable data packet format. Each of these data profiles can be selected by setting the configuration parameter udp_profile_lidar to one of the following options:

  • RNG19_RFL8_SIG16_NIR16 (Single Return Profile)

  • RNG15_RFL8_NIR8 (Low Data Rate Profile)

  • RNG19_RFL8_SIG16_NIR16_DUAL (Dual Return Profile)

More details on how to set the configuration parameters are described in the TCP API Guide portion of this Firmware User Manual.

Note

Calibrated reflectivity has certain hardware requirements. Please refer to the Calibrated Reflectivity section for more details.

Configurable Data Packet Profiles

Description

Single Return Profile

Low Data Rate Profile

Dual Return Profile

Profiles

RNG19_RFL8_SIG16_NIR16

RNG15_RFL8_NIR8

RNG19_RFL8_SIG16_NIR16_DUAL

Words per pixel

3

1

4

Range RET1

19 bits

15 bits

19 bits

Reflectivity RET1

8 bits

8 bits

8 bits

Range RET2

Not Available

Not Available

19 bits

Reflectivity RET2

Not Available

Not Available

8 bits

Signal RET1

16 bits

Not Available

16 bits

Signal RET2

Not Available

Not Available

16 bits

NIR

16 bits

8 bits

16 bits

Single Return Profile

This channel data profile can be activated by setting the configuration parameter udp_profile_lidar to RNG19_RFL8_SIG16_NIR16.

Note

This is only available with firmware version 2.3 or later.

set_config_param udp_profile_lidar RNG19_RFL8_SIG16_NIR16

The above command will set the channel data profile in the configurable data packet format to Single Return mode. This channel data profile is identical to the channel data block present in LEGACY format, but makes use of the configurable data packet format. Users looking to take advantage of the configurable data packet format can use this profile in place of LEGACY. The channel data profile for this is described below.

Channel Data Blocks [96 bits each for RNG19_RFL8_SIG16_NIR16 profile] - For RNG19_RFL8_SIG16_NIR16 profile the channel data block consists of 3 words to accommodate data for porting over the LEGACY profile to configurable Data Packet format. Only a single return will be made available to the user.

  • Range [19 bit unsigned int] - Range in millimeters, discretized to the nearest 1 millimeters with a maximum range of 524m. Note that range value will be set to 0 if out of range or if no detection is made.

  • Calibrated Reflectivity [8 bit unsigned int] - Sensor Signal Photons measurements are scaled based on measured range and sensor sensitivity at that range, providing an indication of target reflectivity.

  • Signal Photons [16 bit unsigned int] - Signal intensity photons in the signal return measurement are reported.

  • Near Infrared Photons [16 bit unsigned int] - NIR photons related to natural environmental illumination are reported.

../../../_images/Channel_data_rate_single.png

Single Return Configuration

Low Data Rate Profile

This channel data profile can be activated by setting the configuration parameter udp_profile_lidar to RNG15_RFL8_NIR8.

Note

This is only available with firmware version 2.3 or later.

set_config_param udp_profile_lidar RNG15_RFL8_NIR8

The above command will set the channel data profile in the configurable data packet format to Low Data Rate configuration.

This channel data profile is especially useful to users who are looking to adopt a channel data profile to fit with a limited compute capabilities. The data rate and the data packet size that are achieved as a result of using this profile will be smaller as compared to the other channel data profile options that are available.

The channel data profile for this is described below.

Channel Data Blocks [32 bits each for RNG15_RFL8_NIR8 profile] - For the RNG15_RFL8_NIR8 profile the channel data block consists of only 1 word to accommodate data for optimizing information at a low data rate. Only a single return will be made available to the user.

  • Range [15 bit unsigned int] - Range in millimeters, discretized to the nearest 8 millimeters with a maximum range of 262m. Note that range value will be set to 0 if out of range or if no detection is made.

  • Calibrated Reflectivity [8 bit unsigned int] - Sensor Signal Photons measurements are scaled based on measured range and sensor sensitivity at that range, providing an indication of target reflectivity.

  • Near Infrared Photons [8 bit unsigned int] - NIR photons related to natural environmental illumination are reported. Measurements are taken similar to LEGACY and other data profiles (Single Data Profile and Dual Return Profile) but it is scaled down by a factor of 16.

../../../_images/Channel_data_rate_Low.png

Low Data Rate Configuration

Dual Return Profile

This channel data profile can be activated by setting the configuration parameter udp_profile_lidar to RNG19_RFL8_SIG16_NIR16_DUAL. Please note in order to enable dual returns the user needs to have both a Rev 06 sensor or later and an upgrade to firmware version 2.2 or later.

set_config_param udp_profile_lidar RNG19_RFL8_SIG16_NIR16_DUAL

This feature is meant to allow the sensor to provide an output up to 2 returns (Strongest and Second Strongest).

This feature will allow Ouster sensors to operate in scenarios with semi-transparent obscurants, such as rain, fog, or even a chain-link fence. In these scenarios, the strongest and second strongest returns are required to see both the semi-transparent object, as well as whatever may lie behind it.

Channel Data Blocks [128 bits each for RNG19_RFL8_SIG16_NIR16_DUAL profile]-

For RNG19_RFL8_SIG16_NIR16_DUAL profile the channel data block consists of 4 words to accommodate data for the multiple returns. A total of up to two returns will be made available to the user.

  • Range RET1/2 [19 bit unsigned int] - range in millimeters, discretized to the nearest 1 millimeters with a maximum range of 524m. Note that range value will be set to 0 if out of range or if no detection is made.

  • Calibrated Reflectivity RET1/2 [8 bit unsigned int] - Sensor Signal Photons measurements are scaled based on measured range and sensor sensitivity at that range, providing an indication of target reflectivity.

  • Signal Photons RET1/2 [16 bit unsigned int] - Signal intensity photons in the signal return measurement are reported.

  • Near Infrared Photons [16 bit unsigned int] - NIR photons related to natural environmental illumination are reported.

../../../_images/OusterDataPackets_dualreturns.png

Dual Return Data Packet Configuration

Packet Size Calculation (Configurable)

Packet size can be calculated by the following formula:

packet_header_size + columns_per_packet * (measurement_header_size + pixels_per_column * channel_data_block_size) + packet_footer_size

For example:

  • 32 + 16 * (12 + n * s) + 32 bytes

    • packet_header_size = 32 bytes

    • columns_per_packet = 16

    • measurement_header_size = 12 bytes

    • n is pixels_per_column (correspond to the number of channels: 128 for OS1-128)

    • s is the size of a channel data block (16 bytes for RNG19_RFL8_SIG16_NIR16_DUAL configuration)

    • packet_footer_size = 32 bytes

The table below calculates the data of all products operating at the highest lidar modes, 2048x10 or 1024x20 for Single Return and Low Data Rate profiles and 1024x10 for Dual Return profile and assuming a default azimuth window of 360°. Providing a custom azimuth window can further lower data rate. See the Azimuth Window section for details on setting a custom azimuth window.

Packet Size (Bytes) and Data Rate (Mbps) Breakdown - Configurable Data Packet Format

Product

Single Return Lidar Packet size (bytes)

Dual Return Lidar Packet size (bytes)

Low Data Rate Lidar Packet size (bytes)

Single Return Data rate (Mbps)

Dual Return Data rate (Mbps)

Low Data Rate (Mbps)

OS0-32, OS1-32, OS2-32

6400

8512

2304

65.57

43.62

23.63

OS0-64, OS1-64, OS2-64

12544

16704

4352

128.49

85.56

43.63

OS0-128, OS1-128, OS2-128

24832

33088

8448

254.32

169.45

86.55

Packet Rate (Hz) Breakdown - Configurable Data Packet Format

Product

Single Return Lidar Packet rate (Hz)

Dual Return Lidar Packet rate (Hz)

Low Data Rate Lidar Packet rate (Hz)

OS0-32, OS1-32, OS2-32

1280

640

1280

OS0-64, OS1-64, OS2-64

1280

640

1280

OS0-128, OS1-128, OS2-128

1280

640

1280

LEGACY Data Packet Format

On firmware version 2.3 the data packet format by default is set to LEGACY. This option is backward compatible and is supported on earlier hardware versions as well. The data profile can be modified by changing the configuration parameter udp_profile_lidar.

Lidar Data Format

Note

Gen 1 OS1-16 and OS1-32 customers should note that upgrading to firmware v2.0.0 or higher will change their lidar packet format which reduces their data rates which is not backwards compatible with pre-v2.0.0 clients.

By default the configuration parameter udp_profile_lidar is set to LEGACY. In this mode, lidar packets consist of 16 Measurement Blocks and vary in size relative to the number of channels in the sensor. The packet rate is dependent on the lidar mode. Words are 32 bits in length and little endian. By default, lidar UDP data is forwarded to Port 7502. Please refer to the TCP API portion of this manual for more information on setting this parameter. Alternately, this mode can also be configured via the Web Interface.

Lidar frames are composed of 512, 1024, or 2048 measurement blocks, depending upon lidar mode and are completely deterministic in number per frame and their monotonic order and position within lidar data packets. This determinism allows for efficient lookup table-based decoding in clients.

Each Measurement Block contains:

Header Block [128 bits]

  • Timestamp [64 bit unsigned int] - timestamp of the measurement in nanoseconds.

  • Measurement ID [16 bit unsigned int] - a sequentially incrementing measurement counting up from 0 to 511, or 0 to 1023, or 0 to 2047 depending on lidar_mode.

  • Frame ID [16 bit unsigned int] - index of the lidar scan. Increments every time the sensor completes a rotation, crossing the zero point of the encoder.

  • Encoder Count [32 bit unsigned int] - an azimuth angle as a raw encoder count, starting from 0 with a max value of 90,111 - incrementing 44 ticks every azimuth angle in 2048 mode, 88 ticks in 1024 mode, and 176 ticks in 512 mode. Note: the encoder count is redundant with the Measurement ID and will be deprecated in the future.

N Channel Data Blocks [96 bits each]

  • Range [32 bit unsigned int - only 20 bits used] - range in millimeters, discretized to the nearest 1 millimeters.

  • Calibrated Reflectivity [8 bit unsigned int] - sensor Signal Photons measurements are scaled based on measured range and sensor sensitivity at that range, providing an indication of target reflectivity. Note that calibrated reflectivity has certain hardware requirements. Please refer to the Calibrated Reflectivity section for more details.

  • Signal Photons [16 bit unsigned int] - signal intensity photons in the signal return measurement are reported.

  • Near Infrared Photons [16 bit unsigned int] - NIR photons related to natural environmental illumination are reported.

Measurement Block Status [32 bits]- indicates whether the measurement block contains valid or zero-padded data in its channels’ Data Blocks. Valid = 0xFFFFFFFF, Padded = 0x0. If the Measurement Block Status is Padded (e.g. in the case of channel data being dropped or if the Measurement Block is outside of the azimuth window), values within the Channel Data Blocks will be 0, but values within the Header Block remain valid.

../../../_images/cal_ref_packet_blk_det.png

LEGACY Packet Data Configuration

Packet Size Calculation (LEGACY)

The table below shows the lidar data packet size breakdown for all products when LEGACY profile is configured. Since the size of the measurement block varies proportional to the number of channels in a sensor, all sensors with the same number of channels have the same lidar packet data structure and size.

Packet Size Breakdown- LEGACY Profile

Product

Number of words in Measurement Block

Size of single Measurement Block (Bytes)

Size of lidar packet (Bytes)

OS1-16

53

212

3,392

OS0-32, OS1-32, OS2-32

101

404

6,464

OS0-64, OS1-64, OS2-64

197

788

12,608

OS0-128, OS1-128, OS2-128

389

1,556

24,896

The table below calculates the data of all products operating at the highest lidar modes, 2048x10 or 1024x20 for LEGACY profile assuming a default azimuth window of 360°. Providing a custom azimuth window can further lower data rate. See the Azimuth Window section for details on setting a custom azimuth window.

Data Rate- LEGACY Profile

Product

LEGACY Lidar packet size (Bytes)

LEGACY Lidar packets rate (Hz)

LEGACY Data Rate (Mbps)

OS1-16

3392

1280

34.77

OS0-32, OS1-32, OS2-32

6464

1280

66.23

OS0-64, OS1-64, OS2-64

12608

1280

129.14

OS0-128, OS1-128, OS2-128

24896

1280

254.97

Calibrated Reflectivity

Starting in firmware v2.1.0, sensors have an 8-bit reflectivity data field. Existing sensors in the field that update to v2.1.0 will have default calibration values pushed to them. Sensors that have been factory calibrated for reflectivity will have a higher accuracy of reflectivity.

The command get_calibration_status will return the status of your sensor calibration. The calibration status is returned with the following format:

{
  "reflectivity":
  {
      "valid": "true: if factory calibrated for better accuracy, false: if not calibrated -- using default values and likely has less accuracy",
      "timestamp": "Date when the calibration has been performed"
  }
}

Please contact your support@ouster.io if you have questions on whether your sensor is hardware-enabled for calibrated reflectivity.

Reflectivity Data Mapping

Reflectivity values between 0-100 are linearly mapped for lambertian targets with values between 0% and 100% reflectivity. Values between 101-255 are mapped as log 2 with linear interpolation between logarithmic points for retroreflective targets. The 255 value corresponds to a retroreflector 864x stronger than a 100% lambertian target. The charts below show the mapping functions.

../../../_images/ref_v_rep_1.png
../../../_images/ref_v_rep_2.png
../../../_images/cal_ref_mapping.png

IMU Data Format

IMU UDP Packets are 48 Bytes long and by default are sent to Port 7503 at 100 Hz. Values are little endian.

Note

IMU data format is the same regardless of the lidar data profile selected by the user.

Each IMU data block contains:

  • IMU Diagnostic Time [64 bit unsigned int] - timestamp of monotonic system time since boot in nanoseconds.

  • Accelerometer Read Time [64 bit unsigned int] - timestamp for accelerometer time relative to timestamp_mode in nanoseconds.

  • Gyroscope Read Time [64 bit unsigned int] - timestamp for gyroscope time relative to timestamp_mode in nanoseconds.

  • Acceleration in X-axis [32 bit float] - acceleration in g.

  • Acceleration in Y-axis [32 bit float] - acceleration in g.

  • Acceleration in Z-axis [32 bit float] - acceleration in g.

  • Angular Velocity about X-axis [32 bit float] - Angular velocity in deg per sec.

  • Angular Velocity about Y-axis [32 bit float] - Angular velocity in deg per sec.

  • Angular Velocity about Z-axis [32 bit float] - Angular velocity in deg per sec.

Note that the first timestamp (Words 0,1) is for diagnostics only and is rarely used under normal operation.

The second two timestamps, (Words 2,3) and (Words 4,5), are sampled on the same clock as the lidar data, so should be used for most applications.

Ouster provides timestamps for both the gyro and accelerometer in order to give access to the lowest level information. In most applications it is acceptable to use the average of the two timestamps.

Data Rate - IMU Data Packet

Product

IMU packet size (Bytes)

IMU packets per second

OS1-16

48

100

OS0-32, OS1-32, OS2-32

48

100

OS0-64, OS1-64, OS2-64

48

100

OS0-128, OS1-128, OS2-128

48

100

../../../_images/imu_packet.svg

IMU Packet Format