Sensors

General

All sensors derive from a common base class. This base class is not available from Python.

class kontiki.sensors.Sensor
relative_pose

A tuple (q, p) where p is the relative position, and q the relative orientation between the sensor coordinate frame, and the trajectory coordinate frame such that X_sensor = R * X_world + p. q is a unit quaternion representing the orientation R. Defaults to the identity orientation, and zero, respectively.

time_offset

The time offset d between a reference time frame, and the sensor. Any function foo(t) of the sensor is instead called as foo(t + d). Defaults to 0.

max_time_offset

When optimizing the time offset, this is the maximum deviation from 0.

from_trajectory(X : ndarray) → ndarray

Moves the 3D point X from the trajectory to the sensor coordinate frame, by applying the relative pose.

to_trajectory(X : ndarray) → ndarray

Moves the 3D point X from the sensor to the trajectory coordinate frame, by applying the relative pose.

relative_orientation_locked

If True, the orientation part of the relative pose can not be changed during optimization. Defaults to True.

relative_position_locked

If True, the translation part of the relative pose can not be changed during optimization. Defaults to True.

time_offset_locked

If True, the time offset can not be changed during optimization. Defaults to True.

Cameras

All cameras share the following (unavailable) base class

class kontiki.sensors.Camera
rows

The number of image rows

cols

The number of image columns

readout

Rolling shutter readout time. Set to 0 for global shutter.

project(X : ndarray) → ndarray

Projects the 3D point X in camera coordinates, to its 2D image plane location using the camera projection model.

Note

This does not apply the relative pose of the camera

unproject(y : ndarray) → ndarray

Apply inverse projection on image (2D) location y, to get a 3D point X=(x, y, z), where z=1.

Note

This does not apply the relative pose of the camera

to_trajectory(X : ndarray) → ndarray

Moves the 3D point X in camera coordinates t

Camera classes

class kontiki.sensors.PinholeCamera

Standard pinhole camera

camera_matrix

The 3x3 internal camera calibration matrix

class kontiki.sensors.AtanCamera

Arc-tan camera model for wide-angle cameras

Implementation of the 3-parameter FOV model of [Devernay2001].

Subclass of PinholeCamera.

References

[Devernay2001]Devernay, F. and Faugeras, O. Straight lines have to be straight: Automatic calibration and removal of distortion from scenes of structured environments Machie Vision and Applications, Vol 13., 2001
gamma

Distortion parameter

wc

Distortion center

IMUs

All inertial measurement units share the following (unavailable) base class:

class kontiki.sensors.Imu
accelerometer(trajectory : Trajectory, t : float) → ndarray

A single accelerometer measurement at time t, using the specified trajectory.

gyroscope(trajectory : Trajectory, t : float) → ndarray

A single gyroscope measurement at time t, using the specified trajectory.

IMU classes

class kontiki.sensors.BasicImu

Basic IMU

This IMU model produces ideal IMU measurements.

class kontiki.sensors.ConstantBiasImu

IMU with constant biases

Both biases are modeled as constants.

accelerometer_bias

Accelerometer bias

accelerometer_bias_locked

If True (default), then the accelerometer bias is not changed during optimization.

gyroscope_bias

Gyroscope bias

gyroscope_bias_locked

If True (default), then the gyrocope bias is not changed during optimization.