Module ouster.sdk.mapping

ouster.sdk.mapping

class PoseOptimizer(*args, **kwargs)

Bases: pybind11_object

A class for optimizing LiDAR sensor trajectories using various geometric constraints.

This class allows adding different types of constraints (pose-to-pose, absolute pose, point-to-point) and solving the trajectory optimization problem to generate a more accurate and consistent sensor path. The optimization aims to minimize the error across all defined constraints while maintaining a physically plausible trajectory.

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, options: ouster.sdk._bindings.mapping.SolverConfig, fix_first_node: bool = False) -> None

    Initialize PoseOptimizer with an OSF file and solver options.

    Args:

    osf_filename (str): Path to the OSF file containing trajectory data. options (SolverConfig): Solver configuration options. fix_first_node (bool, optional): Flag to fix the first node in the trajectory. Default is False.

  2. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, key_frame_distance: float, fix_first_node: bool = False) -> None

    Initialize PoseOptimizer with an OSF file and a node gap.

    Args:

    osf_filename (str): Path to the OSF file containing trajectory data. key_frame_distance (float): The gap distance between nodes in the trajectory. fix_first_node (bool, optional): Flag to fix the first node in the trajectory. Default is False.

add_absolute_pose_constraint(*args, **kwargs)

Overloaded function.

  1. add_absolute_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts: int, target_pose: numpy.ndarray[numpy.float64[6, 1]], rotation_weight: float = 1.0, translation_weight: float = 1.0, diff: numpy.ndarray[numpy.float64[6, 1]] = array([0., 0., 0., 0., 0., 0.])) -> bool

    Add a constraint fixing a pose to an absolute position and orientation.

    This constraint anchors a pose at a specific timestamp to a known fixed position/orientation in the global coordinate frame, such as from GPS or manual ground truth annotations.

    Args:

    ts (int): Timestamp at which the absolute pose constraint is applied. target_pose (Eigen::Matrix<double, 6, 1>): The target pose [rx,ry,rz,tx,ty,tz] in global coordinates. rotation_weight (float, optional): Weight for rotation constraints. Default is 1.0. translation_weight (float, optional): Weight for translation constraints. Default is 1.0. diff (Eigen::Matrix<double, 6, 1>, optional): The expected difference (rotation and translation) between the source and target. Default is zero.

    Returns:

    bool: True if the constraint was successfully added, False otherwise.

  2. add_absolute_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts: int, target_pose: numpy.ndarray[numpy.float64[4, 4]], rotation_weight: float = 1.0, translation_weight: float = 1.0, diff: numpy.ndarray[numpy.float64[4, 4]] = array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]])) -> bool

    Add a constraint fixing a pose to an absolute position and orientation with a 4x4 matrix.

    This constraint anchors a pose at a specific timestamp to a known fixed position/orientation in the global coordinate frame, such as from GPS or manual ground truth annotations, using a 4x4 transformation matrix.

    Args:

    ts (int): Timestamp at which the absolute pose constraint is applied. target_pose (Eigen::Matrix<double, 4, 4>): The target pose as a 4x4 transformation matrix in global coordinates. rotation_weight (float, optional): Weight for rotation constraints. Default is 1.0. translation_weight (float, optional): Weight for translation constraints. Default is 1.0. diff (Eigen::Matrix<double, 4, 4>, optional): The expected difference (rotation and translation) between the source and target. Default is identity.

    Returns:

    bool: True if the constraint was successfully added, False otherwise.

  3. add_absolute_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts: int, target_pose: numpy.ndarray[numpy.float64[6, 1]], rotation_weights: Annotated[list[float], FixedSize(3)] = [1.0, 1.0, 1.0], translation_weights: Annotated[list[float], FixedSize(3)] = [1.0, 1.0, 1.0], diff: numpy.ndarray[numpy.float64[6, 1]] = array([0., 0., 0., 0., 0., 0.])) -> bool

    Adds an absolute pose constraint with a predefined pose difference for a given timestamp (6x1 form).

    This function adds a constraint to enforce a specific pose (target_pose) at timestamp ts, weighted by per-axis rotation and translation weights. The pose difference can further adjust how the target pose is enforced.

    Args:

    ts (int): Timestamp at which the absolute pose constraint is applied. target_pose (Eigen::Matrix<double, 6, 1>): The target pose [rx, ry, rz, tx, ty, tz]. rotation_weights (List[float]): Rotational weight for each axis ([rx_weight, ry_weight, rz_weight]). translation_weights (List[float]): Translational weight for each axis ([tx_weight, ty_weight, tz_weight]). diff (Eigen::Matrix<double, 6, 1>, optional): The pose difference in 6x1 form. Default is zero.

    Returns:

    bool: True if the constraint was successfully added, false otherwise.

  4. add_absolute_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts: int, target_pose: numpy.ndarray[numpy.float64[4, 4]], rotation_weights: Annotated[list[float], FixedSize(3)] = [1.0, 1.0, 1.0], translation_weights: Annotated[list[float], FixedSize(3)] = [1.0, 1.0, 1.0], diff: numpy.ndarray[numpy.float64[4, 4]] = array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]])) -> bool

    Adds an absolute pose constraint with a predefined pose difference for a given timestamp (4x4 matrix form).

    This function adds a constraint to enforce a specific pose (target_pose) at timestamp ts, weighted by per-axis rotation and translation weights. The pose difference can further adjust how the target pose is enforced using a 4x4 transformation matrix.

    Args:

    ts (int): Timestamp at which the absolute pose constraint is applied. target_pose (Eigen::Matrix<double, 4, 4>): The target pose as a 4x4 transformation matrix. rotation_weights (List[float]): Rotational weight for each axis ([rx_weight, ry_weight, rz_weight]). translation_weights (List[float]): Translational weight for each direction ([tx_weight, ty_weight, tz_weight]). diff (Eigen::Matrix<double, 4, 4>, optional): The pose difference in 4x4 form. Default is identity.

    Returns:

    bool: True if the constraint was successfully added, false otherwise.

add_point_to_point_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts1: int, row1: int, col1: int, return_idx1: int, ts2: int, row2: int, col2: int, return_idx2: int, translation_weight: float = 1.0) bool

Add a constraint between two specific points that should represent the same physical location.

This constraint enforces that two LiDAR points from different frames, identified by their row/column coordinates, should map to the same physical location in the world after applying their respective pose transformations. Useful for manual feature correspondence.

Parameters:
  • ts1 (int) – Timestamp of the first frame.

  • row1 (int) – Row index of the point in the first frame’s 2D point representation.

  • col1 (int) – Column index of the point in the first frame’s 2D point representation.

  • return_idx1 (int) – Lidar return index for multi-return sensors (0 for first return).

  • ts2 (int) – Timestamp of the second frame.

  • row2 (int) – Row index of the point in the second frame’s 2D point representation.

  • col2 (int) – Column index of the point in the second frame’s 2D point representation.

  • return_idx2 (int) – Lidar return index for multi-return sensors (0 for first return).

  • translation_weight (float, optional) – Weight for this constraint. Default is 1.0.

Returns:

True if the constraint was successfully added, False otherwise.

Return type:

bool

add_pose_to_pose_constraint(*args, **kwargs)

Overloaded function.

  1. add_pose_to_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts1: int, ts2: int, diff: numpy.ndarray[numpy.float64[6, 1]], rotation_weight: float = 1.0, translation_weight: float = 1.0) -> bool

    Add a relative pose constraint between two frames with a known transformation.

    This constraint specifies that the relative transformation between poses at timestamps ts1 and ts2 should match the provided difference. Useful when you have externally computed transformations (e.g., from ICP or visual odometry).

    Args:

    ts1 (int): Timestamp of the first frame. ts2 (int): Timestamp of the second frame. diff (Eigen::Matrix<double, 6, 1>): Pose difference between the two frames [rx,ry,rz,tx,ty,tz] rotation_weight (float, optional): Weight for rotation constraints. Default is 1.0. translation_weight (float, optional): Weight for translation constraints. Default is 1.0.

    Returns:

    bool: True if the constraint was successfully added, False otherwise.

  2. add_pose_to_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts1: int, ts2: int, diff: numpy.ndarray[numpy.float64[4, 4]], rotation_weight: float = 1.0, translation_weight: float = 1.0) -> bool

    Add a relative pose constraint between two frames with a known transformation in 4x4 matrix.

    This constraint specifies that the relative transformation between poses at timestamps ts1 and ts2 should match the provided difference in 4x4 matrix form. Useful when you have externally computed transformations (e.g., from ICP or visual odometry).

    Args:

    ts1 (int): Timestamp of the first frame. ts2 (int): Timestamp of the second frame. diff (Eigen::Matrix<double, 4, 4>): Pose difference between the two frames as a 4x4 transformation matrix. rotation_weight (float, optional): Weight for rotation constraints. Default is 1.0. translation_weight (float, optional): Weight for translation constraints. Default is 1.0.

    Returns:

    bool: True if the constraint was successfully added, False otherwise.

  3. add_pose_to_pose_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, ts1: int, ts2: int, rotation_weight: float = 1.0, translation_weight: float = 1.0) -> bool

    Add a relative pose constraint between two frames using automatic alignment.

    This overload automatically computes the transformation between frames at ts1 and ts2 using the built-in ICP algorithm on the point clouds from these timestamps.

    Args:

    ts1 (int): Timestamp of the first frame. ts2 (int): Timestamp of the second frame. rotation_weight (float, optional): Weight for rotation constraints. Default is 1.0. translation_weight (float, optional): Weight for translation constraints. Default is 1.0.

    Returns:

    bool: True if the constraint was successfully added, False otherwise.

get_poses(self: ouster.sdk._bindings.mapping.PoseOptimizer, type: ouster.sdk._bindings.mapping.SamplingMode) numpy.ndarray[numpy.float64]

Retrieve poses as a NumPy array of 4×4 transformation matrices.

Parameters:

type (SamplingMode) – Sampling strategy to use. - SamplingMode.KEY_FRAMES: Returns poses at key-frame timestamps. - SamplingMode.COLUMNS: Returns poses of every lidarscan’s columns.

Returns:

An (n, 4, 4) array of 4×4 poses.

Return type:

numpy.ndarray[np.float64]

get_timestamps(self: ouster.sdk._bindings.mapping.PoseOptimizer, type: ouster.sdk._bindings.mapping.SamplingMode) numpy.ndarray[numpy.uint64]

Retrieve timestamps corresponding to the selected sampling mode.

Parameters:

type (SamplingMode) – Sampling strategy to use. - SamplingMode.KEY_FRAMES: Returns timestamps at key-frame poses. - SamplingMode.COLUMNS: Returns timestamps of every lidarscan’s columns.

Returns:

A 1D array of timestamps (nanoseconds).

Return type:

numpy.ndarray[np.uint64]

save(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_name: str) None

Save the optimized trajectory to an OSF file.

This method writes the current state of the optimized trajectory to a new OSF file, preserving all other data from the original file.

Parameters:

osf_name (str) – The name of the output OSF file.

Returns:

True if the file was successfully saved, False otherwise.

Return type:

bool

solve(self: ouster.sdk._bindings.mapping.PoseOptimizer, steps: int = 0) None

Incrementally optimize the trajectory.

This method performs a fixed number of iterations of the optimization algorithm, continuing from the current state. It can be called repeatedly to gradually refine the trajectory. The number of iterations to execute is specified by ‘steps’.

Parameters:

steps (int, optional) – The number of iterations to run for this incremental optimization. Defaults to 0 (uses whatever max_num_iterations was already set).

ouster.sdk.mapping.json_parser

validate_constraints_json(constraints_json_file)[source]

Loads and validates the JSON file containing Pose Optimizer constraints.

The function checks that:
  • The JSON file can be loaded.

  • The top-level “constraints” field exists.

  • Each constraint includes all required fields based on its type.

It also validates that rotation_weight(s) and translation_weight(s) are either single floats/integers or lists of exactly three floats/integers.

Additionally, it returns a boolean value indicating whether the first node needs to be fixed. (If no ABSOLUTE_POSE constraint exists, fix_first_node is True.)

Returns:

  • data: Parsed JSON data if valid, otherwise None.

  • fix_first_node: True if no ABSOLUTE_POSE constraint exists, False otherwise.

  • errors: A list of error messages found during validation.

Return type:

A tuple of (data, fix_first_node, errors) where

ouster.sdk.mapping.kiss_localization

class KissLocalization(infos, config, map)[source]

Bases: LocalizationBackend

LocalizationBackend constructor

classmethod params()[source]
Return type:

LocalizationConfig

update(scans)[source]

Update the pose (per_column_global_pose) variable in scan and return

Return type:

List[Optional[LidarScan]]

ouster.sdk.mapping.kiss_slam

class KissSlam(infos, config)[source]

Bases: SlamBackend

Wraps kiss-icp odometry to use with Ouster pipelines.

SlamBackend constructor

update(scans)[source]

Update the pose information of each lidar scan based on SLAM pose estimation.

Workflow: • Initialize frame_valid_id_range if not already set. • Compute overall frame timestamp range. • Check inter-sensor synchronization:

  • If sensors are out of sync, enable packet-offset mode.

  • Monotonicity check (ignoring zero timestamps): - For any scan whose timestamps go backwards, correct its timestamps

    and enable packet-offset mode.

  • Packet-offset handling: - If offset mode is active, compute fallback timestamp offsets. - Abort early if offset computation fails.

  • Dynamic voxel size: - If a voxel_size was provided then apply it.

  • Frame-ID handling: - Compute per-sensor frame-ID diffs (with overflow protection). - Invalidate any out-of-order scans by zeroing their ranges. - Track the smallest non-zero diff for SLAM integration.

  • Point-cloud aggregation: - Merge valid points and their (possibly offset) timestamps. - Abort early if no points remain.

  • SLAM registration: - Register the aggregated frame with KISS-ICP.

  • Pose interpolation: - Interpolate between the last and new SLAM poses. - Write per-column poses back into each scan.

  • Update internal state: - Store the new last SLAM pose, last frame-ID array, and timestamp range.

Return type:

List[Optional[LidarScan]]

Returns:

The same list of scans with the updated per-column poses.

ouster.sdk.mapping.localization_backend

class LocalizationConfig[source]

Bases: object

min_range: float = 0.0
max_range: float = 150.0
voxel_size: float = 1.0
initial_pose: Optional[ndarray] = None
backend: str = 'kiss'
class LocalizationBackend(infos, loc_config, map)[source]

Bases: ABC

base class of general slam solutions for SDK cli usage

LocalizationBackend constructor

abstract update(scans)[source]

Update the pose (per_column_global_pose) variable in scan and return

Return type:

List[Optional[LidarScan]]

ouster.sdk.mapping.localization_engine

class LocalizationEngine(infos, config, map)[source]

Bases: object

base class of general slam solutions for SDK cli usage

SlamEngine constructor

update(scans)[source]

Update the pose (per_column_global_pose) variable in scan and return

Return type:

List[Optional[LidarScan]]

ouster.sdk.mapping.ouster_kiss_icp

# MIT License # # Copyright (c) 2022 Ignacio Vizzo, Tiziano Guadagnino, Benedikt Mersch, Cyrill # Stachniss. # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the “Software”), to deal # in the Software without restriction, including without limitation the rights # to use, copy, modify, merge, publish, distribute, sublicense, and/or sell # copies of the Software, and to permit persons to whom the Software is # furnished to do so, subject to the following conditions: # # The above copyright notice and this permission notice shall be included in all # copies or substantial portions of the Software. # # THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR # IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, # FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE # AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE # SOFTWARE.

Module ouster_kiss_icp

Description:

This module was a copy from the KissICP repository https://github.com/PRBonn/kiss-icp We edit it to fit our use cases better

class Preprocessor(max_range, min_range, deskew, max_num_threads)[source]

Bases: object

preprocess(frame, timestamps, relative_motion)[source]
class KissICP(config, initial_pose=array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]))[source]

Bases: object

register_frame(frame, timestamps, delta_ratio=1)[source]
voxelize(iframe)[source]

ouster.sdk.mapping.ply_to_png

ouster.sdk.mapping.slam_backend

class SlamConfig[source]

Bases: object

min_range: float = 0.0
max_range: float = 150.0
voxel_size: float = 1.0
initial_pose: Optional[ndarray] = None
backend: str = 'kiss'
class SlamBackend(infos, config)[source]

Bases: ABC

base class of general slam solutions for SDK cli usage

SlamBackend constructor

abstract update(scans)[source]

Update the pose (per_column_global_pose) variable in scan and return

Return type:

List[Optional[LidarScan]]

ouster.sdk.mapping.slam_engine

class SlamEngine(infos, config)[source]

Bases: object

base class of general slam solutions for SDK cli usage

SlamEngine constructor

update(scans)[source]

Update the pose (per_column_global_pose) variable in scan and return

Return type:

List[Optional[LidarScan]]

property last_pose

Get the current pose

ouster.sdk.mapping.util

get_frame_ts_range(scans)[source]

Returns a list of (first_valid_column_timestamp, last_valid_column_timestamp) for each scan. If a scan is None, returns (-1, -1) for that position.

Return type:

List[Tuple[int64, int64]]

get_frame_id_range(scans)[source]

Returns a list of (first_valid_column, last_valid_column) for each scan. If a scan is None, returns (-1, -1) for that position.

Return type:

List[Tuple[int, int]]

get_total_frame_pts_and_ts(scans, xyz_lut, ts_offsets)[source]
write_interpolated_poses(slam_prev_pose, slam_curr_pose, scans, normalized_ts_list, slam_frame_diff=1)[source]
determine_voxel_size(scans, start_pct=0.92, end_pct=0.96)[source]

Average highest 92% to 96% range readings and use this averaged range value to calculate the voxel map size

Return type:

Optional[float]

_make_ortho(matrix)[source]

Takes a 3x3 rotation matrix and returns an orthonormal matrix of it using SVD.

Return type:

ndarray