# ImgTransformations

ImgTransformations are not a standalone message type, but are metadata attached to several DepthAI messages that describe all the
parameters of the virtual camera that would produce such an image. The stored information includes the full history of
transformations (crop, resize, rotate, align, warp), distortion coefficients, image dimensions and extrinsics to a common
reference coordinate system. They are tracked explicitly across all nodes, instead of forcing you to manually reconstruct them
from the node configuration. Nodes can use ImgTransformations for a variety of purposes, including:

 * Aligning RGB, depth, and other derived streams when geometry needs to move between them.
 * Remapping rectangles, points, and other image-space geometry after an
   [ImageManip](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/image_manip.md),
   [ImageAlign](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/image_align.md), or similar operation.
 * Reading intrinsics, extrinsics or any other camera properties for the image that was actually produced, rather than assuming
   the original sensor intrinsics still apply.

```python
frame = queue.get()
transform = frame.getTransformation()
intrinsics = transform.getSourceIntrinsicMatrix()
```

## Usage

The following messages have an ImgTransformations field:

 * [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)
 * [Tracklets](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/tracklets.md)
 * [ImgDetections](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_detections.md)
 * [SpatialImgDetections](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/spatial_img_detections.md)
 * [AprilTags](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/april_tags.md)
 * [PointCloudData](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/pointcloud_data.md)

## Related examples

 * [ImageManip remap](https://docs.luxonis.com/software-v3/depthai/examples/image_manip/image_manip_remap.md)
 * [Object Tracker Remap](https://docs.luxonis.com/software-v3/depthai/examples/object_tracker/object_tracker_remap.md)
 * [Stereo Depth Remap](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth_remap.md)

## Reference

### dai::ImgTransformation

Kind: struct

ImgTransformation struct. Holds information of how a ImgFrame or related message was transformed from their source. Useful for
remapping from one ImgFrame to another.

#### ImgTransformation()

Kind: function

#### ImgTransformation(size_t width, size_t height)

Kind: function

#### ImgTransformation(size_t srcWidth, size_t srcHeight, size_t width, size_t height)

Kind: function

#### ImgTransformation(size_t width, size_t height, std::array< std::array< float, 3 >, 3 > sourceIntrinsicMatrix)

Kind: function

#### ImgTransformation(size_t width, size_t height, std::array< std::array< float, 3 >, 3 > sourceIntrinsicMatrix, CameraModel
distortionModel, std::vector< float > distortionCoefficients)

Kind: function

#### ImgTransformation(size_t width, size_t height, std::array< std::array< float, 3 >, 3 > sourceIntrinsicMatrix, CameraModel
distortionModel, std::vector< float > distortionCoefficients, Extrinsics extrinsics)

Kind: function

#### dai::Point2f transformPoint(dai::Point2f point)

Kind: function

Transform a point from the source frame to the current frame. parameters: point: Point to transform return: Transformed point

#### dai::RotatedRect transformRect(dai::RotatedRect rect)

Kind: function

Transform a rotated rect from the source frame to the current frame. parameters: rect: Rectangle to transform return: Transformed
rectangle

#### dai::Point2f invTransformPoint(dai::Point2f point)

Kind: function

Transform a point from the current frame to the source frame. parameters: point: Point to transform return: Transformed point

#### dai::RotatedRect invTransformRect(dai::RotatedRect rect)

Kind: function

Transform a rotated rect from the current frame to the source frame. parameters: rect: Rectangle to transform return: Transformed
rectangle

#### std::pair< size_t, size_t > getSize()

Kind: function

Retrieve the size of the frame. Should be equal to the size of the corresponding ImgFrame message. return: Size of the frame

#### std::pair< size_t, size_t > getSourceSize()

Kind: function

Retrieve the size of the source frame from which this frame was derived. return: Size of the frame

#### std::array< std::array< float, 3 >, 3 > getMatrix()

Kind: function

Retrieve the transformation matrix from the source frame to the current frame. return: Transformation matrix

#### std::array< std::array< float, 3 >, 3 > getMatrixInv()

Kind: function

Retrieve the inverse transformation matrix from the current frame to the source frame. return: Inverse transformation matrix

#### std::array< std::array< float, 3 >, 3 > getSourceIntrinsicMatrix()

Kind: function

Retrieve the intrinsic matrix of the source sensor. return: Intrinsic matrix

#### std::array< std::array< float, 3 >, 3 > getSourceIntrinsicMatrixInv()

Kind: function

Retrieve the inverse intrinsic matrix of the source sensor. return: Inverse intrinsic matrix

#### CameraModel getDistortionModel()

Kind: function

Retrieve the distortion model of the source sensor return: Distortion model

#### std::vector< float > getDistortionCoefficients()

Kind: function

Retrieve the distortion coefficients of the source sensor return: vector of distortion coefficients

#### Extrinsics getExtrinsics()

Kind: function

Retrieve the extrinsics to the source sensor. return: Extrinsics

#### bool isEqualTransformation(const ImgTransformation & other)

Kind: function

Two transformations are equal if the transformation matrices, intrinsic matrices, distortion models, distortion coefficients,
extrinsics, and sizes are all equal. parameters: other: Transformation to compare with return: True if the transformations are
equal, false otherwise

#### std::array< std::array< float, 3 >, 3 > getTransformationMatrix()

Kind: function

#### std::array< std::array< float, 3 >, 3 > getTransformationMatrixInv()

Kind: function

#### std::array< std::array< float, 3 >, 3 > getIntrinsicMatrix()

Kind: function

Retrieve the total intrinsic matrix calculated from transform * intrinsic. return: total intrinsic matrix

#### std::array< std::array< float, 3 >, 3 > getIntrinsicMatrixInv()

Kind: function

Retrieve the inverse of the total intrinsic matrix. return: inverse total intrinsic matrix

#### float getDFov(bool source)

Kind: function

Retrieve the diagonal field of view of the image. parameters: source: If true, the source field of view will be returned.
Otherwise, the current field of view will be returned. return: Diagonal field of view in degrees

#### float getHFov(bool source)

Kind: function

Retrieve the horizontal field of view of the image. parameters: source: If true, the source field of view will be returned.
Otherwise, the current field of view will be returned. return: Horizontal field of view in degrees

#### float getVFov(bool source)

Kind: function

Retrieve the vertical field of view of the image. parameters: source: If true, the source field of view will be returned.
Otherwise, the current field of view will be returned. return: Vertical field of view in degrees

#### std::vector< dai::RotatedRect > getSrcCrops()

Kind: function

#### bool getSrcMaskPt(size_t x, size_t y)

Kind: function

Returns true if the point is inside the transformed region of interest (determined by crops used).

#### bool getDstMaskPt(size_t x, size_t y)

Kind: function

Returns true if the point is inside the image region (not in the background region).

#### ImgTransformation & addTransformation(std::array< std::array< float, 3 >, 3 > matrix)

Kind: function

Add a new transformation. parameters: matrix: Transformation matrix

#### ImgTransformation & addCrop(int x, int y, int width, int height)

Kind: function

Add a crop transformation. parameters: x: X coordinate of the top-left corner of the crop; y: Y coordinate of the top-left corner
of the crop; width: Width of the crop; height: Height of the crop

#### ImgTransformation & addPadding(int top, int bottom, int left, int right)

Kind: function

Add a pad transformation. Works like crop, but in reverse. parameters: top: Padding on the top; bottom: Padding on the bottom;
left: Padding on the left; right: Padding on the right

#### ImgTransformation & addFlipVertical()

Kind: function

Add a vertical flip transformation.

#### ImgTransformation & addFlipHorizontal()

Kind: function

Add a horizontal flip transformation.

#### ImgTransformation & addRotation(float angle, dai::Point2f rotationPoint)

Kind: function

Add a rotation transformation. parameters: angle: Angle in degrees; rotationPoint: Point around which to rotate

#### ImgTransformation & addScale(float scaleX, float scaleY)

Kind: function

Add a scale transformation. parameters: scaleX: Scale factor in the horizontal direction; scaleY: Scale factor in the vertical
direction

#### ImgTransformation & addSrcCrops(const std::vector< dai::RotatedRect > & crops)

Kind: function

#### ImgTransformation & setSize(size_t width, size_t height)

Kind: function

#### ImgTransformation & setSourceSize(size_t width, size_t height)

Kind: function

#### ImgTransformation & setExtrinsics(const Extrinsics & extrinsics)

Kind: function

#### ImgTransformation & setIntrinsicMatrix(std::array< std::array< float, 3 >, 3 > intrinsicMatrix)

Kind: function

#### ImgTransformation & setDistortionModel(CameraModel model)

Kind: function

#### ImgTransformation & setDistortionCoefficients(std::vector< float > coefficients)

Kind: function

#### dai::Point2f remapPointTo(const ImgTransformation & to, dai::Point2f point)

Kind: function

Remap a point from this transformation to another. If the intrinsics are different (e.g. different camera), the function will also
use the intrinsics to remap the point. parameters: to: Transformation to remap to; point: Point to remap note: This function
assumes both transformations have the same source (eg. same source camera socket). If they don't, remapping will be inaccurate.

#### dai::Point2f remapPointFrom(const ImgTransformation & from, dai::Point2f point)

Kind: function

Remap a point to this transformation from another. If the intrinsics are different (e.g. different camera), the function will also
use the intrinsics to remap the point. parameters: from: Transformation to remap from; point: Point to remap

#### dai::RotatedRect remapRectTo(const ImgTransformation & to, dai::RotatedRect rect)

Kind: function

Remap a rotated rect from this transformation to another. If the intrinsics are different (e.g. different camera), the function
will also use the intrinsics to remap the rect. parameters: to: Transformation to remap to; rect: RotatedRect to remap

#### dai::RotatedRect remapRectFrom(const ImgTransformation & from, dai::RotatedRect rect)

Kind: function

Remap a rotated rect to this transformation from another. If the intrinsics are different (e.g. different camera), the function
will also use the intrinsics to remap the rect. parameters: from: Transformation to remap from; rect: RotatedRect to remap

#### dai::Point2f project3DPoint(const dai::Point3f & point)

Kind: function

Project a 3D spatial point into 2D point in the current frame defined by this transformation. parameters: point: 3D point to
project return: Projected 2D point in the current frame note: This function assumes that the point is in the coordinate system of
the current frame.

#### dai::Point2f projectPointTo(const ImgTransformation & to, dai::Point2f & point, float depth)

Kind: function

Project a 2D point from the source frame defined by this transformation into a 2D point in the target frame defined by the to
transformation. This function will use the depth of the point to project it into 3D space and then reproject it back to 2D in the
target frame. parameters: to: Target transformation to project to; point2f: Source 2D point in the current frame; depth: (mm)
Depth of the point to project return: Projected 2D point in the target frame (to transformation)

#### dai::RotatedRect projectRectTo(const ImgTransformation & to, RotatedRect & rect, float depth)

Kind: function

Project a rotated rectangle from the source frame defined by this transformation into the target frame defined by the to
transformation. This function assumes the rectangle is parallel to the image plane (i.e. the entire rectangle is at the same depth
away). The function fits the smallest possible rectangle on to the projected corners of the original rectangle. parameters: to:
Target transformation to project to; rect: Source rotated rectangle in the current frame; depth: (mm) Depth of the rectangle to
project

#### dai::Point2f project3DPointTo(const ImgTransformation & to, const dai::Point3f & point)

Kind: function

Project a 3D spatial point from the source coordinate system (this transformation) into a 2D point in the target frame (to
transformation). parameters: to: Target transformation to project to; point3f: 3D point to project return: Projected 2D point in
the target frame (to transformation) note: This function assumes that the point3f is in the coordinate system of the current
frame.

#### dai::Point2f project3DPointFrom(const ImgTransformation & from, const dai::Point3f & point)

Kind: function

Project a 3D point from the source frame (from transformation) into a 2D point in the current frame (this transformation).
parameters: from: Transformation to project from; point3f: 3D point to project return: Projected 2D point in the current frame
note: This function assumes that the point3f is in the coordinate system of the source frame.

#### dai::Point3f remap3DPointTo(const ImgTransformation & to, const dai::Point3f & point)

Kind: function

Remap a 3D point from the source coordinate system of this transformation to the coordinate system of the target transformation
(to transformation). parameters: to: Target transformation to remap to; point: 3D point to remap return: Remapped 3D point in the
target coordinate system note: This function assumes that the point is in the coordinate system of the current frame.

#### dai::Point3f remap3DPointFrom(const ImgTransformation & from, const dai::Point3f & point)

Kind: function

Remap a 3D point to the coordinate system of this transformation from the source coordinate system of the from transformation.
parameters: from: Transformation to remap from; point: 3D point to remap return: Remapped 3D point in the current coordinate
system note: This function assumes that the point is in the coordinate system of the source frame.

#### std::array< std::array< float, 4 >, 4 > getExtrinsicsTransformationMatrixTo(const ImgTransformation & to, bool
useSpecTranslation, LengthUnit sourceUnit)

Kind: function

Get the extrinsic transformation matrix from the source coordinate system of this transformation to the target coordinate system
of the to transformation. parameters: to: Target transformation to get extrinsics to; useSpecTranslation: If true, the translation
vector w.r.t. the CAD design will be used instead of the translation vector obtained through calibration.; sourceUnit: The desired
measurement unit in which to return the transformation matrix in. return: 4x4 homogeneous transformation matrix representing the
extrinsics from this transformation to the target transformation note: Both transformations must have a common toCameraSocket.
Otherwise extrinsics cannot be calculated.

#### std::array< std::array< float, 3 >, 3 > getRotationMatrixTo(const ImgTransformation & to)

Kind: function

Get the extrinsic rotation matrix from the source coordinate system of this transformation to the target coordinate system of the
to transformation. parameters: to: Transformation to get extrinsics to return: 3x3 rotation matrix representing the extrinsic
rotation from this transformation to the target transformation

#### std::array< float, 3 > getTranslationVectorTo(const ImgTransformation & to, bool useSpecTranslation, LengthUnit sourceUnit)

Kind: function

Get the extrinsic translation vector from the source coordinate system of this transformation to the target coordinate system of
the to transformation. parameters: to: Transformation to get extrinsics to return: 3x1 translation vector representing the
extrinsic translation from this transformation to the target transformation

#### bool isAlignedTo(const ImgTransformation & to)

Kind: function

Check if the transformations are aligned parameters: to: Transformation to compare with

#### bool isValid()

Kind: function

Check if the transformations are valid. The transformations are valid if the source frame size and the current frame size are set.

#### DEPTHAI_SERIALIZE(ImgTransformation, extrinsics, transformationMatrix, transformationMatrixInv, sourceIntrinsicMatrix,
sourceIntrinsicMatrixInv, distortionModel, distortionCoefficients, srcWidth, srcHeight, width, height, srcCrops)

Kind: function

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
