ouster.sdk.mapping

Module contents

Copyright (c) 2024, Ouster, Inc. All rights reserved.

This module provides tools and classes for SLAM, localization, and mapping utilities for Ouster lidar data in Python. It helps building maps, track poses, and process mapping results.

ouster.sdk.mapping.ply_to_png

get_doll_dist(points)[source]
peak_start_point(ply_files)[source]
output_ext_verify(filename)[source]
screenshot_and_save_png(viz, screenshot_path)[source]
scale_rgb_channel(channel)[source]
convert_ply_to_png(ply_files, screenshot_path, is_plot)[source]

SlamConfig

class SlamConfig(self: ouster.sdk._bindings.mapping.SlamConfig)

Configuration options for the SLAM engine.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.SlamConfig) None

__module__ = 'ouster.sdk._bindings.mapping'
property backend
property deskew_method
property initial_pose
property max_range
property min_range
property voxel_size

SlamEngine

class SlamEngine(self: ouster.sdk._bindings.mapping.SlamEngine, infos: list[ouster.sdk._bindings.client.SensorInfo], config: ouster.sdk._bindings.mapping.SlamConfig)

The SLAM engine for processing LiDAR scans and computing poses.

SlamEngine constructor.

Parameters:
  • infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

  • config (SlamConfig) – Configuration options for the SLAM engine.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.SlamEngine, infos: list[ouster.sdk._bindings.client.SensorInfo], config: ouster.sdk._bindings.mapping.SlamConfig) None

SlamEngine constructor.

Parameters:
  • infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

  • config (SlamConfig) – Configuration options for the SLAM engine.

__module__ = 'ouster.sdk._bindings.mapping'
get_point_cloud(self: ouster.sdk._bindings.mapping.SlamEngine) numpy.ndarray[numpy.float32[m, 3]]

Get the current point cloud from the SLAM engine.

Returns:

The point cloud generated by the SLAM engine.

Return type:

Nx3

update(self: ouster.sdk._bindings.mapping.SlamEngine, scans: ouster.sdk._bindings.client.LidarScanSet) ouster.sdk._bindings.client.LidarScanSet

Update the pose (per_column_global_pose) variable in scan and return

Parameters:

scans (List[LidarScan]) – List of scans to update with the latest pose.

Returns:

The updated scans with per_column_global_pose set.

Return type:

List[LidarScan]

LocalizationConfig

class LocalizationConfig(self: ouster.sdk._bindings.mapping.LocalizationConfig)

Configuration options for the Localization engine.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.LocalizationConfig) None

__module__ = 'ouster.sdk._bindings.mapping'
property backend
property deskew_method
property initial_pose
property max_range
property min_range
property voxel_size

LocalizationEngine

class LocalizationEngine(self: ouster.sdk._bindings.mapping.LocalizationEngine, infos: list[ouster.sdk._bindings.client.SensorInfo], config: ouster.sdk._bindings.mapping.LocalizationConfig, map: str)

The Localization engine for processing LiDAR scans and computing poses based on prebuilt pointcloud map.

LocalizationEngine constructor.

Parameters:
  • infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

  • config (LocalizationConfig) – Configuration options for the Localization engine.

  • map_path (string) – Path to the point cloud map.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.LocalizationEngine, infos: list[ouster.sdk._bindings.client.SensorInfo], config: ouster.sdk._bindings.mapping.LocalizationConfig, map: str) None

LocalizationEngine constructor.

Parameters:
  • infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

  • config (LocalizationConfig) – Configuration options for the Localization engine.

  • map_path (string) – Path to the point cloud map.

__module__ = 'ouster.sdk._bindings.mapping'
update(self: ouster.sdk._bindings.mapping.LocalizationEngine, scans: ouster.sdk._bindings.client.LidarScanSet) ouster.sdk._bindings.client.LidarScanSet

Update the pose (per_column_global_pose) variable in scan and return

Parameters:

scans (List[LidarScan]) – List of scans to update with the latest pose.

Returns:

The updated scans with per_column_global_pose set

Return type:

List[LidarScan]

DeskewMethod

class DeskewMethod(self: ouster.sdk._bindings.mapping.DeskewMethod, infos: list[ouster.sdk._bindings.client.SensorInfo])

Base class for all deskewing methods.

This is the abstract base class for all deskewing methods. Use specific derived classes like ConstantVelocityDeskewMethod instead of using this class directly.

ConstantVelocityDeskewMethod constructor.

Parameters:

infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.DeskewMethod, infos: list[ouster.sdk._bindings.client.SensorInfo]) None

ConstantVelocityDeskewMethod constructor.

Parameters:

infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

__module__ = 'ouster.sdk._bindings.mapping'
update(self: ouster.sdk._bindings.mapping.DeskewMethod, scans: ouster.sdk._bindings.client.LidarScanSet) ouster.sdk._bindings.client.LidarScanSet

Update the pose (per_column_global_pose) variable in scan.

Parameters:

scans (LidarScanSet) – a LidarScanSet.

Returns:

The updated lidar scans with per_column_global_pose set

Return type:

LidarScanSet

ConstantVelocityDeskewMethod

class ConstantVelocityDeskewMethod(self: ouster.sdk._bindings.mapping.ConstantVelocityDeskewMethod, infos: list[ouster.sdk._bindings.client.SensorInfo])

Deskew method that assumes constant velocity motion between poses.

ConstantVelocityDeskewMethod constructor.

Parameters:

infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.ConstantVelocityDeskewMethod, infos: list[ouster.sdk._bindings.client.SensorInfo]) None

ConstantVelocityDeskewMethod constructor.

Parameters:

infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

__module__ = 'ouster.sdk._bindings.mapping'
set_last_pose(self: ouster.sdk._bindings.mapping.ConstantVelocityDeskewMethod, ts: int, pose: numpy.ndarray[numpy.float64]) None

Set the current pose to use for deskewing.

This method allows setting the current pose that will be used as a reference for deskewing incoming scans. The current pose should represent the sensor’s pose at the time of the most recent scan.

Parameters:
  • ts (int) – The timestamp (nanoseconds) associated with the pose.

  • pose (numpy.ndarray) – A 4x4 transformation matrix representing the current pose.

DeskewMethodFactory

class DeskewMethodFactory

Factory class for creating DeskewMethod instances.

__annotations__ = {}
__init__(*args, **kwargs)
__module__ = 'ouster.sdk._bindings.mapping'
static create(method_name: str, infos: list[ouster.sdk._bindings.client.SensorInfo]) ouster.sdk._bindings.mapping.DeskewMethod

Create a DeskewMethod instance based on the specified method name.

Parameters:
  • method_name (str) – The name of the deskew method to create.

  • infos (List[SensorInfo]) – List of sensor info objects for each sensor in the system.

Returns:

A new instance of the specified deskew method.

Return type:

DeskewMethod

ActiveTimeCorrection

class ActiveTimeCorrection(self: ouster.sdk._bindings.mapping.ActiveTimeCorrection, infos: list[ouster.sdk._bindings.client.SensorInfo])

Class for correcting timestamps of LiDAR scans based on active time correction.

ActiveTimeCorrection constructor. :param infos: List of sensor info objects for each

sensor in the system.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.ActiveTimeCorrection, infos: list[ouster.sdk._bindings.client.SensorInfo]) None

ActiveTimeCorrection constructor. :param infos: List of sensor info objects for each

sensor in the system.

__module__ = 'ouster.sdk._bindings.mapping'
reset(self: ouster.sdk._bindings.mapping.ActiveTimeCorrection, scans: ouster.sdk._bindings.client.LidarScanSet) ouster.sdk._bindings.client.LidarScanSet

Restore the timestamps in the provided LidarScanSet to their original values before active time correction was applied.

update(self: ouster.sdk._bindings.mapping.ActiveTimeCorrection, scans: ouster.sdk._bindings.client.LidarScanSet) ouster.sdk._bindings.client.LidarScanSet

Update the timestamps in the provided LidarScanSet using active time correction.

PoseOptimizer

class PoseOptimizer(*args, **kwargs)

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) -> 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. Set options.fix_first_node to True to fix the first node.

  2. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, config_filename: str) -> None

    Initialize PoseOptimizer with an OSF file and solver options loaded from a config file.

    Args:

    osf_filename (str): Path to the OSF file containing trajectory data. config_filename: Path to the configuration file (JSON) containing solver options. Set fix_first_node in the config file to True to fix the first node.

  3. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, key_frame_distance: float) -> 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. To fix the first node, set fix_first_node in the SolverConfig after construction.

__annotations__ = {}
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, options: ouster.sdk._bindings.mapping.SolverConfig) -> 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. Set options.fix_first_node to True to fix the first node.

  2. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, config_filename: str) -> None

    Initialize PoseOptimizer with an OSF file and solver options loaded from a config file.

    Args:

    osf_filename (str): Path to the OSF file containing trajectory data. config_filename: Path to the configuration file (JSON) containing solver options. Set fix_first_node in the config file to True to fix the first node.

  3. __init__(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: str, key_frame_distance: float) -> 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. To fix the first node, set fix_first_node in the SolverConfig after construction.

__module__ = 'ouster.sdk._bindings.mapping'
add_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, constraint: ouster.sdk._bindings.mapping.Constraint) int

Add a constraint to the pose optimization problem.

This is the new unified API for adding constraints. Use the constraint class constructors to create constraints, then pass them to this method. The constraint will be assigned a unique ID for later removal if needed.

Parameters:

constraint – A constraint object created by one of the constraint constructors.

Returns:

The unique constraint ID assigned to the added constraint.

Return type:

int

Raises:

RuntimeError – If the constraint cannot be added.

get_constraints(*args, **kwargs)

Overloaded function.

  1. get_constraints(self: ouster.sdk._bindings.mapping.PoseOptimizer) -> list

    Get all constraints currently added to the pose optimizer.

    Returns:

    list: A list of constraint objects (copies) currently configured in the optimizer.

  2. get_constraints(self: ouster.sdk._bindings.mapping.PoseOptimizer) -> list

    Get all constraints currently configured in the pose optimizer.

    This method returns a copy of all constraints that are currently configured in the pose optimizer, including both constraints loaded from JSON files during construction and constraints added later via add_constraint().

    Returns:

    List[Constraint]: A list of Constraint objects representing all currently configured constraints.

get_cost_value(self: ouster.sdk._bindings.mapping.PoseOptimizer) float

Get the last solver cost value (final cost from the last solve()).

Returns:

The last recorded solver cost value.

Return type:

float

get_key_frame_distance(self: ouster.sdk._bindings.mapping.PoseOptimizer) float

Return the configured key-frame distance (meters) used when constructing the trajectory.

get_node(self: ouster.sdk._bindings.mapping.PoseOptimizer, timestamp: int) ouster.sdk._bindings.mapping.PoseOptimizerNode

Get the node associated with a given timestamp (first-valid-column ts). The node pose is updated before returning. Returns None if not found.

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_sampled_nodes(self: ouster.sdk._bindings.mapping.PoseOptimizer, count: int = 100) list

Retrieve up to count scan nodes evenly sampled across the OSF.

Each node is guaranteed to have a downsampled point cloud; nodes are created on-demand if necessary.

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]

get_total_iterations(self: ouster.sdk._bindings.mapping.PoseOptimizer) int

Get the cumulative number of solver iterations executed so far.

Returns:

Total iterations across all calls to solve().

Return type:

int

initialize_trajectory_alignment(self: ouster.sdk._bindings.mapping.PoseOptimizer) bool

Initialize trajectory alignment using average absolute constraints.

Computes a weighted average SE(3) transform from the currently loaded absolute pose and absolute point constraints (using their weights in Lie algebra space) and left-multiplies the entire trajectory by that transform as an initial alignment step before optimization.

Returns:

True if an alignment transform was applied, False if

skipped (e.g. no absolute constraints or negligible delta).

Return type:

bool

remove_constraint(self: ouster.sdk._bindings.mapping.PoseOptimizer, constraint_id: int) None

Remove a constraint from the pose optimization problem.

Parameters:

constraint_id (int) – The unique ID of the constraint to remove.

Raises:

RuntimeError – If the constraint ID is not found.

save(self: ouster.sdk._bindings.mapping.PoseOptimizer, osf_filename: 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_filename (str) – The name of the output OSF file.

Returns:

True if the file was successfully saved, False otherwise.

Return type:

bool

save_config(self: ouster.sdk._bindings.mapping.PoseOptimizer, config_filename: str) None

Save the current SolverConfig (including constraints) to a JSON file.

This method serializes the current solver configuration and all constraints to a JSON file. The resulting file can be used later with Pose Optimizer construction to restore the exact same optimization setup.

Parameters:

config_filename (str) – Path where the JSON file should be saved.

Raises:

RuntimeError – If the file cannot be saved.

set_constraints(self: ouster.sdk._bindings.mapping.PoseOptimizer, constraints: list) None

Set all constraints for the pose optimizer.

This method replaces all existing constraints with the provided set of constraints. Any constraints previously loaded from JSON files or added via add_constraint() will be removed and replaced with the new constraint set.

Parameters:
  • constraints (List[Constraint]) – A list of Constraint objects to set as the

  • set. (complete constraint) –

Raises:

RuntimeError – If the constraints cannot be set.

set_solver_step_callback(self: ouster.sdk._bindings.mapping.PoseOptimizer, callback: Callable) None

Register a Python callable to be invoked at each solver iteration.

The callable runs on the same thread as solve(), once per ceres iteration. Use this to hook visualization or logging.

Parameters:

callback (Callable[[], None]) – Function to call each iteration.

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

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).

Returns:

The cost value from the last solve call.

Return type:

float

SolverConfig

class SolverConfig(self: ouster.sdk._bindings.mapping.SolverConfig)

Configuration options for the non-linear optimization solver used in trajectory refinement.

This class encapsulates the configuration options for the solver used in the PoseOptimizer.

key_frame_distance

The distance between nodes in the trajectory (in meters). Controls trajectory discretization.

Type:

float

traj_rotation_weight

The weight for rotational constraints during trajectory optimization. Higher values enforce stronger rotation consistency.

Type:

float

traj_translation_weight

The weight for translational constraints during trajectory optimization. Higher values enforce stronger position consistency.

Type:

float

max_num_iterations

The maximum number of iterations the solver will perform before terminating.

Type:

int

function_tolerance

The tolerance threshold for changes in the cost function. Solver stops when improvements fall below this value.

Type:

float

gradient_tolerance

The tolerance threshold for changes in the gradient. Solver stops when gradient magnitude falls below this value.

Type:

float

parameter_tolerance

The tolerance threshold for changes in parameters. Solver stops when parameter changes fall below this value.

Type:

float

process_printout

Flag to enable or disable detailed printout of the optimization process.

Type:

bool

loss_function

The name of the robust loss function to use (e.g., “HUBER_LOSS”, “CAUCHY_LOSS”, “SOFT_L_ONE_LOSS”, “ARCTAN_LOSS”, “TRIVIAL_LOSS”).

Type:

str

loss_scale

The scaling parameter for the chosen loss function. Higher values make the loss less sensitive to outliers.

Type:

float

fix_first_node

Flag to fix the first node of the trajectory during optimization. Default is False.

Type:

bool

Initialize SolverConfig with default values.

__annotations__ = {}
__init__(self: ouster.sdk._bindings.mapping.SolverConfig) None

Initialize SolverConfig with default values.

__module__ = 'ouster.sdk._bindings.mapping'
property fix_first_node
property function_tolerance
property gradient_tolerance
property key_frame_distance
property loss_function
property loss_scale
property max_num_iterations
property parameter_tolerance
property process_printout
property traj_rotation_weight
property traj_translation_weight

SamplingMode

class SamplingMode(self: ouster.sdk._bindings.mapping.SamplingMode, value: int)

Members:

KEY_FRAMES

COLUMNS

COLUMNS = <SamplingMode.COLUMNS: 1>
KEY_FRAMES = <SamplingMode.KEY_FRAMES: 0>
__annotations__ = {}
__eq__(self: object, other: object) bool
__getstate__(self: object) int
__hash__(self: object) int
__index__(self: ouster.sdk._bindings.mapping.SamplingMode) int
__init__(self: ouster.sdk._bindings.mapping.SamplingMode, value: int) None
__int__(self: ouster.sdk._bindings.mapping.SamplingMode) int
__members__ = {'COLUMNS': <SamplingMode.COLUMNS: 1>, 'KEY_FRAMES': <SamplingMode.KEY_FRAMES: 0>}
__module__ = 'ouster.sdk._bindings.mapping'
__ne__(self: object, other: object) bool
__repr__(self: object) str
__setstate__(self: ouster.sdk._bindings.mapping.SamplingMode, state: int) None
__str__(self: object) str
property name
property value

LossFunction

class LossFunction(self: ouster.sdk._bindings.mapping.LossFunction, value: int)

Members:

HUBER_LOSS

CAUCHY_LOSS

SOFT_L_ONE_LOSS

ARCTAN_LOSS

TRIVIAL_LOSS

ARCTAN_LOSS = <LossFunction.ARCTAN_LOSS: 3>
CAUCHY_LOSS = <LossFunction.CAUCHY_LOSS: 1>
HUBER_LOSS = <LossFunction.HUBER_LOSS: 0>
SOFT_L_ONE_LOSS = <LossFunction.SOFT_L_ONE_LOSS: 2>
TRIVIAL_LOSS = <LossFunction.TRIVIAL_LOSS: 4>
__annotations__ = {}
__eq__(self: object, other: object) bool
__getstate__(self: object) int
__hash__(self: object) int
__index__(self: ouster.sdk._bindings.mapping.LossFunction) int
__init__(self: ouster.sdk._bindings.mapping.LossFunction, value: int) None
__int__(self: ouster.sdk._bindings.mapping.LossFunction) int
__members__ = {'ARCTAN_LOSS': <LossFunction.ARCTAN_LOSS: 3>, 'CAUCHY_LOSS': <LossFunction.CAUCHY_LOSS: 1>, 'HUBER_LOSS': <LossFunction.HUBER_LOSS: 0>, 'SOFT_L_ONE_LOSS': <LossFunction.SOFT_L_ONE_LOSS: 2>, 'TRIVIAL_LOSS': <LossFunction.TRIVIAL_LOSS: 4>}
__module__ = 'ouster.sdk._bindings.mapping'
__ne__(self: object, other: object) bool
__repr__(self: object) str
__setstate__(self: ouster.sdk._bindings.mapping.LossFunction, state: int) None
__str__(self: object) str
static from_string(name: str) ouster.sdk._bindings.mapping.LossFunction

Convert a string (e.g. “HUBER_LOSS”) to the corresponding LossFunction enum.

Args:

name: one of “HUBER_LOSS”, “CAUCHY_LOSS”, “SOFT_L_ONE_LOSS”, “ARCTAN_LOSS”, “TRIVIAL_LOSS”

property name
property value

AbsolutePoseConstraint

class AbsolutePoseConstraint(*args, **kwargs)

Absolute pose constraint - fixes a pose at a specific timestamp.

This constraint type enforces that the sensor pose at a given timestamp matches a specific target pose.

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePoseConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePoseConstraint, timestamp: int, pose: numpy.ndarray[numpy.float64[4, 4]], rotation_weight: float = 1.0, translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for AbsolutePoseConstraint.

    Args:

    timestamp (int): Timestamp of the pose to constrain (nanoseconds) pose: The 4x4 transformation matrix (SE3) to constrain to rotation_weight: Scalar weight applied to the quaternion axis-alignment residual translation_weight: Weight for translation constraints (x, y, z)

__annotations__ = {}
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePoseConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePoseConstraint, timestamp: int, pose: numpy.ndarray[numpy.float64[4, 4]], rotation_weight: float = 1.0, translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for AbsolutePoseConstraint.

    Args:

    timestamp (int): Timestamp of the pose to constrain (nanoseconds) pose: The 4x4 transformation matrix (SE3) to constrain to rotation_weight: Scalar weight applied to the quaternion axis-alignment residual translation_weight: Weight for translation constraints (x, y, z)

__module__ = 'ouster.sdk._bindings.mapping'
property pose
property rotation_weight
property timestamp
property translation_weights

AbsolutePointConstraint

class AbsolutePointConstraint(*args, **kwargs)

Absolute point constraint.

Constrains a single 3D point from a LiDAR scan, identified by its 2D image coordinates (row, col) and return index at a given timestamp, to match a user-defined absolute 3D position in the world frame. The 3D point is computed the same way as in PointToPointConstraint (via RANGE/ RANGE2 and the XYZ LUT), but is compared to a provided global point instead of another scan point.

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePointConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePointConstraint, timestamp: int, row: int, col: int, return_idx: int, absolute_position: numpy.ndarray[numpy.float64[3, 1]], translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for AbsolutePointConstraint.

    Args:

    timestamp (int): Timestamp of the point’s pose (nanoseconds) row (int): Row index of the point col (int): Column index of the point return_idx (int): Return index of the point (1 or 2) absolute_position: Target world position (x, y, z) translation_weight: Weight for translation constraints (x, y, z)

__annotations__ = {}
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePointConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.AbsolutePointConstraint, timestamp: int, row: int, col: int, return_idx: int, absolute_position: numpy.ndarray[numpy.float64[3, 1]], translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for AbsolutePointConstraint.

    Args:

    timestamp (int): Timestamp of the point’s pose (nanoseconds) row (int): Row index of the point col (int): Column index of the point return_idx (int): Return index of the point (1 or 2) absolute_position: Target world position (x, y, z) translation_weight: Weight for translation constraints (x, y, z)

__module__ = 'ouster.sdk._bindings.mapping'
property absolute_position
property col
property return_idx
property row
property timestamp
property translation_weights

PoseToPoseConstraint

class PoseToPoseConstraint(*args, **kwargs)

Relative pose-to-pose constraint - enforces relative transformation between two poses.

This constraint type enforces a specific relative transformation between two poses at different timestamps.

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.PoseToPoseConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.PoseToPoseConstraint, timestamp1: int, timestamp2: int, relative_pose: numpy.ndarray[numpy.float64[4, 4]] = array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]), rotation_weight: float = 1.0, translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for PoseToPoseConstraint.

    Args:

    timestamp1 (int): Timestamp of the first pose (nanoseconds) timestamp2 (int): Timestamp of the second pose (nanoseconds) relative_pose: Expected relative transformation from pose1 to pose2.

    Use the identity matrix to let PoseOptimizer auto-estimate it via ICP.

    rotation_weight: Scalar weight applied to the quaternion axis-alignment residual translation_weight: Weight for translation constraints (x, y, z)

__annotations__ = {}
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.PoseToPoseConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.PoseToPoseConstraint, timestamp1: int, timestamp2: int, relative_pose: numpy.ndarray[numpy.float64[4, 4]] = array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]), rotation_weight: float = 1.0, translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for PoseToPoseConstraint.

    Args:

    timestamp1 (int): Timestamp of the first pose (nanoseconds) timestamp2 (int): Timestamp of the second pose (nanoseconds) relative_pose: Expected relative transformation from pose1 to pose2.

    Use the identity matrix to let PoseOptimizer auto-estimate it via ICP.

    rotation_weight: Scalar weight applied to the quaternion axis-alignment residual translation_weight: Weight for translation constraints (x, y, z)

__module__ = 'ouster.sdk._bindings.mapping'
property relative_pose
property rotation_weight
property timestamp1
property timestamp2
property translation_weights

PointToPointConstraint

class PointToPointConstraint(*args, **kwargs)

Point-to-point constraint - enforces correspondence between points.

This constraint type enforces that specific points in two different lidar scans correspond to the same physical location.

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.PointToPointConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.PointToPointConstraint, timestamp1: int, row1: int, col1: int, return_idx1: int, timestamp2: int, row2: int, col2: int, return_idx2: int, translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for PointToPointConstraint.

    Args:

    timestamp1 (int): Timestamp of the first point’s pose (nanoseconds) row1 (int): Row index of the first point col1 (int): Column index of the first point return_idx1 (int): Return index of the first point (1 or 2) timestamp2 (int): Timestamp of the second point’s pose (nanoseconds) row2 (int): Row index of the second point col2 (int): Column index of the second point return_idx2 (int): Return index of the second point (1 or 2) translation_weight: Weight for translation constraints (x, y, z)

__annotations__ = {}
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: ouster.sdk._bindings.mapping.PointToPointConstraint) -> None

Default constructor

  1. __init__(self: ouster.sdk._bindings.mapping.PointToPointConstraint, timestamp1: int, row1: int, col1: int, return_idx1: int, timestamp2: int, row2: int, col2: int, return_idx2: int, translation_weight: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.])) -> None

    Constructor for PointToPointConstraint.

    Args:

    timestamp1 (int): Timestamp of the first point’s pose (nanoseconds) row1 (int): Row index of the first point col1 (int): Column index of the first point return_idx1 (int): Return index of the first point (1 or 2) timestamp2 (int): Timestamp of the second point’s pose (nanoseconds) row2 (int): Row index of the second point col2 (int): Column index of the second point return_idx2 (int): Return index of the second point (1 or 2) translation_weight: Weight for translation constraints (x, y, z)

__module__ = 'ouster.sdk._bindings.mapping'
property col1
property col2
property return_idx1
property return_idx2
property row1
property row2
property timestamp1
property timestamp2
property translation_weights

save_trajectory

save_trajectory(filename: str, timestamps: numpy.ndarray[numpy.uint64], poses: numpy.ndarray[numpy.float64], file_type: str = 'csv') None