pypose.point2pixel¶
- pypose.point2pixel(points, intrinsics, extrinsics=None)[source]¶
Project batched sets of points (either in camera or world frame) to pixels.
- Parameters:
points (
torch.Tensor
) – The 3D coordinate of points. Assumed to be in the camera frame ifextrinsics
isNone
, otherwiwse in the world frame. The shape has to be (…, N, 3).intrinsics (
torch.Tensor
) – The intrinsic parameters of cameras. The shape has to be (…, 3, 3).extrinsics (
pypose.LieTensor
, optional) – The extrinsic parameters of cameras. The shape has to be (…, 7). Default:None
.
- Returns:
The associated pixel with shape (…, N, 2).
- Return type:
torch.Tensor
Example
>>> import torch, pypose as pp >>> f, (H, W) = 2, (9, 9) # focal length and image height, width >>> intrinsics = torch.tensor([[f, 0, H / 2], ... [0, f, W / 2], ... [0, 0, 1 ]]) >>> object = torch.tensor([[2., 0., 2.], ... [1., 0., 2.], ... [0., 1., 1.], ... [0., 0., 1.], ... [1., 0., 1.], ... [5., 5., 3.]]) >>> pixels = pp.point2pixel(object, intrinsics) tensor([[6.5000, 4.5000], [5.5000, 4.5000], [4.5000, 6.5000], [4.5000, 4.5000], [6.5000, 4.5000], [7.8333, 7.8333]]) >>> pose = pp.SE3([ 0., -8, 0., 0., -0.3827, 0., 0.9239]) >>> pixels = pp.point2pixel(object, intrinsics, pose) tensor([[ 4.4999, -1.1568], [ 3.8332, -3.0425], [ 2.4998, -15.2997], [ 2.4998, -18.1282], [ 4.4999, -6.8135], [ 4.9999, 3.4394]])