ouster.sdk.util
Module contents
Copyright (c) 2024, Ouster, Inc. All rights reserved.
This module provides generic utility functions and helpers for working with Ouster lidar data.
ouster.sdk.util.extrinsics
Miscellaneous utilities.
- img_aspect_ratio(info)[source]
Returns 2D image aspect ratio based on sensor FOV angles.
- Return type:
float
- Uses the order:
img_aspect_ratio = FOV_vertical / FOV_horizontal
- quaternion_to_rotation_matrix(q)[source]
Converts Quaternion [w, x, y, z] to Rotation [3x3] matrix.
- Return type:
ndarray
- rotation_matrix_to_quaternion(R)[source]
Converts a Rotation [3x3] matrix to Quaternion [w, x, y, z].
- Return type:
ndarray
- position_quaternion_to_transform(p, q)[source]
Converts Quaternion + Pose [7] vector to homogeneous [4x4] matrix.
- Return type:
ndarray
- euler_to_rotation_matrix(roll, pitch, yaw)[source]
Convert Euler angles (roll, pitch, yaw) to a 3D rotation matrix.
- Parameters:
roll – Rotation about the x-axis (rad)
pitch – Rotation about the y-axis (rad)
yaw – Rotation about the z-axis (rad)
- Returns:
3x3 rotation matrix
- Return type:
R
- xyzrpy_to_matrix(px, py, pz, r, p, y)[source]
A method that takes position + euler angles (rad) and produces an equivalent 4x4 transform.
- Parameters:
px – position
py – position
pz – position
r – rotation expressed in euler angles (rad)
p – rotation expressed in euler angles (rad)
y – rotation expressed in euler angles (rad)
- Returns:
4x4 transformation matrix
- Return type:
R
- xyzq_to_matrix(px, py, pz, qx, qy, qz, qw)[source]
A method that takes position + quaternion (rad) and produces an equivalent 4x4 transform.
- Parameters:
px – position
py – position
pz – position
qx – rotation expressed in a quaternion
qy – rotation expressed in a quaternion
qz – rotation expressed in a quaternion
qw – rotation expressed in a quaternion
- Returns:
4x4 transformation matrix
- Return type:
R
- parse_extrinsics_from_string(extrinsics, degrees=True)[source]
A utility method to parse extrinsics in multiple formats.
- Parameters:
extrinsics (- A json with containing a per sensor) – a string representing a file or extrinsics in a supported format
degrees – whether angles should be parsed as degress (True by default)
formats (Acceptale extrinsics) –
extrinsics –
identity (- identity ; Use this to override any stored extrinsics with) –
angles (- X Y Z R P Y ; 'R P Y' represent euler) –
; (- X Y Z QX QY QZ QW) –
order (- n1 n2 .. n16 ; 16 floats representing a 2D array in a row-major) –
- Returns:
4x4 transformation matrix or a filename
- Return type:
R
ouster.sdk.util.forward_slicer
- class ForwardSlicer[source]
Bases:
objectForwardSlicer provides slicing methods to slice up a container with step to containers that only support forward slicing
- static slice_iter(data_iter, key)[source]
Performs forward slicing on a dataset with step
Parameters: - key: must be a normalized slice key with relation to the used data_iter.
a normalized slice key is one where key.start < key.stop and no non-values
- Returns:
an iterator scoped to the input key
- Return type:
Iterator
- static slice(data_iter, key)[source]
Performs forward slicing on a dataset with step
Parameters: - key: must be a normalized slice key with relation to the used data_iter.
a normalized slice key is one where key.start < key.stop and no non-values
- Returns:
a list of items scoped to the input key
- Return type:
List
ouster.sdk.util.metadata
Miscellaneous utilites.
- resolve_metadata(data_path, meta_path=None)[source]
Look for a metadata file based on the data path if needed.
Convenient to use in CLI tools when –meta param can be omitted in lots of trivial cases when pcap filename has the same prefix as the metadata json filename.
- Parameters:
data_path (
str) – filename location with the data, usually .pcap or .bag that is used to search metadata with the most common prefix filemeta_path (
Optional[str]) – the pass through metadata path, if set guessing and search for other metadata jsons is skipped
- Return type:
Optional[str]- Returns:
metadata json paths guessed with the most common prefix match or passed through from meta_path parameter
ouster.sdk.util.parsing
R/W implementation of packet parsing.
Doesn’t rely on custom C++ extensions (just numpy). Provides writable view of packet data for testing and development.
- tohex(data)[source]
Makes a hex string for debug print outs of buffers.
Selects the biggest devisor of np.uint32, np.uint16 or np.uint8 for making a hex output of the provided data. (clunky but usefull for debugging)
- Return type:
str
- scan_to_packets(ls, info)[source]
Converts LidarScan to a lidar_packet buffers
- Parameters:
ls (
LidarScan) – LidarScan; if LidarScan has RAW_HEADERS field, packet headers are recreated to how they were in the original packetsinfo (
SensorInfo) – metadata of the ls scan
- Return type:
List[Packet]- Returns:
A set of lidar packets that will produce the same LidarScan if passed through the ScanBatcher again (less fields data)
ouster.sdk.util.pose_util
- exp_rot_vec(vec)[source]
Converts so3 vector to a rotation matrix.
- Parameters:
vec (
ndarray) – so3 rotation vector [3] or vectors [N, 3] to rotation matrix [3, 3] or matrices [N, 3, 3]- Return type:
ndarray- Returns:
rotation matrix or matrices
- log_rot_mat(rm)[source]
Convert rotation matrix to so3 coordinates (i.e. log() operator)
- Parameters:
rm (
ndarray) – rotation matrix [3, 3] or matrices [N, 3, 3]- Return type:
ndarray- Returns:
so3 coordinate rotation vector [3] or [N, 3]
- exp_pose6(pose6)[source]
Convert exponential poses to homogeneous matrix poses.
- Parameters:
pose6 (
ndarray) – vector [6] or matrix [N, 6] of exponential poses- Return type:
ndarray- Returns:
Homogeneous matrix poses of size [4, 4] or [N, 4, 4].
- log_pose(pose)[source]
Convert homogeneous matrix(s) to exp pose coordinates.
- Parameters:
pose (
ndarray) – homogeneous pose [4, 4] or poses [N, 4, 4]- Return type:
ndarray- Returns:
exp pose coordinates [6] or [N, 6]
- pose_interp(p1, p2, t, *, delta_pose6=None)[source]
Pose interpolation between pose1 and pose2 at time t as ratio.
- Parameters:
p1 (
ndarray) – starting posep2 (
ndarray) – ending poset (
float) – ratio between pose p1 and p2 at what point to interpolate, not restricted between [0, 1] and can be extended for out of boundsdelta_pose6 (
Optional[ndarray]) – pre-calculated difference inv(p1) @ p2, saves computation if it’s available already
- Return type:
ndarray- Returns:
pose of the point at time t on the line defined by p1 and p2 on SE3 manifold
- traj_interp(traj_poses, ts)[source]
Trajectory interpolation for points in between.
TODO[pb]: Extend with time_bounds args for traj evaluator when needed
- Return type:
ndarray
- class TrajectoryEvaluator(poses, *, time_bounds=0)[source]
Bases:
PoserInterpolates trajectory for a set of timestamps from knot poses.
TODO[pb]: Add function to add/remove knot poses from traj eval.
- TODO: Optionally, we may want to implement these calculations in C++ and
use bindings to make it faster.
- Parameters:
poses (
Sequence[Tuple[Union[int,float,number],ndarray]]) – List of knot poses with timestamps. Every list item is a tuple (ts, pose).time_bounds (
Optional[float]) –whether to restrict the pose interpolation to the timestamp range within the poses list: None - no restriction at all on the timestamps that can
be used to get pose from the trajectory
- 0 - strict bounds on the timestamp range in the
poses list
- >0 - ratio that is allowed to go over the timestamp
bounds. ratio value is applied as the ratio of pose[1].ts - pose[0].ts for the left bound, and pose[N].ts - pose[N-1].ts for the right bound.
- get_rot_matrix_to_align_to_gravity(accel_x, accel_y, accel_z)[source]
Computes the rotation matrix needed to align a given acceleration vector with the direction of gravity, fixing the yaw angle to zero.
- Parameters:
accel_x (
float) – x-component of the acceleration vector.accel_y (
float) – y-component of the acceleration vector.accel_z (
float) – z-component of the acceleration vector.
- Returns:
A 3x3 rotation matrix that aligns the acceleration vector with the gravity vector [0,0,1] while fixing the yaw angle to zero.
- pose_scans(source, *, poses=None)[source]
Add poses to LidarScans stream.
- Parameters:
source – one of: - Sequence[core.LidarScan] - single scan sources - Sequence[core.LidarScanSet] - multi scans sources
- load_kitti_poses(file)[source]
Loads the Kitti poses from the file.
- Return type:
ndarray- Returns:
[N, 4, 4] array of homogeneous poses
- make_kiss_traj_poses(poses)[source]
Makes a traj poses from kiss poses.
- Parameters:
poses (
Union[Sequence[ndarray],ndarray]) – pose for every scan in the sequence as returned by KissICP- Returns:
0.5 For example scan indexes 0, 1, 2 produce timestamps 0.5, 1.5, 2.5
- Return type:
trajectory poses timestamped by the scan index mid point
- pose_scans_from_kitti(source, kitti_poses)[source]
Add poses to LidarScans stream using the previously saved per scan poses.
Every pose is considered to be in the middle of the scan. We assume that very first scan starts at t = 0 and ends at t = 1, thus the first pose is timestamped as 0.5, second pose is timestamped at 1.5 (middle of the second scan), and so on … to the very last pose N which timestamped at N + 0.5 for the last N scan.
- Parameters:
source – one of: - Sequence[core.LidarScan] - single scan sources - Sequence[core.LidarScanSet] - multi scans sources
kitti_poses (
str) – path to the file with in kitti poses format, i.e. every line contains 12 floats of 4x4 homogeneous transformation matrix ([:3, :]in numpy notation, row-major serialized)
ouster.sdk.util.progress_bar
- progressbar(progress, total, prefix='', suffix='')[source]
Displays progress in the console as a percentage.
- Parameters:
progress – The current progress (number of items completed).
total – The total number of items.
prefix – A prefix string to display before the progress bar (optional).
suffix – A suffix string to display after the progress bar (optional).
resolve_field_types
- resolve_field_types(metadata: list[ouster::sdk::core::SensorInfo], raw_headers: bool = False, raw_fields: bool = False, field_names: Optional[list[str]] = None) list[list[ouster.sdk._bindings.client.FieldType]]
Resolve field types for a given set of metadata and field names.
This function determines the types of fields (e.g., signal, reflectivity) based on the provided sensor metadata and field names.
- Parameters:
metadata (List[SensorInfo]) – A list of sensor metadata objects.
raw_headers (bool) – Whether to include raw headers in the resolution. Default is False.
raw_fields (bool) – Whether to include raw fields in the resolution. Default is False.
field_names (List[str]) – A list of field names to resolve. Default is an empty list.
- Returns:
A list of resolved field types.
- Return type:
List[FieldType]