kornia.geometry.conversions¶
Angles¶
- kornia.geometry.conversions.rad2deg(tensor)¶
Function that converts angles from radians to degrees.
- Parameters:
tensor (
Tensor
) – Tensor of arbitrary shape.- Return type:
- Returns:
Tensor with same shape as input.
Example
>>> input = tensor(3.1415926535) >>> rad2deg(input) tensor(180.)
- kornia.geometry.conversions.deg2rad(tensor)¶
Function that converts angles from degrees to radians.
- Parameters:
tensor (
Tensor
) – Tensor of arbitrary shape.- Return type:
- Returns:
tensor with same shape as input.
Examples
>>> input = tensor(180.) >>> deg2rad(input) tensor(3.1416)
- kornia.geometry.conversions.pol2cart(rho, phi)¶
Function that converts polar coordinates to cartesian coordinates.
- Parameters:
- Returns:
Tensor with same shape as input. - y: Tensor with same shape as input.
- Return type:
x
Example
>>> rho = torch.rand(1, 3, 3) >>> phi = torch.rand(1, 3, 3) >>> x, y = pol2cart(rho, phi)
- kornia.geometry.conversions.cart2pol(x, y, eps=1.0e-8)¶
Function that converts cartesian coordinates to polar coordinates.
- Parameters:
- Returns:
Tensor with same shape as input. - phi: Tensor with same shape as input.
- Return type:
rho
Example
>>> x = torch.rand(1, 3, 3) >>> y = torch.rand(1, 3, 3) >>> rho, phi = cart2pol(x, y)
- kornia.geometry.conversions.angle_to_rotation_matrix(angle)¶
Create a rotation matrix out of angles in degrees.
- Parameters:
angle (
Tensor
) – tensor of angles in degrees, any shape \((*)\).- Return type:
- Returns:
tensor of rotation matrices with shape \((*, 2, 2)\).
Example
>>> input = torch.rand(1, 3) # Nx3 >>> output = angle_to_rotation_matrix(input) # Nx3x2x2
Coordinates¶
- kornia.geometry.conversions.convert_points_from_homogeneous(points, eps=1e-8)¶
Function that converts points from homogeneous to Euclidean space.
- Parameters:
- Return type:
- Returns:
the points in Euclidean space \((B, N, D-1)\).
Examples
>>> input = tensor([[0., 0., 1.]]) >>> convert_points_from_homogeneous(input) tensor([[0., 0.]])
- kornia.geometry.conversions.convert_points_to_homogeneous(points)¶
Function that converts points from Euclidean to homogeneous space.
- Parameters:
points (
Tensor
) – the points to be transformed with shape \((*, N, D)\).- Return type:
- Returns:
the points in homogeneous coordinates \((*, N, D+1)\).
Examples
>>> input = tensor([[0., 0.]]) >>> convert_points_to_homogeneous(input) tensor([[0., 0., 1.]])
- kornia.geometry.conversions.convert_affinematrix_to_homography(A)¶
Function that converts batch of affine matrices.
- Parameters:
A (
Tensor
) – the affine matrix with shape \((B,2,3)\).- Return type:
- Returns:
the homography matrix with shape of \((B,3,3)\).
Examples
>>> A = tensor([[[1., 0., 0.], ... [0., 1., 0.]]]) >>> convert_affinematrix_to_homography(A) tensor([[[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]])
- kornia.geometry.conversions.denormalize_pixel_coordinates(pixel_coordinates, height, width, eps=1e-8)¶
Denormalize pixel coordinates.
The input is assumed to be -1 if on extreme left, 1 if on extreme right (x = w-1).
- Parameters:
- Return type:
- Returns:
the denormalized pixel coordinates with shape \((*, 2)\).
Examples
>>> coords = tensor([[-1., -1.]]) >>> denormalize_pixel_coordinates(coords, 100, 50) tensor([[0., 0.]])
- kornia.geometry.conversions.normalize_pixel_coordinates(pixel_coordinates, height, width, eps=1e-8)¶
Normalize pixel coordinates between -1 and 1.
Normalized, -1 if on extreme left, 1 if on extreme right (x = w-1).
- Parameters:
- Return type:
- Returns:
the normalized pixel coordinates with shape \((*, 2)\).
Examples
>>> coords = tensor([[50., 100.]]) >>> normalize_pixel_coordinates(coords, 100, 50) tensor([[1.0408, 1.0202]])
- kornia.geometry.conversions.denormalize_pixel_coordinates3d(pixel_coordinates, depth, height, width, eps=1e-8)¶
Denormalize pixel coordinates.
The input is assumed to be -1 if on extreme left, 1 if on extreme right (x = w-1).
- Parameters:
- Return type:
- Returns:
the denormalized pixel coordinates.
- kornia.geometry.conversions.normalize_pixel_coordinates3d(pixel_coordinates, depth, height, width, eps=1e-8)¶
Normalize pixel coordinates between -1 and 1.
Normalized, -1 if on extreme left, 1 if on extreme right (x = w-1).
- Parameters:
- Return type:
- Returns:
the normalized pixel coordinates.
- kornia.geometry.conversions.normalize_points_with_intrinsics(point_2d, camera_matrix)¶
Normalizes points with intrinsics. Useful for conversion of keypoints to be used with essential matrix.
- Parameters:
- Return type:
- Returns:
tensor of (u, v) cam coordinates with shape \((*, 2)\).
Example
>>> _ = torch.manual_seed(0) >>> X = torch.rand(1, 2) >>> K = torch.eye(3)[None] >>> normalize_points_with_intrinsics(X, K) tensor([[0.4963, 0.7682]])
- kornia.geometry.conversions.denormalize_points_with_intrinsics(point_2d_norm, camera_matrix)¶
Normalizes points with intrinsics. Useful for conversion of keypoints to be used with essential matrix.
- Parameters:
- Return type:
- Returns:
tensor of (u, v) cam coordinates with shape \((*, 2)\).
Example
>>> _ = torch.manual_seed(0) >>> X = torch.rand(1, 2) >>> K = torch.eye(3)[None] >>> denormalize_points_with_intrinsics(X, K) tensor([[0.4963, 0.7682]])
Homography¶
- kornia.geometry.conversions.normalize_homography(dst_pix_trans_src_pix, dsize_src, dsize_dst)¶
Normalize a given homography in pixels to [-1, 1].
- Parameters:
- Return type:
- Returns:
the normalized homography of shape \((B, 3, 3)\).
- kornia.geometry.conversions.denormalize_homography(dst_pix_trans_src_pix, dsize_src, dsize_dst)¶
De-normalize a given homography in pixels from [-1, 1] to actual height and width.
- Parameters:
- Return type:
- Returns:
the denormalized homography of shape \((B, 3, 3)\).
- kornia.geometry.conversions.normalize_homography3d(dst_pix_trans_src_pix, dsize_src, dsize_dst)¶
Normalize a given homography in pixels to [-1, 1].
- Parameters:
- Return type:
- Returns:
the normalized homography.
- Shape:
Output: \((B, 4, 4)\)
Quaternion¶
- kornia.geometry.conversions.quaternion_to_axis_angle(quaternion)¶
Convert quaternion vector to axis angle of rotation in radians.
The quaternion should be in (w, x, y, z) format.
Adapted from ceres C++ library: ceres-solver/include/ceres/rotation.h
- Parameters:
quaternion (
Tensor
) – tensor with quaternions.- Return type:
- Returns:
tensor with axis angle of rotation.
- Shape:
Input: \((*, 4)\) where * means, any number of dimensions
Output: \((*, 3)\)
Example
>>> quaternion = tensor((1., 0., 0., 0.)) >>> quaternion_to_axis_angle(quaternion) tensor([0., 0., 0.])
- kornia.geometry.conversions.quaternion_to_rotation_matrix(quaternion)¶
Convert a quaternion to a rotation matrix.
The quaternion should be in (w, x, y, z) format.
- Parameters:
quaternion (
Tensor
) – a tensor containing a quaternion to be converted. The tensor can be of shape \((*, 4)\).- Return type:
- Returns:
the rotation matrix of shape \((*, 3, 3)\).
Example
>>> quaternion = tensor((0., 0., 0., 1.)) >>> quaternion_to_rotation_matrix(quaternion) tensor([[-1., 0., 0.], [ 0., -1., 0.], [ 0., 0., 1.]])
- kornia.geometry.conversions.quaternion_log_to_exp(quaternion, eps=1.0e-8)¶
Apply exponential map to log quaternion.
The quaternion should be in (w, x, y, z) format.
- Parameters:
- Return type:
- Returns:
the quaternion exponential map of shape \((*, 4)\).
Example
>>> quaternion = tensor((0., 0., 0.)) >>> quaternion_log_to_exp(quaternion, eps=torch.finfo(quaternion.dtype).eps) tensor([1., 0., 0., 0.])
- kornia.geometry.conversions.quaternion_exp_to_log(quaternion, eps=1.0e-8)¶
Apply the log map to a quaternion.
The quaternion should be in (w, x, y, z) format.
- Parameters:
- Return type:
- Returns:
the quaternion log map of shape \((*, 3)\).
Example
>>> quaternion = tensor((1., 0., 0., 0.)) >>> quaternion_exp_to_log(quaternion, eps=torch.finfo(quaternion.dtype).eps) tensor([0., 0., 0.])
- kornia.geometry.conversions.normalize_quaternion(quaternion, eps=1.0e-12)¶
Normalize a quaternion.
The quaternion should be in (x, y, z, w) or (w, x, y, z) format.
- Parameters:
- Return type:
- Returns:
the normalized quaternion of shape \((*, 4)\).
Example
>>> quaternion = tensor((1., 0., 1., 0.)) >>> normalize_quaternion(quaternion) tensor([0.7071, 0.0000, 0.7071, 0.0000])
Vector¶
- kornia.geometry.conversions.vector_to_skew_symmetric_matrix(vec)¶
Converts a vector to a skew symmetric matrix.
A vector \((v1, v2, v3)\) has a corresponding skew-symmetric matrix, which is of the form:
\[\begin{split}\begin{bmatrix} 0 & -v3 & v2 \\ v3 & 0 & -v1 \\ -v2 & v1 & 0\end{bmatrix}\end{split}\]- Parameters:
x – tensor of shape \((B, 3)\).
- Return type:
- Returns:
tensor of shape \((B, 3, 3)\).
Example
>>> vec = torch.tensor([1.0, 2.0, 3.0]) >>> vector_to_skew_symmetric_matrix(vec) tensor([[ 0., -3., 2.], [ 3., 0., -1.], [-2., 1., 0.]])
Rotation Matrix¶
- kornia.geometry.conversions.rotation_matrix_to_axis_angle(rotation_matrix)¶
Convert 3x3 rotation matrix to Rodrigues vector in radians.
- Parameters:
rotation_matrix (
Tensor
) – rotation matrix of shape \((N, 3, 3)\).- Return type:
- Returns:
Rodrigues vector transformation of shape \((N, 3)\).
Example
>>> input = tensor([[1., 0., 0.], ... [0., 1., 0.], ... [0., 0., 1.]]) >>> rotation_matrix_to_axis_angle(input) tensor([0., 0., 0.])
>>> input = tensor([[1., 0., 0.], ... [0., 0., -1.], ... [0., 1., 0.]]) >>> rotation_matrix_to_axis_angle(input) tensor([1.5708, 0.0000, 0.0000])
- kornia.geometry.conversions.rotation_matrix_to_quaternion(rotation_matrix, eps=1.0e-8)¶
Convert 3x3 rotation matrix to 4d quaternion vector.
The quaternion vector has components in (w, x, y, z) format.
- Parameters:
- Return type:
- Returns:
the rotation in quaternion with shape \((*, 4)\).
Example
>>> input = tensor([[1., 0., 0.], ... [0., 1., 0.], ... [0., 0., 1.]]) >>> rotation_matrix_to_quaternion(input, eps=torch.finfo(input.dtype).eps) tensor([1., 0., 0., 0.])
Axis Angle¶
- kornia.geometry.conversions.axis_angle_to_quaternion(axis_angle)¶
Convert an axis angle to a quaternion.
The quaternion vector has components in (w, x, y, z) format.
Adapted from ceres C++ library: ceres-solver/include/ceres/rotation.h
- Parameters:
axis_angle (
Tensor
) – tensor with axis angle in radians.- Return type:
- Returns:
tensor with quaternion.
- Shape:
Input: \((*, 3)\) where * means, any number of dimensions
Output: \((*, 4)\)
Example
>>> axis_angle = tensor((0., 1., 0.)) >>> axis_angle_to_quaternion(axis_angle) tensor([0.8776, 0.0000, 0.4794, 0.0000])
- kornia.geometry.conversions.axis_angle_to_rotation_matrix(axis_angle)¶
Convert 3d vector of axis-angle rotation to 3x3 rotation matrix.
- Parameters:
axis_angle (
Tensor
) – tensor of 3d vector of axis-angle rotations in radians with shape \((N, 3)\).- Return type:
- Returns:
tensor of rotation matrices of shape \((N, 3, 3)\).
Example
>>> input = tensor([[0., 0., 0.]]) >>> axis_angle_to_rotation_matrix(input) tensor([[[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]])
>>> input = tensor([[1.5708, 0., 0.]]) >>> axis_angle_to_rotation_matrix(input) tensor([[[ 1.0000e+00, 0.0000e+00, 0.0000e+00], [ 0.0000e+00, -3.6200e-06, -1.0000e+00], [ 0.0000e+00, 1.0000e+00, -3.6200e-06]]])
Euler Angles¶
- kornia.geometry.conversions.quaternion_from_euler(roll, pitch, yaw)¶
Convert Euler angles to quaternion coefficients.
Euler angles are assumed to be in radians in XYZ convention.
- kornia.geometry.conversions.euler_from_quaternion(w, x, y, z)¶
Convert a quaternion coefficients to Euler angles.
Returned angles are in radians in XYZ convention.
Pose¶
- kornia.geometry.conversions.Rt_to_matrix4x4(R, t)¶
Combines 3x3 rotation matrix R and 1x3 translation vector t into 4x4 extrinsics.
- Parameters:
- Return type:
- Returns:
the extrinsics \((B, 4, 4)\).
Example
>>> R, t = torch.eye(3)[None], torch.ones(3).reshape(1, 3, 1) >>> Rt_to_matrix4x4(R, t) tensor([[[1., 0., 0., 1.], [0., 1., 0., 1.], [0., 0., 1., 1.], [0., 0., 0., 1.]]])
- kornia.geometry.conversions.matrix4x4_to_Rt(extrinsics)¶
Converts 4x4 extrinsics into 3x3 rotation matrix R and 1x3 translation vector ts.
- Parameters:
extrinsics (
Tensor
) – pose matrix \((B, 4, 4)\).- Returns:
Rotation matrix, \((B, 3, 3).\) t: Translation matrix \((B, 3, 1)\).
- Return type:
R
Example
>>> ext = torch.eye(4)[None] >>> matrix4x4_to_Rt(ext) (tensor([[[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]]), tensor([[[0.], [0.], [0.]]]))
- kornia.geometry.conversions.worldtocam_to_camtoworld_Rt(R, t)¶
Converts worldtocam frame i.e. projection from world to the camera coordinate system (used in Colmap) to camtoworld, i.e. projection from camera coordinate system to world coordinate system.
- Parameters:
- Returns:
Rotation matrix, \((B, 3, 3).\) tinv: Translation matrix \((B, 3, 1)\).
- Return type:
Rinv
Example
>>> R, t = torch.eye(3)[None], torch.ones(3).reshape(1, 3, 1) >>> worldtocam_to_camtoworld_Rt(R, t) (tensor([[[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]]), tensor([[[-1.], [-1.], [-1.]]]))
- kornia.geometry.conversions.camtoworld_to_worldtocam_Rt(R, t)¶
Converts camtoworld, i.e. projection from camera coordinate system to world coordinate system, to worldtocam frame i.e. projection from world to the camera coordinate system (used in Colmap). See long-url: https://colmap.github.io/format.html#output-format
- Parameters:
- Returns:
Rotation matrix, \((B, 3, 3).\) tinv: Translation matrix \((B, 3, 1)\).
- Return type:
Rinv
Example
>>> R, t = torch.eye(3)[None], torch.ones(3).reshape(1, 3, 1) >>> camtoworld_to_worldtocam_Rt(R, t) (tensor([[[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]]), tensor([[[-1.], [-1.], [-1.]]]))
- kornia.geometry.conversions.camtoworld_graphics_to_vision_4x4(extrinsics_graphics)¶
Converts graphics coordinate frame (e.g. OpenGL) to vision coordinate frame (e.g. OpenCV.), , i.e. flips y and z axis. Graphics convention: [+x, +y, +z] == [right, up, backwards]. Vision convention: [+x, +y, +z] ==
[right, down, forwards]
- Parameters:
extrinsics – pose matrix \((B, 4, 4)\).
- Returns:
pose matrix \((B, 4, 4)\).
- Return type:
extrinsics
Example
>>> ext = torch.eye(4)[None] >>> camtoworld_graphics_to_vision_4x4(ext) tensor([[[ 1., 0., 0., 0.], [ 0., -1., 0., 0.], [ 0., 0., -1., 0.], [ 0., 0., 0., 1.]]])
- kornia.geometry.conversions.camtoworld_vision_to_graphics_4x4(extrinsics_vision)¶
Converts vision coordinate frame (e.g. OpenCV) to graphics coordinate frame (e.g. OpenGK.), i.e. flips y and z axis Graphics convention: [+x, +y, +z] == [right, up, backwards]. Vision convention: [+x, +y, +z] == [right, down, forwards]
- Parameters:
extrinsics – pose matrix \((B, 4, 4)\).
- Returns:
pose matrix \((B, 4, 4)\).
- Return type:
extrinsics
Example
>>> ext = torch.eye(4)[None] >>> camtoworld_vision_to_graphics_4x4(ext) tensor([[[ 1., 0., 0., 0.], [ 0., -1., 0., 0.], [ 0., 0., -1., 0.], [ 0., 0., 0., 1.]]])
- kornia.geometry.conversions.camtoworld_graphics_to_vision_Rt(R, t)¶
Converts graphics coordinate frame (e.g. OpenGL) to vision coordinate frame (e.g. OpenCV.), , i.e. flips y and z axis. Graphics convention: [+x, +y, +z] == [right, up, backwards]. Vision convention: [+x, +y, +z] ==
[right, down, forwards]
- Parameters:
- Returns:
Rotation matrix, \((B, 3, 3).\) t: Translation matrix \((B, 3, 1)\).
- Return type:
R
Example
>>> R, t = torch.eye(3)[None], torch.ones(3).reshape(1, 3, 1) >>> camtoworld_graphics_to_vision_Rt(R, t) (tensor([[[ 1., 0., 0.], [ 0., -1., 0.], [ 0., 0., -1.]]]), tensor([[[1.], [1.], [1.]]]))
- kornia.geometry.conversions.camtoworld_vision_to_graphics_Rt(R, t)¶
Converts graphics coordinate frame (e.g. OpenGL) to vision coordinate frame (e.g. OpenCV.), , i.e. flips y and z axis. Graphics convention: [+x, +y, +z] == [right, up, backwards]. Vision convention: [+x, +y, +z] ==
[right, down, forwards]
- Parameters:
- Returns:
Rotation matrix, \((B, 3, 3).\) t: Translation matrix \((B, 3, 1)\).
- Return type:
R
Example
>>> R, t = torch.eye(3)[None], torch.ones(3).reshape(1, 3, 1) >>> camtoworld_vision_to_graphics_Rt(R, t) (tensor([[[ 1., 0., 0.], [ 0., -1., 0.], [ 0., 0., -1.]]]), tensor([[[1.], [1.], [1.]]]))
- kornia.geometry.conversions.ARKitQTVecs_to_ColmapQTVecs(qvec, tvec)¶
Converts output of Apple ARKit screen pose (in quaternion representation) to the camera-to-world transformation, expected by Colmap, also in quaternion representation.
- Parameters:
- Returns:
Colmap rotation quaternion \((B, 4)\), [w, x, y, z] format. tvec: translation vector \((B, 3, 1)\), [x, y, z]
- Return type:
qvec
Example
>>> q, t = tensor([0, 1, 0, 1.])[None], torch.ones(3).reshape(1, 3, 1) >>> ARKitQTVecs_to_ColmapQTVecs(q, t) (tensor([[0.7071, 0.0000, 0.7071, 0.0000]]), tensor([[[-1.0000], [-1.0000], [ 1.0000]]]))