Module ouster.client
Core
- exception ClientOverflow[source]
Raised when data loss is possible due to internal buffers filling up.
- class PacketSource[source]
Bases:
Protocol
Represents a single-sensor data stream.
- __iter__()[source]
A PacketSource supports
Iterable[Packet]
.Currently defined explicitly due to: https://github.com/python/typing/issues/561
- Return type:
Iterator
[Union
[ImuPacket
,LidarPacket
]]
- property metadata: SensorInfo
Metadata associated with the packet stream.
- class Packets(it, metadata)[source]
Create a
PacketSource
from an existing iterator.- Parameters:
it (
Iterable
[Union
[ImuPacket
,LidarPacket
]]) – A stream of packetsmetadata (
SensorInfo
) – Metadata for the packet stream
- property metadata: SensorInfo
Metadata associated with the packet stream.
- __iter__()[source]
Return the underlying iterator.
- Return type:
Iterator
[Union
[ImuPacket
,LidarPacket
]]
- class Sensor(hostname, lidar_port, imu_port, *, metadata=None, buf_size=128, timeout=2.0, _overflow_err=False, _flush_before_read=True, _flush_frames=5, _legacy_format=False, soft_id_check=False, _skip_metadata_beam_validation=False)[source]
A packet source listening on local UDP ports.
Uses a separate thread that fills internal buffers without holding the GIL.
Note
Make sure
close()
will be called on all instances before Python attempts to exit, or the interpreter will hang waiting to join the thread (like any other non-daemonized Python thread).Neither the ports nor udp destination configuration on the sensor will be updated. The metadata will be fetched over the network from the sensor unless explicitly provided using the
metadata
parameter.- Parameters:
hostname (
str
) – hostname or IP address of the sensorlidar_port (
int
) – UDP port to listen on for lidar dataimu_port (
int
) – UDP port to listen on for imu datametadata (
Optional
[SensorInfo
]) – explicitly provide metadata for the streambuf_size (
int
) – number of packets to buffer before dropping datatimeout (
Optional
[float
]) – seconds to wait for packets before signaling error or None_overflow_err (
bool
) – if True, raise ClientOverflow_flush_before_read (
bool
) – if True, try to clear buffers before reading_flush_frames (
int
) – the number of frames to skip/flush on start of a new iter_legacy_format (
bool
) – if True, use legacy metadata formatsoft_id_check (
bool
) – if True, don’t skip lidar packets buffers on,mismatch (id) –
_skip_metadata_beam_validation (
bool
) – if True, skip metadata beam angle check
- Raises:
ClientError – If initializing the client fails.
- write_metadata(path)[source]
Save metadata to disk.
- Parameters:
path (
str
) – path to write- Return type:
None
- property metadata: SensorInfo
Metadata associated with the packet stream.
- __iter__()[source]
Access the UDP data stream as an iterator.
Reading may block waiting for network data for up to the specified timeout. Failing to consume this iterator faster than the data rate of the sensor may cause packets to be dropped. Returned packet is meant to be consumed prior to incrementing the iterator, and storing the returned packet in a container may result in the contents being invalidated. If such behaviour is necessary, deepcopy the packets upon retrieval.
- Raises:
ClientTimeout – if no packets are received within the configured timeout
ClientError – if the client enters an unspecified error state
ValueError – if the packet source has already been closed
- Return type:
Iterator
[Union
[ImuPacket
,LidarPacket
]]
- flush(n_frames=3, *, full=False)[source]
Drop some data to clear internal buffers.
- Parameters:
n_frames (
int
) – number of frames to dropfull – clear internal buffers first, so data is read from the OS receive buffers (or the network) directly
- Return type:
int
- Returns:
The number of packets dropped
- Raises:
ClientTimeout – if a lidar packet is not received within the configured timeout
ClientError – if the client enters an unspecified error state
- class Scans(source, *, complete=False, timeout=2.0, fields=None, _max_latency=0)[source]
An iterable stream of scans batched from a PacketSource.
Batching will emit a scan every time the frame_id increments (i.e. on receiving first packet in the next scan). Reordered packets will be handled, except across frame boundaries: packets from the previous scan will be dropped.
Optionally filters out incomplete frames and enforces a timeout. A batching timeout can be useful to detect when we’re only receiving incomplete frames or only imu packets. Can also be configured to manage internal buffers for soft real-time applications.
- Parameters:
source (
PacketSource
) – any source of packetscomplete (
bool
) – if True, only return full scanstimeout (
Optional
[float
]) – seconds to wait for a scan before error or Nonefields (
Optional
[Dict
[ChanField
,Type
[unsignedinteger
]]]) – specify which channel fields to populate on LidarScans_max_latency (
int
) – (experimental) approximate max number of frames to buffer
- property metadata: SensorInfo
Return metadata from the underlying PacketSource.
- property is_live: bool
True if data obtained from the RUNNING sensor or as a stream from the socket
- Returns:
True if data obtained from the RUNNING sensor or as a stream from the socket False if data is read from a stored media. Restarting an
iter()
means thatthe data can be read again.
- property is_seekable: bool
True for non-live sources, This property can be True regardless of scan source being indexed or not.
- property is_indexed: bool
True for IndexedPcap and OSF scan sources, this property tells users whether the underlying source allows for random access of scans, see __getitem__.
- property fields: Dict[ChanField, Type[unsignedinteger]]
Field types are present in the LidarScan objects on read from iterator
- property scans_num: int | None
Number of scans available, in case of a live sensor or non-indexable scan source this method returns None
- classmethod sample(hostname='localhost', n=1, lidar_port=7502, *, metadata=None)[source]
Conveniently sample n consecutive scans from a sensor.
Does not leave UDP ports open. Suitable for interactive use.
- Parameters:
hostname (
str
) – hostname of the sensorn (
int
) – number of consecutive frames in each samplelidar_port (
int
) – UDP port to listen on for lidar datametadata (
Optional
[SensorInfo
]) – explicitly provide metadata for the stream
- Return type:
Tuple
[SensorInfo
,Iterator
[List
[LidarScan
]]]- Returns:
A tuple of metadata queried from the sensor and an iterator that samples n consecutive scans
- classmethod stream(hostname='localhost', lidar_port=7502, *, buf_size=640, timeout=2.0, complete=True, metadata=None, fields=None)[source]
Stream scans from a sensor.
Will drop frames preemptively to avoid filling up internal buffers and to avoid returning frames older than the scanning period of the sensor.
- Parameters:
hostname (
str
) – hostname of the sensorlidar_port (
int
) – UDP port to listen on for lidar datatimeout (
Optional
[float
]) – seconds to wait for scans before signaling errorcomplete (
bool
) – if True, only return full scansmetadata (
Optional
[SensorInfo
]) – explicitly provide metadata for the streamfields (
Optional
[Dict
[ChanField
,Type
[unsignedinteger
]]]) – specify which channel fields to populate on LidarScans
- Return type:
Metadata
- class SensorInfo
Sensor Info required to interpret UDP data streams.
See the sensor documentation for the meaning of each property.
- Parameters:
raw (str) – json string to parse
- property beam_altitude_angles
Beam altitude angles, useful for XYZ projection.
- property beam_azimuth_angles
Beam azimuth angles, useful for XYZ projection.
- property beam_to_lidar_transform
Homogenous transformation matrix reprsenting Beam to Lidar Transform
- property build_date
Build date
- property cal
sensor calibration
- property config
sensor config
- property extrinsic
Extrinsic Matrix.
- property format
Describes the structure of a lidar packet. See class DataFormat.
- static from_default()
Create gen-1 OS-1-64 SensorInfo populated with design values.
- property fw_rev
Sensor firmware revision.
- has_fields_equal()
Compare public fields”
- property hostname
Sensor hostname.
- property image_rev
Image rev
- property imu_to_sensor_transform
Homogenous transformation matrix representing IMU offset to Sensor Coordinate Frame.
- property init_id
Initialization id.
- property lidar_origin_to_beam_origin_mm
Distance between lidar origin and beam origin in millimeters.
- property lidar_to_sensor_transform
Homogeneous transformation matrix from Lidar Coordinate Frame to Sensor Coordinate Frame.
- property mode
Lidar mode, e.g., 1024x10.
- original_string()
Return original string that initialized sensor_info”
- property prod_line
Product line, e.g., ‘OS-1-128’.
- property prod_pn
Prod pn
- property sn
Sensor serial number.
- property status
sensor status
- property udp_port_imu
Configured port for imu data.
- property udp_port_lidar
Configured port for lidar data.
- updated_metadata_string()
Return metadata string made from updated entries”
- class DataFormat
Data Format of a packet coming from sensor
See sensor documentation for the meaning of each property
- property column_window
Firing window of sensor, set by config.azimuth_window
- Type:
Tuple[int, int]
- property columns_per_frame
Columns per frame in the lidar packet, corresponding with lidar_mode
- Type:
int
- property columns_per_packet
Columns per packet in the lidar packet, typically 16
- Type:
int
- property fps
Frames per second, e.g., 10 for lidar_mode 1024x10
- Type:
int
- property pixel_shift_by_row
Shift of pixels by row to create natural images
- Type:
List[int]
- property pixels_per_column
Pixels per column in the lidar packet, synonymous with the number of beams of the sensor
- Type:
int
- property udp_profile_imu
IMU packet profile
- property udp_profile_lidar
Lidar packet profile
- class SensorConfig
Corresponds to sensor config parameters. Please see sensor documentation for the meaning of each property.
- Parameters:
raw (str) – json string to parse
- property accel_fsr
The accelerometer full scale measurement range to use. See sensor documentation for details.
- property azimuth_window
Tuple representing the visible region of interest of the sensor in millidegrees, .e.g., (0, 360000) for full visibility.
- property columns_per_packet
Measurement blocks per UDP packet. See sensor documentation for details.
- property gyro_fsr
The gyro full scale measurement range to use. See sensor documentation for details.
- property lidar_mode
Horizontal and Vertical Resolution rate of sensor as mode, e.g., 1024x10. See class LidarMode.
- property min_range_threshold_cm
The minimum detection range of the sensor in cm. See sensor documentation for details.
- property multipurpose_io_mode
Mode of MULTIPURPOSE_IO pin. See class MultipurposeIOMode.
- property nmea_baud_rate
Expected baud rate sensor attempts to decode for NMEA UART input $GPRMC messages.
- property nmea_ignore_valid_char
NMEA Ignore Valid Char. True corresponds to 1 and False to 0 for property; see sensor documentation for details.
- property nmea_in_polarity
Polarity of NMEA UART input $GPRMC messages. See sensor documentation for details.
- property nmea_leap_seconds
Integer number of leap seconds that will be added to the UDP timetsamp when calculating seconds since Unix Epoch time. See sensor documentation for details.
- property operating_mode
Operating Mode of sensor. See class OperatingMode.
- property phase_lock_enable
Enable phase lock. See sensor documentation for more details.
- property phase_lock_offset
Angle in Lidar Coordinate Frame that sensors are locked to, in millidegrees. See sensor documentation for details.
- property return_order
The priority of sensor returns to output. See sensor documentation for details.
- property signal_multiplier
Multiplier for signal strength of sensor, corresponding to maximum allowable azimuth_window. Gen 2 Only.
- property sync_pulse_in_polarity
Polarity of SYNC_PULSE_IN pin. See sensor documentation for details.
- property sync_pulse_out_angle
Polarity of SYNC_PULSE_OUT output. See sensor documentation for details.
- property sync_pulse_out_frequency
SYNC_PULSE_OUT rate. See sensor documentation for details.
- property sync_pulse_out_polarity
Polarity of SYNC_PULSE_OUT output. See sensor documentation for details.
- property sync_pulse_out_pulse_width
SYNC_PULSE_OUT pulse width in ms. See sensor documentation for details.
- property timestamp_mode
Timestamp mode of sensor. See class TimestampMode.
- property udp_dest
Destination to which sensor sends UDP traffic.
- property udp_port_imu
Port on UDP destination to which IMU data will be sent.
- property udp_port_lidar
Port on UDP destination to which lidar data will be sent.
- property udp_profile_imu
UDP packet format for imu data. See sensor documentation for details.
- property udp_profile_lidar
UDP packet format for lidar data. See sensor documentation for details.
- get_config()
Returns sensor config parameters as SensorConfig.
- Parameters:
hostname (str) – hostname of the sensor
active (bool) – return active or staged sensor configuration
- set_config()
Set sensor config parameters on sensor.
- Parameters:
hostname (str) – hostname of the sensor
config (SensorConfig) – config to set sensor parameters to
persist (bool) – persist parameters after sensor disconnection (default = False)
udp_dest_auto (bool) – automatically determine sender’s IP at the time command was sent and set it as destination of UDP traffic. Function will error out if config has udp_dest member. (default = False)
force_reinit (bool) – forces the sensor to re-init during set_config even when config params have not changed. (default = False)
- class LidarMode
Possible Lidar Modes of sensor.
Determines to horizontal and vertical resolution rates of sensor. See sensor documentation for details.
Members:
MODE_UNKNOWN
MODE_512x10
MODE_512x20
MODE_1024x10
MODE_1024x20
MODE_2048x10
MODE_4096x5
MODE_UNSPEC
- MODE_1024x10 = <LidarMode.MODE_1024x10: 3>
- MODE_1024x20 = <LidarMode.MODE_1024x20: 4>
- MODE_2048x10 = <LidarMode.MODE_2048x10: 5>
- MODE_4096x5 = <LidarMode.MODE_4096x5: 6>
- MODE_512x10 = <LidarMode.MODE_512x10: 1>
- MODE_512x20 = <LidarMode.MODE_512x20: 2>
- MODE_UNKNOWN = <LidarMode.MODE_UNKNOWN: 0>
- MODE_UNSPEC = <LidarMode.MODE_UNKNOWN: 0>
- property cols
Returns columns of lidar mode, e.g., 1024 for LidarMode 1024x10.
- property frequency
Returns frequency of lidar mode, e.g. 10 for LidarMode 512x10.
- from_string()
Create LidarMode from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class TimestampMode
Possible Timestamp modes of sensor.
See sensor documentation for details.
Members:
UNKNOWN
TIME_FROM_INTERNAL_OSC
TIME_FROM_SYNC_PULSE_IN
TIME_FROM_PTP_1588
TIME_FROM_UNSPEC
- TIME_FROM_INTERNAL_OSC = <TimestampMode.TIME_FROM_INTERNAL_OSC: 1>
- TIME_FROM_PTP_1588 = <TimestampMode.TIME_FROM_PTP_1588: 3>
- TIME_FROM_SYNC_PULSE_IN = <TimestampMode.TIME_FROM_SYNC_PULSE_IN: 2>
- TIME_FROM_UNSPEC = <TimestampMode.UNKNOWN: 0>
- UNKNOWN = <TimestampMode.UNKNOWN: 0>
- from_string()
Create TimestampMode from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class OperatingMode
Possible Operating modes of sensor.
See sensor documentation for details.
Members:
OPERATING_NORMAL
OPERATING_STANDBY
- OPERATING_NORMAL = <OperatingMode.OPERATING_NORMAL: 1>
- OPERATING_STANDBY = <OperatingMode.OPERATING_STANDBY: 2>
- static from_string()
Create enum value from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class MultipurposeIOMode
Mode of MULTIPURPOSE_IO pin.
See sensor documentation for details.
Members:
MULTIPURPOSE_OFF
MULTIPURPOSE_INPUT_NMEA_UART
MULTIPURPOSE_OUTPUT_FROM_INTERNAL_OSC
MULTIPURPOSE_OUTPUT_FROM_SYNC_PULSE_IN
MULTIPURPOSE_OUTPUT_FROM_PTP_1588
MULTIPURPOSE_OUTPUT_FROM_ENCODER_ANGLE
- MULTIPURPOSE_INPUT_NMEA_UART = <MultipurposeIOMode.MULTIPURPOSE_INPUT_NMEA_UART: 2>
- MULTIPURPOSE_OFF = <MultipurposeIOMode.MULTIPURPOSE_OFF: 1>
- MULTIPURPOSE_OUTPUT_FROM_ENCODER_ANGLE = <MultipurposeIOMode.MULTIPURPOSE_OUTPUT_FROM_ENCODER_ANGLE: 6>
- MULTIPURPOSE_OUTPUT_FROM_INTERNAL_OSC = <MultipurposeIOMode.MULTIPURPOSE_OUTPUT_FROM_INTERNAL_OSC: 3>
- MULTIPURPOSE_OUTPUT_FROM_PTP_1588 = <MultipurposeIOMode.MULTIPURPOSE_OUTPUT_FROM_PTP_1588: 5>
- MULTIPURPOSE_OUTPUT_FROM_SYNC_PULSE_IN = <MultipurposeIOMode.MULTIPURPOSE_OUTPUT_FROM_SYNC_PULSE_IN: 4>
- static from_string()
Create enum value from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class Polarity
Pulse Polarity.
Applicable to several Polarity settings on sensor.
Members:
POLARITY_ACTIVE_LOW
POLARITY_ACTIVE_HIGH
- POLARITY_ACTIVE_HIGH = <Polarity.POLARITY_ACTIVE_HIGH: 2>
- POLARITY_ACTIVE_LOW = <Polarity.POLARITY_ACTIVE_LOW: 1>
- static from_string()
Create enum value from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class NMEABaudRate
Expected baud rate sensor attempts to decode for NMEA UART input $GPRMC messages.
Members:
BAUD_9600
BAUD_115200
- BAUD_115200 = <NMEABaudRate.BAUD_115200: 2>
- BAUD_9600 = <NMEABaudRate.BAUD_9600: 1>
- static from_string()
Create enum value from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class UDPProfileLidar
UDP lidar profile.
Members:
PROFILE_LIDAR_UNKNOWN
PROFILE_LIDAR_LEGACY
PROFILE_LIDAR_RNG19_RFL8_SIG16_NIR16_DUAL
PROFILE_LIDAR_RNG19_RFL8_SIG16_NIR16
PROFILE_LIDAR_RNG15_RFL8_NIR8
PROFILE_LIDAR_FIVE_WORD_PIXEL
PROFILE_LIDAR_FUSA_RNG15_RFL8_NIR8_DUAL
- PROFILE_LIDAR_FIVE_WORD_PIXEL = <UDPProfileLidar.PROFILE_LIDAR_FIVE_WORD_PIXEL: 5>
- PROFILE_LIDAR_FUSA_RNG15_RFL8_NIR8_DUAL = <UDPProfileLidar.PROFILE_LIDAR_FUSA_RNG15_RFL8_NIR8_DUAL: 6>
- PROFILE_LIDAR_LEGACY = <UDPProfileLidar.PROFILE_LIDAR_LEGACY: 1>
- PROFILE_LIDAR_RNG15_RFL8_NIR8 = <UDPProfileLidar.PROFILE_LIDAR_RNG15_RFL8_NIR8: 4>
- PROFILE_LIDAR_RNG19_RFL8_SIG16_NIR16 = <UDPProfileLidar.PROFILE_LIDAR_RNG19_RFL8_SIG16_NIR16: 3>
- PROFILE_LIDAR_RNG19_RFL8_SIG16_NIR16_DUAL = <UDPProfileLidar.PROFILE_LIDAR_RNG19_RFL8_SIG16_NIR16_DUAL: 2>
- PROFILE_LIDAR_UNKNOWN = <UDPProfileLidar.PROFILE_LIDAR_UNKNOWN: 0>
- from_string()
Create UDPProfileLidar from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
Data
- BufferT
alias of
Union
[bytes
,bytearray
,memoryview
,ndarray
]
- Packet
alias of
Union
[ImuPacket
,LidarPacket
]
- class ImuPacket(data=None, info=None, timestamp=None, *, packet_format=None)[source]
Read IMU Packet data from a buffer.
- Parameters:
data (
Union
[bytes
,bytearray
,memoryview
,ndarray
,None
]) – Buffer containing the packet payloadinfo (
Optional
[SensorInfo
]) – Metadata associated with the sensor packet streamtimestamp (
Optional
[float
]) – A capture timestamp, in seconds
- Raises:
ValueError – If the buffer is smaller than the size specified by the packet format
- property sys_ts: int
System timestamp in nanoseconds.
- property accel_ts: int
Accelerometer read time in nanoseconds.
- property gyro_ts: int
Gyro read time in nanoseconds.
- property accel: ndarray
Acceleration as a 3-D vector in G.
- property angular_vel: ndarray
Angular velocity as a 3-D vector in deg/second.
- class LidarPacket(data=None, info=None, timestamp=None, *, packet_format=None, _raise_on_id_check=True)[source]
Read lidar packet data as numpy arrays.
The dimensions of returned arrays depend on the sensor product line and configuration. Measurement headers will be arrays of size matching the configured
columns_per_packet
, while measurement fields will be 2d arrays of sizepixels_per_column
bycolumns_per_packet
.- Parameters:
data (
Union
[bytes
,bytearray
,memoryview
,ndarray
,None
]) – Buffer containing the packet payloadinfo (
Optional
[SensorInfo
]) – Metadata associated with the sensor packet streamtimestamp (
Optional
[float
]) – A capture timestamp, in seconds_raise_on_id_check (
bool
) – raise PacketIdError if metadata init_id/sn doesn’t match packet init_id/sn.
- Raises:
ValueError – If the buffer is smaller than the size specified by the packet format, or if the init_id doesn’t match the metadata
- property id_error: bool
Check the metadata init_id/sn and packet init_id/sn mismatch.
- property packet_type: int
Get the type header of the packet.
- property frame_id: int
Get the frame id of the packet.
- property init_id: int
Get the initialization id of the packet.
- property prod_sn: int
Get the serial no header of the packet.
- property countdown_thermal_shutdown: int
Get the thermal shutdown countdown of the packet.
- property countdown_shot_limiting: int
Get the shot limiting countdown of the packet.
- property thermal_shutdown: int
Get the thermal shutdown status of the packet.
- property shot_limiting: int
Get the shot limiting status of the packet.
- field(field)[source]
Create a view of the specified channel field.
- Parameters:
field (
ChanField
) – The channel field to view- Return type:
ndarray
- Returns:
A numpy array containing a copy of the specified field values
- property timestamp: ndarray
Parse the measurement block timestamps out of a packet buffer.
- Returns:
An array of the timestamps of all measurement blocks in the packet.
- property measurement_id: ndarray
Parse the measurement ids out of a packet buffer.
- Returns:
An array of the ids of all measurement blocks in the packet.
- property status: ndarray
Parse the measurement statuses of a packet buffer.
- Returns:
An array of the statuses of all measurement blocks in the packet.
- class ChanField
Channel data block fields
Members:
RANGE
RANGE2
SIGNAL
SIGNAL2
REFLECTIVITY
REFLECTIVITY2
NEAR_IR
FLAGS
FLAGS2
RAW_HEADERS
CUSTOM0
CUSTOM1
CUSTOM2
CUSTOM3
CUSTOM4
CUSTOM5
CUSTOM6
CUSTOM7
CUSTOM8
CUSTOM9
RAW32_WORD1
RAW32_WORD2
RAW32_WORD3
RAW32_WORD4
RAW32_WORD5
RAW32_WORD6
RAW32_WORD7
RAW32_WORD8
RAW32_WORD9
- CUSTOM0 = <ChanField.CUSTOM0: 50>
- CUSTOM1 = <ChanField.CUSTOM1: 51>
- CUSTOM2 = <ChanField.CUSTOM2: 52>
- CUSTOM3 = <ChanField.CUSTOM3: 53>
- CUSTOM4 = <ChanField.CUSTOM4: 54>
- CUSTOM5 = <ChanField.CUSTOM5: 55>
- CUSTOM6 = <ChanField.CUSTOM6: 56>
- CUSTOM7 = <ChanField.CUSTOM7: 57>
- CUSTOM8 = <ChanField.CUSTOM8: 58>
- CUSTOM9 = <ChanField.CUSTOM9: 59>
- FLAGS = <ChanField.FLAGS: 8>
- FLAGS2 = <ChanField.FLAGS2: 9>
- NEAR_IR = <ChanField.NEAR_IR: 7>
- RANGE = <ChanField.RANGE: 1>
- RANGE2 = <ChanField.RANGE2: 2>
- RAW32_WORD1 = <ChanField.RAW32_WORD1: 60>
- RAW32_WORD2 = <ChanField.RAW32_WORD2: 61>
- RAW32_WORD3 = <ChanField.RAW32_WORD3: 62>
- RAW32_WORD4 = <ChanField.RAW32_WORD4: 63>
- RAW32_WORD5 = <ChanField.RAW32_WORD5: 45>
- RAW32_WORD6 = <ChanField.RAW32_WORD6: 46>
- RAW32_WORD7 = <ChanField.RAW32_WORD7: 47>
- RAW32_WORD8 = <ChanField.RAW32_WORD8: 48>
- RAW32_WORD9 = <ChanField.RAW32_WORD9: 49>
- RAW_HEADERS = <ChanField.RAW_HEADERS: 40>
- REFLECTIVITY = <ChanField.REFLECTIVITY: 5>
- REFLECTIVITY2 = <ChanField.REFLECTIVITY2: 6>
- SIGNAL = <ChanField.SIGNAL: 3>
- SIGNAL2 = <ChanField.SIGNAL2: 4>
- static from_string()
Create enum value from string.
- property name
The name of the Enum member.
- property value
The value of the Enum member.
- values = <iterator object>
- class ColHeader(value)[source]
Column headers available in lidar data.
This definition is deprecated.
- TIMESTAMP = 0
- ENCODER_COUNT = 1
- MEASUREMENT_ID = 2
- STATUS = 3
- FRAME_ID = 4
- class LidarScan
Represents a single “scan” or “frame” of lidar data.
This is a “struct of arrays” representation of lidar data. Column headers are stored as contiguous W element arrays, while fields are WxH arrays. Channel fields are staggered, so the ith column header value corresponds to the ith column of data in each field.
Default constructor creates a 0 x 0 scan
- Parameters:
height – height of scan
width – width of scan
- Returns:
New LidarScan of 0x0 expecting fields of the LEGACY profile
Initialize a scan with the default fields for a particular udp profile
- Parameters:
height – height of LidarScan, i.e., number of channels
width – width of LidarScan
profile – udp profile
- Returns:
New LidarScan of specified dimensions expecting fields of specified profile
Initialize a scan with a custom set of fields
- Parameters:
height – height of LidarScan, i.e., number of channels
width – width of LidarScan
fields_dict – dict where keys are ChanFields and values are type, e.g., {client.ChanField.SIGNAL: np.uint32}
- Returns:
New LidarScan of specified dimensions expecting fields specified by dict
Initialize a lidar scan from another with only the indicated fields. Casts, zero pads or removes fields from the original scan if necessary.
- Parameters:
source – LidarScan to copy data from
fields_dict – dict of fields to have in the new scan where keys are ChanFields and values are type, e.g., {client.ChanField.SIGNAL: np.uint32}
- Returns:
New LidarScan with selected data copied over or zero padded
Initialize a lidar scan with a copy of the data from another.
- Parameters:
source – LidarScan to copy
- Returns:
New LidarScan with data copied over from provided scan.
- field()
Return a view of the specified channel field.
- Parameters:
field – The channel field to return
- Returns:
The specified field as a numpy array
- property fields
Return an iterator of available channel fields.
- property frame_id
Corresponds to the frame id header in the packet format.
- property frame_status
Information from the packet header which corresponds to a frame.
- property h
Height or vertical resolution of the scan.
- property measurement_id
The measurement id header as a W-element numpy array.
- property packet_timestamp
The host timestamp header as a numpy array with W/columns-per-packet entries.
- property pose
The pose vector of 4x4 homogeneous matrices (per each timestamp).
- shot_limiting()
The frame shot limiting status.
- property status
The measurement status header as a W-element numpy array.
- thermal_shutdown()
The frame thermal shutdown status.
- property timestamp
The measurement timestamp header as a W-element numpy array.
- property w
Width or horizontal resolution of the scan.
- XYZLut(info, use_extrinsics=False)[source]
Return a function that can project scans into Cartesian coordinates.
If called with a numpy array representing a range image, the range image must be in “staggered” form, where each column corresponds to a single measurement block. LidarScan fields are always staggered.
Internally, this will pre-compute a lookup table using the supplied intrinsic parameters. XYZ points are returned as a H x W x 3 array of doubles, where H is the number of beams and W is the horizontal resolution of the scan.
The coordinates are reported in meters in the sensor frame (when
use_extrinsics
is False, default) as defined in the sensor documentation.However, the result is returned in the “extrinsics frame” if
use_extrinsics
is True, which makes additional transform from “sensor frame” to “extrinsics frame” using the homogeneous 4x4 transform matrix frominfo.extrinsic
property.- Parameters:
info (
SensorInfo
) – sensor metadatause_extrinsics (
bool
) – if True, applies theinfo.extrinsic
transform to the resulting “sensor frame” coordinates and returns the result in “extrinsics frame”.
- Return type:
Callable
[[Union
[LidarScan
,ndarray
]],ndarray
]- Returns:
A function that computes a point cloud given a range image
- destagger(info, fields, inverse=False)[source]
Return a destaggered copy of the provided fields.
In the default staggered representation, each column corresponds to a single timestamp. A destaggered representation compensates for the azimuth offset of each beam, returning columns that correspond to a single azimuth angle.
- Parameters:
info (
SensorInfo
) – Sensor metadata associated with the provided datafields (
ndarray
) – A numpy array of shape H X W or H X W X Ninverse – perform inverse “staggering” operation
- Return type:
ndarray
- Returns:
A destaggered numpy array of the same shape