TCP API Guide

Querying Sensor Info and Intrinsic Calibration

The sensor can be queried and configured using a simple plaintext protocol over TCP on port 7501.

An example session using the unix netcat utility is shown below. Note: “xxx” refers to the sensor serial number. The hostname of the sensor can look like “os-xxx” or “os1-xxx”.

$ nc os-991900123456.local 7501
get_sensor_info

 {"prod_line": "OS-1-128", "prod_pn": "840-103575-06", "prod_sn": "992139000666",
  "image_rev": "ousteros-image-prod-aries-v2.3.0-rc.1+20220319004702.staging", "build_rev": "v2.3.0-rc.1",
  "build_date": "2022-03-18T20:00:29Z", "status": "RUNNING", "initialization_id": 9599936, "base_pn": "",
  "base_sn": "", "proto_rev": ""}

A sensor may have one of the following statuses:

Sensor Status

Status

Description

INITIALIZING

When the sensor is booting and not yet outputting data

WARMUP

Sensor has gone into thermal warmup state

UPDATING

When the sensor is updating the FPGA firmware on the first reboot after a firmware upgrade

RUNNING

When the sensor has reached the final running state where it can output data

STANDBY

The sensor has been configured into a low-power state where sensor is on but not spinning

ERROR

Check error codes in the errors field for more information

UNCONFIGURED

An error with factory calibration that requires a manual power cycle or reboot

Note

If the sensor is set to STANDBY mode some of these commands will not return the expected values.

If the sensor is in an ERROR or UNCONFIGURED state, please contact Ouster support with the diagnostic file found at http://os-9919xxxxxxxx/diag for support.

The following commands will return sensor configuration and calibration information:

Note

If the sensor is set to STANDBY mode some of these commands will not return the expected values.

Sensor Configuration and Calibration

Command

Description

Response Example

get_config_param <active/staged>

Returns all active or staged JSON-formatted sensor configuration. Note: The get_config_param active command is functionally the same as the deprecated command get_config_txt.

{
 "udp_ip": "169.254.175.254",
 "udp_dest": "169.254.175.254",
 "udp_port_lidar": 7502,
 "udp_port_imu": 7503,
 "udp_profile_lidar": "RNG19_RFL8_SIG16_NIR16_DUAL",
 "udp_profile_imu": "LEGACY",
 "columns_per_packet": 16,
 "timestamp_mode": "TIME_FROM_INTERNAL_OSC",
 "sync_pulse_in_polarity": "ACTIVE_HIGH",
 "nmea_in_polarity": "ACTIVE_HIGH",
 "nmea_ignore_valid_char": 0,
 "nmea_baud_rate": "BAUD_9600",
 "nmea_leap_seconds": 0,
 "multipurpose_io_mode": "OFF",
 "sync_pulse_out_polarity": "ACTIVE_HIGH",
 "sync_pulse_out_frequency": 1,
 "sync_pulse_out_angle": 360,
 "sync_pulse_out_pulse_width": 10,
 "auto_start_flag": 1,
 "operating_mode": "NORMAL",
 "lidar_mode": "1024x10",
 "azimuth_window": [90000, 270000],
 "signal_multiplier": 1,
 "phase_lock_enable": false,
 "phase_lock_offset": 0
}

get_sensor_info

Returns JSON-formatted sensor metadata: serial number, hardware and software revision, and sensor status.

{
   "prod_line": "OS-1-128",
   "prod_pn": "840-103575-06",
   "prod_sn": "992139000666",
   "image_rev": "ousteros-image-prod-aries-v2.3.0-rc.1+20220319004702.staging",
   "build_rev": "v2.3.0-rc.1",
   "build_date": "2022-03-18T20:00:29Z",
   "status": "RUNNING",
   "initialization_id": 9599936,
   "base_pn": "",
   "base_sn": "",
   "proto_rev": ""
}

get_time_info

Returns JSON-formatted sensor timing configuration and status of udp timestamp, sync_pulse_in, and multipurpose_io.

{
   "timestamp":
     {
       "time": 3709.04727264,
       "mode": "TIME_FROM_INTERNAL_OSC",
      "time_options":
         {
            "ptp_1588": 3718,
            "sync_pulse_in": 1,
            "internal_osc": 3709
         }
     },
   "sync_pulse_in":
     {
       "locked": 0,
       "polarity": "ACTIVE_HIGH",
       "diagnostics":
         {
            "last_period_nsec": 0,
            "count": 1,
            "count_unfiltered": 0
         }
     },
   "multipurpose_io":
     {
       "mode": "OFF",
       "sync_pulse_out":
        {
          "polarity": "ACTIVE_HIGH",
          "frequency_hz": 1,
          "angle_deg": 360,
          "pulse_width_ms": 10
        },

get_time_info

**Continued from previous page**

      "nmea":
        {
          "locked": 0,
          "polarity": "ACTIVE_HIGH",
          "ignore_valid_char": 0,
          "baud_rate": "BAUD_9600",
          "leap_seconds": 0,
          "diagnostics":
           {
             "decoding":
               {
                 "utc_decoded_count": 0,
                 "date_decoded_count": 0,
                 "not_valid_count": 0,
                 "last_read_message": ""
               },
             "io_checks":
               {
                 "start_char_count": 0,
                 "char_count": 0,
                 "bit_count": 1,
                 "bit_count_unfiltered": 0
               }
           }
        }
     }
}

get_beam_intrinsics

Returns JSON-formatted beam altitude and azimuth offsets, in degrees. Length of arrays is equal to the number of channels in the sensor. Also returns distance between lidar origin and beam origin in mm, to be used for point cloud calculations.

{
  "beam_altitude_angles": [21.01, 20.72, 20.42,
    20.1, 19.79, 19.48, 19.17,
    18.84, 18.55, 18.22, 17.9, 17.6,
    17.27, 16.96, 16.65, 16.32, 15.97,
    15.65, 15.34, 15.01, 14.67, 14.35,
    14.01, 13.68, 13.33, 13.02, 12.67,
    12.34, 11.99, 11.65, 11.33, 10.98,
    10.64, 10.28, 9.949999999999999,
    9.609999999999999, 9.27, 8.92, 8.57,
    8.23, 7.88, 7.54, 7.18, 6.84, 6.47,
    6.13, 5.78, 5.45, 5.09, 4.73,
    4.41, 4.05, 3.69, 3.32, 2.98,
    2.63, 2.27, 1.93, 1.57, 1.22,
    0.85, 0.5, 0.15, -0.19, -0.55, -0.92,
   -1.25, -1.63, -1.98, -2.31, -2.67,
   -3.04, -3.4, -3.74, -4.09, -4.45, -4.8,
   -5.15, -5.5, -5.87, -6.21, -6.57, -6.91,
   -7.25, -7.62, -7.95, -8.300000000000001,
   -8.65, -9.01, -9.35, -9.69, -10.05,
   -10.39, -10.74, -11.09, -11.42, -11.77,
   -12.11, -12.45, -12.8, -13.14, -13.47,
   -13.81, -14.15, -14.48, -14.82, -15.13,
   -15.47, -15.81, -16.15, -16.48, -16.8,
   -17.15, -17.48, -17.79, -18.12, -18.47,
   -18.77, -19.09, -19.42, -19.73, -20.06,
   -20.36, -20.69, -21, -21.32, -21.62, -21.94],
  "beam_azimuth_angles": [4.23, 1.41, -1.4,
   -4.21, 4.22, 1.42, -1.41, -4.22, 4.23,
    1.41, -1.42, -4.21, 4.23, 1.42, -1.4,
   -4.2, 4.23, 1.41, -1.39, -4.21, 4.25,
    1.43, -1.41,-4.22, 4.24, 1.44, -1.41,
   -4.22, 4.23, 1.42, -1.38, -4.22, 4.24,
    1.42, -1.4, -4.23, 4.26, 1.44, -1.41,
   -4.23, 4.24, 1.44, -1.41, -4.23, 4.24,
    1.42, -1.41, -4.24, 4.25, 1.42, -1.39,
   -4.22, 4.25, 1.41, -1.4, -4.23, 4.24,
    1.43, -1.41, -4.23, 4.24, 1.42, -1.41,
   -4.23, 4.25, 1.42, -1.4, -4.24, 4.24,
    1.44, -1.4, -4.24, 4.24, 1.43, -1.4, -4.24,
    4.25, 1.43, -1.41, -4.24, 4.25, 1.42, -1.42,
   -4.22, 4.24, 1.43, -1.4, -4.24, 4.25, 1.44,
   -1.41, -4.24, 4.25, 1.42, -1.41, -4.24,
    4.25, 1.42, -1.41, -4.25, 4.26, 1.43, -1.41,
   -4.26, 4.27, 1.43, -1.4, -4.24, 4.25, 1.43,
   -1.4, -4.24, 4.26, 1.42, -1.4, -4.25, 4.26,
    1.43, -1.41, -4.26, 4.26, 1.42, -1.42,
    -4.26, 4.25, 1.42, -1.42, -4.27],
  "lidar_origin_to_beam_origin_mm": 15.806
}

get_imu_intrinsics

Returns JSON-formatted IMU transformation matrix needed to transform to the Sensor Coordinate Frame.

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

get_lidar_intrinsics

Returns JSON-formatted lidar transformation matrix needed to transform to the Sensor Coordinate Frame.

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

get_alerts <START_CURSOR>

Returns JSON-formatted sensor diagnostic information.

The log list contains alerts when they were activated or deactivated. An optional START_CURSOR argument specifies where the log should start.

The active list contains all currently active alerts.

{
   "log":
  [
    {
        "active": true,
        "category": "UDP_TRANSMISSION",
        "cursor": 0,
        "id": "0x01000018",
        "level": "WARNING",
        "msg": "Client machine announced
            it is not reachable on the
            provided not reachable on
            IMU data port; check that
            udp_dest and udp_port_imu
            configured on the sensor matches
            client IP and port.",
        "msg_verbose": "Failed to send
            imu UDP data to destination
            host 169.254.175.254:7503",
        "realtime": "39850161524"
    },

get_alerts <START_CURSOR>

**Continued from previous page**

{
    "active": true,
    "category": "UDP_TRANSMISSION",
    "cursor": 1,
    "id": "0x01000015",
    "level": "WARNING",
    "msg": "Client machine announced
        it is not reachable on the
        provided lidar data port;
        check that udp_dest and
        udp_port_lidar configured on
        the sensor matches client IP
        and port.",
    "msg_verbose": "Failed to send
        lidar UDP data to destination
        host 169.254.175.254:7502",
    "realtime": "40842065146"
},
{
    "active": true,
    "category": "ETHERNET_LINK_BAD",
    "cursor": 2,
    "id": "0x01000011",
    "level": "WARNING",
    "msg": "Ethernet link bad, please
        check network switch and
        harnessing can support
        1 Gbps Ethernet.",
    "msg_verbose": "Link transitioned
        to 0/Unknown",
    "realtime": "414257307390"
},
{
    "active": true,
    "category": "ETHERNET_LINK_BAD",
    "cursor": 2,
    "id": "0x01000011",
    "level": "WARNING",
    "msg": "Ethernet link bad, please
        check network switch and
        harnessing can support
        1 Gbps Ethernet.",
    "msg_verbose": "Link transitioned
        to 0/Unknown",
    "realtime": "414257307390"
},

get_alerts <START_CURSOR>

*Continues from previous page.*

{
      "active": true,
      "category": "UDP_TRANSMISSION",
      "cursor": 3,
      "id": "0x01000016",
      "level": "WARNING",
      "msg": "Could not send lidar data
          UDP packet to host; check that
          network is up.",
      "msg_verbose": "Failed to send
          lidar UDP data to destination
          host 169.254.175.254:7502",
      "realtime": "414261086316"
  },
  {
      "active": true,
      "category": "UDP_TRANSMISSION",
      "cursor": 4,
      "id": "0x01000019",
      "level": "WARNING",
      "msg": "Could not send IMU UDP
          packet to host; check
          that network is up.",
      "msg_verbose": "Failed to send imu
          UDP data to destination
          host 169.254.175.254:7503",
      "realtime": "414266339945"
  },
  {
      "active": false,
      "category": "ETHERNET_LINK_BAD",
      "cursor": 5,
      "id": "0x01000011",
      "level": "WARNING",
      "msg": "Ethernet link bad,
          please check network switch
          and harnessing can support
          1 Gbps Ethernet.",
      "msg_verbose": "Link transitioned
          to 1000/Full",
      "realtime": "416337486469"
  }
],

get_alerts <START_CURSOR>

*Continues from previous page.*

"next_cursor": 6,
"active":
  [
    {
      "active": true,
      "category": "UDP_TRANSMISSION",
      "cursor": 1,
      "id": "0x01000015",
      "level": "WARNING",
      "msg": "Client machine announced
          it is not reachable on the
          provided lidar data port;
          check that udp_dest and
          udp_port_lidar configured
          on the sensor matches
          client IP and port.",
      "msg_verbose": "Failed to send
          lidar UDP data to destination
          host 169.254.175.254:7502",
      "realtime": "40842065146"
    },
    {
      "active": true,
      "category": "UDP_TRANSMISSION",
      "cursor": 3,
      "id": "0x01000016",
      "level": "WARNING",
      "msg": "Could not send lidar data
          UDP packet to host;
          check that network is up.",
      "msg_verbose": "Failed to send
          lidar UDP data to destination
          host 169.254.175.254:7502",
      "realtime": "414261086316"
    },

get_alerts <START_CURSOR>

*Continues from previous page.*

      {
        "active": true,
        "category": "UDP_TRANSMISSION",
        "cursor": 0,
        "id": "0x01000018",
        "level": "WARNING",
        "msg": "Client machine announced
            it is not reachable on the provided
            not reachable on IMU data port;
            check that udp_dest and
            udp_port_imu configured on the
            sensor matches client IP
            and port.",
        "msg_verbose": "Failed to send imu
            UDP data to destination host
            169.254.175.254:7503",
        "realtime": "39850161524"
      },
      {
        "active": true,
        "category": "UDP_TRANSMISSION",
        "cursor": 4,
        "id": "0x01000019",
        "level": "WARNING",
        "msg": "Could not send IMU UDP
            packet to host; check that
            network is up.",
        "msg_verbose": "Failed to send
            imu UDP data to destination
            host 169.254.175.254:7503",
        "realtime": "414266339945"
      }
    ]
}

get_lidar_data_format

Returns JSON-formatted response that describes the structure of a lidar packet.

columns_per_frame: Number of measurement columns per frame. This can be 512, 1024, or 2048, depending upon the set lidar mode.

columns_per_packet: Number of measurement blocks contained in a single lidar packet. Currently in v2.2.0 and earlier, this is 16. Note: This is not user configurable.

pixel_shift_by_row: Offset in terms of pixel count. Can be used to destagger image. Varies by lidar mode. Length of this array is equal to the number of channels of the sensor.

pixels_per_column: Number of channels of the sensor.

column_window: Index of measurement blocks that are active. Default is [0, lidar_mode-1], e.g. [0,1023]. If there is an azimuth window set, this parameter will reflect which measurement blocks of data are within the region of interest.

{
 "pixels_per_column": 128,
 "columns_per_packet": 16,
 "columns_per_frame": 1024,
 "pixel_shift_by_row": [24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0, 24, 16, 8, 0, 24, 16, 8, 0, 24, 16,
  8, 0]
 "column_window": [0, 1023],
 "udp_profile_lidar": "RNG19_RFL8_SIG16_NIR16_DUAL",
 "udp_profile_imu": "LEGACY"
}

get_lidar_data_format *Continues from previous page.*

udp_profile_lidar - Lidar data profile format [Default LEGACY]. udp_profile_lidar - Lidar data profile format [Default LEGACY]. udp_profile_imu - IMU data profile format [Default LEGACY].

NOTE: This command only works when the sensor is in RUNNING status.

get_calibration_status

Returns JSON-formatted calibration status of the sensor reflectivity. valid: true/false depending on calibration status. timestamp: if valid is true; time at which the calibration was completed.

{
  "reflectivity":
   {
     "valid": true,
     "timestamp": "2021-10-05T00:02:36"
   }
}

get_telemetry

Returns JSON-formatted response that provides sensor system state information. This includes the FPGA Timestamp in ns (Nanoseconds) at which the information was collected from the FPGA, Lidar Input Voltage in mv (Millivolt), Lidar Input Current in ma (Milliamp), Internal Temperature of the sensor in ºC (Degree Celsius) and Phase Lock status namely LOCKED, LOST, DISABLED.

{
  "input_current_ma": 758,
  "input_voltage_mv": 23606,
  "internal_temperature_deg_c": 45,
  "phase_lock_status": "DISABLED",
  "timestamp_ns": 2962666299310
}

Note

Using get_telemetry, Internal temperature can only be measured with Rev 06 and above sensors.

Note

Phase lock output will not indicate loss of lock if the PTP source is lost.

Querying Active or Staged Parameters

Sensor configurations and operating modes can also be queried over TCP. Below is the command format:

get_config_param active <parameter> will return the current active configuration parameter values.

get_config_param staged <parameter> will return the parameter values that will take place after issuing a reinitialize command or after sensor reboot.

Warning

The command get_config_txt is deprecated and superseded by get_config_param active, which provides the same response. get_config_txt will be removed in a future firmware.

An example session using the unix netcat utility is shown below:

$ nc os-991900123456 7501
get_config_param active lidar_mode
1024x10

The following commands will return sensor active or staged configuration parameters:

Sensor Configurations

get_config_param

Command Description

Response

udp_dest

Returns the destination to which the sensor sends UDP traffic. Note: udp_ip is the deprecated parameter name whose value will always be the same as udp_dest.

"" (default)

udp_port_lidar

Returns the port number of lidar UDP data packets.

7502 (default)

udp_port_imu

Returns the port number of IMU UDP data packets.

7503 (default)

sync_pulse_in_polarity

Returns the polarity of the SYNC_PULSE_IN input, which controls polarity of SYNC_PULSE_IN pin when timestamp_mode is set in TIME_FROM_SYNC_PULSE_IN. Use ACTIVE_HIGH if PPS is active high, idle low.

Either ACTIVE_HIGH (default) or ACTIVE_LOW

sync_pulse_out_polarity

Returns the polarity of SYNC_PULSE_OUT output, if the sensor is using this for time synchronization.

Either ACTIVE_HIGH or ACTIVE_LOW (default)

sync_pulse_out_frequency

Returns the output SYNC_PULSE_OUT pulse rate in Hz.

1 (default)

sync_pulse_out_angle

Returns the angle in terms of degrees that the sensor traverses between each SYNC_PULSE_OUT pulse. E.g. a value of 180 means a sync pulse is sent out every 180° for a total of two pulses per revolution and angular frequency of 20 Hz if the sensor is 1024x10 Hz lidar mode.

360 (default)

sync_pulse_out_pulse_width

Returns the output SYNC_PULSE_OUT pulse width in ms.

10 (default)

nmea_in_polarity

Returns the polarity of NMEA UART input messages. See Time Synchronization section in sensor user manual for NMEA use case. Use ACTIVE_HIGH if UART is active high, idle low, and start bit is after a falling edge.

Either ACTIVE_HIGH (default) or ACTIVE_LOW

nmea_ignore_valid_char

Returns 0 if NMEA UART input $GPRMC messages should be ignored if valid character is not set, and 1 if messages should be used for time syncing regardless of the valid character.

Either 0 (default) or 1

nmea_baud_rate

Returns BAUD_9600 (default) or BAUD_115200 for the expected baud rate the sensor is attempting to decode for NMEA UART input $GPRMC messages.

Either BAUD_9600 or BAUD_115200

nmea_leap_seconds

Returns the number of leap seconds that will be added to the UDP timestamp when calculating seconds since 00:00:00 Thursday, 1 January 1970. For Unix Epoch time, this should be set to 0.

Either 0 (default) or a positive integer

azimuth_window

Returns the visible region of interest of the sensor in millidegrees. Only data within the specified bounds of the region of interest is sent from the sensor.

[0,360000] (defaults to an azimuth window of 360°)

signal_multiplier

Returns the value that the signal_multiplier is configured. By default the sensor has a signal multiplier value of 1.

Either 1 (default) or 2 or 3

udp_profile_lidar

Returns the configuration of the LIDAR data packets. Valid values are LEGACY [Default], RNG19_RFL8_SIG16_NIR16, RNG19_RFL8_SIG16_NIR16_DUAL, RNG15_RFL8_NIR8

LEGACY

udp_profile_imu

Returns the configuration of the IMU data packets. Valid value is LEGACY

LEGACY

phase_lock_enable

Returns whether phase locking is enabled.

Either false (default) or true

phase_lock_offset

Returns the angle in the Lidar Coordinate Frame that sensors are locked to in millidegrees if phase locking is enabled.

Integer between 0 and 360000 inclusive

lidar_mode

Returns a string indicating the horizontal resolution and rotation frequency [Hz].

One of 512x10, 1024x10, 2048x10, 512x20, or 1024x20

timestamp_mode

Returns the method used to timestamp measurements.

One of TIME_FROM_INTERNAL_OSC, TIME_FROM_PTP_1588, or TIME_FROM_SYNC_PULSE_IN

multipurpose_io_mode

Returns the configured mode of the MULTIPURPOSE_IO pin. See Time Synchronization section in sensor user manual for a detailed description of each option.

One of OFF (default), INPUT_NMEA_UART, OUTPUT_FROM_INTERNAL_OSC, OUTPUT_FROM_SYNC_PULSE_IN, OUTPUT_FROM_PTP_1588, or OUTPUT_FROM_ENCODER_ANGLE

operating_mode

Returns the operating mode that the sensor is in. NORMAL is the default value. STANDBY is a low power (5W) operating mode. Note: auto_start_flag is soon to be deprecated parameter name where auto_start_flag 0 is equivalent to operating_mode STANDBY and auto_start_flag 1 is equivalent to operating_mode NORMAL.

Either NORMAL (default) or STANDBY (low power/standby state)

Setting Configuration Parameters

set_config_param <parameter> <value> will set new values for configuration parameters, which will take effect after issuing the reinitialize command or after sensor reset.

reinitialize will reinitialize the sensor so the staged values of the parameters will take effect immediately.

save_config_params will write new values of active parameters into a configuration file, so they will persist after sensor reset. In order to permanently change a parameter in the configuration file, first use set_config_param to update the parameter in a staging area, then use reinitialize to make that parameter active. Only after the parameter is made active will save_config_params capture it to persist after reset.

Warning

The command write_config_txt will be deprecated in a future firmware. The command save_config_params provides the same response.

While in STANDBY mode, we can set the config parameters, but it will not take effect until we switch the sensor back to NORMAL mode.

set_udp_dest_auto will automatically determine the sender’s IP address at the time the command was sent, and set it as the destination of UDP traffic. This takes effect after issuing a reinitialize command. Using this command has the same effect as using set_config_param udp_dest <ip address>.

An example session using the unix netcat utility is shown below.

Note

In the example below, to distinguish between the command and expected response, a dash has been added before the expected response. The actual response will be without the dash.

$ nc os-991900123456 7501
set_config_param lidar_mode 512x20
-set_config_param
set_udp_dest_auto
-set_udp_dest_auto
reinitialize
-reinitialize
save_config_params
-save_config_params

The following commands will set sensor configuration parameters:

Note

Each of the following commands have two responses: * set_config_param on Success * error: Otherwise

Setting Config Parameters

set_config_param

Command Description

udp_dest <destination>

Set the <destination> to which the sensor sends UDP traffic. On boot, the sensor will not output data until this is set. If the IP address is not known, this can also be accomplished with the set_udp_dest_auto command (details above). The sensor supports unicast, IPv4 broadcast (255.255.255.255), IPv4 multicast (239.x.x.x), and IPv6 multicast (ff02::01) addresses. Note: udp_ip is the deprecated parameter name. However during the deprecation phase, either udp_ip or udp_dest may be used. When either one is updated, the other parameter value will be updated to match upon setting the parameter value.

udp_port_lidar <port>

Set the <port> on udp_dest to which lidar data will be sent (7502, default).

udp_port_imu <port>

Set the <port> on udp_dest to which IMU data will be sent (7503, default).

sync_pulse_in_polarity <ACTIVE_HIGH/ACTIVE_LOW>

Set the polarity of SYNC_PULSE_IN input, which controls polarity of SYNC_PULSE_IN pin when timestamp_mode is set in TIME_FROM_SYNC_PULSE_IN.

sync_pulse_out_polarity <ACTIVE_HIGH/ACTIVE_LOW>

Set the polarity of SYNC_PULSE_OUT output, if the sensor is set as the master sensor used for time synchronization.

sync_pulse_out_frequency <rate in Hz>

Set output SYNC_PULSE_OUT rate. Valid inputs are integers >0 Hz, but also limited by the criteria described in the Time Synchronization section of the Firmware User Manual.

sync_pulse_out_angle <angle in deg>

Set output SYNC_PULSE_OUT rate defined by rotation angle. E.g. a value of 180 means a sync pulse is sent out every 180° for a total of two pulses per revolution and angular frequency of 20 Hz if the sensor is 1024x10 Hz lidar mode. Valid inputs are integers between 0 and 360 inclusive but also limited by the criteria described in the Time Synchronization section of Firmware User Manual.

sync_pulse_out_pulse_width <width in ms>

Set output SYNC_PULSE_OUT pulse width in ms, in 1 ms increments. Valid inputs are integers greater than 0 ms, but also limited by the criteria described in the Time Synchronization section of Firmware User Manual.

nmea_in_polarity <ACTIVE_HIGH/ACTIVE_LOW>

Set the polarity of NMEA UART input $GPRMC messages. See Time Synchronization section in sensor user manual for NMEA use case. Use ACTIVE_HIGH if UART is active high, idle low, and start bit is after a falling edge.

nmea_ignore_valid_char <1/0>

Set 0 if NMEA UART input $GPRMC messages should be ignored if valid character is not set, and 1 if messages should be used for time syncing regardless of the valid character.

nmea_baud_rate <rate in baud/s>

Set BAUD_9600 (default) or BAUD_115200 for the expected baud rate the sensor is attempting to decode for NMEA UART input $GPRMC messages.

nmea_leap_seconds <s>

Set an integer number of leap seconds that will be added to the UDP timestamp when calculating seconds since 00:00:00 Thursday, 1 January 1970. For Unix Epoch time, this should be set to 0.

azimuth_window <[min_bound_millideg, max_bound_millideg]>

Set the visible region of interest of the sensor in millidegrees. Only data from within the specified azimuth window bounds is sent.

phase_lock_enable <true/false>

Set whether phase locking is enabled. See Firmware User Manual for more details on using phase lock.

phase_lock_offset <angle in millideg>

Set the angle in the Lidar Coordinate Frame that sensors are locked to in millidegrees if phase locking is enabled. Angle is traversed at the top of the second.

lidar_mode <mode>

Set the horizontal resolution and rotation rate of the sensor. Valid modes are 512x10, 1024x10, 2048x10, 512x20, and 1024x20. The effective range of the sensor is increased by 15-20% for every halving of the number of points gathered e.g. 512x10 has 15-20% longer range than 512x20.

timestamp_mode <mode>

Set the method used to timestamp measurements. Valid modes are TIME_FROM_INTERNAL_OSC, TIME_FROM_SYNC_PULSE_IN, or TIME_FROM_PTP_1588.

multipurpose_io_mode <mode>

Configure the mode of the MULTIPURPOSE_IO pin. Valid modes are OFF, INPUT_NMEA_UART, OUTPUT_FROM_INTERNAL_OSC, OUTPUT_FROM_SYNC_PULSE_IN, OUTPUT_FROM_PTP_1588, or OUTPUT_FROM_ENCODER_ANGLE.

udp_profile_lidar

Configure the LIDAR data profile, valid modes are LEGACY [Default], RNG19_RFL8_SIG16_NIR16, RNG19_RFL8_SIG16_NIR16_DUAL, RNG15_RFL8_NIR8.

operating_mode <NORMAL/STANDBY>

Set NORMAL to put the sensor into a normal operating mode or STANDBY to put the sensor into a low power (5W) operating mode where the motor does not spin and lasers do not fire. Note: auto_start_flag <1/0> is soon to be deprecated parameter name where auto_start_flag 0 is equivalent to operating_mode STANDBY and auto_start_flag 1 is equivalent to operating_mode NORMAL. However, during the deprecation phase, either operating_mode or auto_start_flag may be used. When either one is updated, the other parameter value will be updated to match upon setting the parameter value.

Reinitialize, Write Configuration, and Auto Destination UDP

Command

Command Description

Response

reinitialize or reinit

Restarts the sensor. Changes to lidar, multipurpose_io, and timestamp modes will only take effect after reinitialization.

reinitialize or reinit on success

save_config_params

Makes all current parameter settings persist after reboot.

save_config_params on success

set_udp_dest_auto

Set the destination of UDP traffic to the destination address that issued the command.

set_udp_dest_auto on success