@Namespace(value="dai") @NoOffset @Properties(inherit=depthai.class) public class CalibrationHandler extends Pointer
Pointer.CustomDeallocator, Pointer.Deallocator, Pointer.NativeDeallocator, Pointer.ReferenceCounter| Constructor and Description |
|---|
CalibrationHandler() |
CalibrationHandler(EepromData eepromData)
Construct a new Calibration Handler object from EepromData object.
|
CalibrationHandler(long size)
Native array allocator.
|
CalibrationHandler(Path eepromDataPath)
Construct a new Calibration Handler object using the
eeprom json file created from calibration procedure.
|
CalibrationHandler(Path calibrationDataPath,
Path boardConfigPath)
Construct a new Calibration Handler object using the board
config json file and .calib binary files created using gen1 calibration.
|
CalibrationHandler(Pointer p)
Pointer cast constructor.
|
| Modifier and Type | Method and Description |
|---|---|
Pointer |
eepromToJson()
Get JSON representation of calibration data
|
boolean |
eepromToJsonFile(Path destPath)
Write raw calibration/board data to json file.
|
static CalibrationHandler |
fromJson(Pointer eepromDataJson)
Construct a new Calibration Handler object from JSON EepromData.
|
float |
getBaselineDistance() |
float |
getBaselineDistance(depthai.CameraBoardSocket cam1,
depthai.CameraBoardSocket cam2,
boolean useSpecTranslation)
Get the baseline distance between two specified cameras.
|
float |
getBaselineDistance(int cam1,
int cam2,
boolean useSpecTranslation) |
FloatVectorVector |
getCameraExtrinsics(depthai.CameraBoardSocket srcCamera,
depthai.CameraBoardSocket dstCamera) |
FloatVectorVector |
getCameraExtrinsics(depthai.CameraBoardSocket srcCamera,
depthai.CameraBoardSocket dstCamera,
boolean useSpecTranslation)
Get the Camera Extrinsics object between two cameras from the calibration data if there is a linked connection
between any two cameras then the relative rotation and translation (in centimeters) is returned by this function.
|
FloatVectorVector |
getCameraExtrinsics(int srcCamera,
int dstCamera) |
FloatVectorVector |
getCameraExtrinsics(int srcCamera,
int dstCamera,
boolean useSpecTranslation) |
FloatVectorVector |
getCameraIntrinsics(depthai.CameraBoardSocket cameraId) |
FloatVectorVector |
getCameraIntrinsics(depthai.CameraBoardSocket cameraId,
int resizeWidth,
int resizeHeight,
Point2f topLeftPixelId,
Point2f bottomRightPixelId,
boolean keepAspectRatio)
Get the Camera Intrinsics object
|
FloatVectorVector |
getCameraIntrinsics(depthai.CameraBoardSocket cameraId,
Pointer destShape) |
FloatVectorVector |
getCameraIntrinsics(depthai.CameraBoardSocket cameraId,
Pointer destShape,
Point2f topLeftPixelId,
Point2f bottomRightPixelId,
boolean keepAspectRatio)
Get the Camera Intrinsics object
|
FloatVectorVector |
getCameraIntrinsics(depthai.CameraBoardSocket cameraId,
Size2f destShape) |
FloatVectorVector |
getCameraIntrinsics(depthai.CameraBoardSocket cameraId,
Size2f destShape,
Point2f topLeftPixelId,
Point2f bottomRightPixelId,
boolean keepAspectRatio)
Get the Camera Intrinsics object
|
FloatVectorVector |
getCameraIntrinsics(int cameraId) |
FloatVectorVector |
getCameraIntrinsics(int cameraId,
int resizeWidth,
int resizeHeight,
Point2f topLeftPixelId,
Point2f bottomRightPixelId,
boolean keepAspectRatio) |
FloatVectorVector |
getCameraIntrinsics(int cameraId,
Pointer destShape) |
FloatVectorVector |
getCameraIntrinsics(int cameraId,
Pointer destShape,
Point2f topLeftPixelId,
Point2f bottomRightPixelId,
boolean keepAspectRatio) |
FloatVectorVector |
getCameraIntrinsics(int cameraId,
Size2f destShape) |
FloatVectorVector |
getCameraIntrinsics(int cameraId,
Size2f destShape,
Point2f topLeftPixelId,
Point2f bottomRightPixelId,
boolean keepAspectRatio) |
FloatVectorVector |
getCameraToImuExtrinsics(depthai.CameraBoardSocket cameraId) |
FloatVectorVector |
getCameraToImuExtrinsics(depthai.CameraBoardSocket cameraId,
boolean useSpecTranslation)
Get the Camera To Imu Extrinsics object
From the data loaded if there is a linked connection between IMU and the given camera then there relative rotation and translation from the camera to IMU
is returned.
|
FloatVectorVector |
getCameraToImuExtrinsics(int cameraId) |
FloatVectorVector |
getCameraToImuExtrinsics(int cameraId,
boolean useSpecTranslation) |
FloatPointer |
getCameraTranslationVector(depthai.CameraBoardSocket srcCamera,
depthai.CameraBoardSocket dstCamera) |
FloatPointer |
getCameraTranslationVector(depthai.CameraBoardSocket srcCamera,
depthai.CameraBoardSocket dstCamera,
boolean useSpecTranslation)
Get the Camera translation vector between two cameras from the calibration data.
|
FloatBuffer |
getCameraTranslationVector(int srcCamera,
int dstCamera) |
FloatBuffer |
getCameraTranslationVector(int srcCamera,
int dstCamera,
boolean useSpecTranslation) |
FloatVectorVectorIntIntTuple |
getDefaultIntrinsics(depthai.CameraBoardSocket cameraId)
Get the Default Intrinsics object
|
FloatVectorVectorIntIntTuple |
getDefaultIntrinsics(int cameraId) |
FloatPointer |
getDistortionCoefficients(depthai.CameraBoardSocket cameraId)
Get the Distortion Coefficients object
|
FloatBuffer |
getDistortionCoefficients(int cameraId) |
depthai.CameraModel |
getDistortionModel(depthai.CameraBoardSocket cameraId)
Get the distortion model of the given camera
|
byte |
getDistortionModel(int cameraId) |
EepromData |
getEepromData()
Get the Eeprom Data object
|
float |
getFov(depthai.CameraBoardSocket cameraId) |
float |
getFov(depthai.CameraBoardSocket cameraId,
boolean useSpec)
Get the Fov of the camera
|
float |
getFov(int cameraId) |
float |
getFov(int cameraId,
boolean useSpec) |
FloatVectorVector |
getImuToCameraExtrinsics(depthai.CameraBoardSocket cameraId) |
FloatVectorVector |
getImuToCameraExtrinsics(depthai.CameraBoardSocket cameraId,
boolean useSpecTranslation)
Get the Imu To Camera Extrinsics object from the data loaded if there is a linked connection
between IMU and the given camera then there relative rotation and translation from the IMU to Camera
is returned.
|
FloatVectorVector |
getImuToCameraExtrinsics(int cameraId) |
FloatVectorVector |
getImuToCameraExtrinsics(int cameraId,
boolean useSpecTranslation) |
byte |
getLensPosition(depthai.CameraBoardSocket cameraId)
Get the lens position of the given camera
|
byte |
getLensPosition(int cameraId) |
CalibrationHandler |
getPointer(long i) |
depthai.CameraBoardSocket |
getStereoLeftCameraId()
Get the camera id of the camera which is used as left camera of the stereo setup
|
FloatVectorVector |
getStereoLeftRectificationRotation()
Get the Stereo Left Rectification Rotation object
|
depthai.CameraBoardSocket |
getStereoRightCameraId()
Get the camera id of the camera which is used as right camera of the stereo setup
|
FloatVectorVector |
getStereoRightRectificationRotation()
Get the Stereo Right Rectification Rotation object
|
CalibrationHandler |
position(long position) |
void |
setBoardInfo(ByteBuffer boardName,
ByteBuffer boardRev) |
void |
setBoardInfo(ByteBuffer productName,
ByteBuffer boardName,
ByteBuffer boardRev,
ByteBuffer boardConf,
ByteBuffer hardwareConf,
ByteBuffer batchName,
long batchTime,
int boardOptions) |
void |
setBoardInfo(ByteBuffer productName,
ByteBuffer boardName,
ByteBuffer boardRev,
ByteBuffer boardConf,
ByteBuffer hardwareConf,
ByteBuffer batchName,
long batchTime,
int boardOptions,
ByteBuffer boardCustom) |
void |
setBoardInfo(BytePointer boardName,
BytePointer boardRev)
Set the Board Info object
|
void |
setBoardInfo(BytePointer productName,
BytePointer boardName,
BytePointer boardRev,
BytePointer boardConf,
BytePointer hardwareConf,
BytePointer batchName,
long batchTime,
int boardOptions) |
void |
setBoardInfo(BytePointer productName,
BytePointer boardName,
BytePointer boardRev,
BytePointer boardConf,
BytePointer hardwareConf,
BytePointer batchName,
long batchTime,
int boardOptions,
BytePointer boardCustom)
Set the Board Info object.
|
void |
setBoardInfo(String boardName,
String boardRev) |
void |
setBoardInfo(String productName,
String boardName,
String boardRev,
String boardConf,
String hardwareConf,
String batchName,
long batchTime,
int boardOptions) |
void |
setBoardInfo(String productName,
String boardName,
String boardRev,
String boardConf,
String hardwareConf,
String batchName,
long batchTime,
int boardOptions,
String boardCustom) |
void |
setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId,
depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
float[] translation) |
void |
setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId,
depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
float[] translation,
float[] specTranslation) |
void |
setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId,
depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation) |
void |
setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId,
depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation,
FloatBuffer specTranslation) |
void |
setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId,
depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation) |
void |
setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId,
depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation,
FloatPointer specTranslation)
Set the Camera Extrinsics object
|
void |
setCameraExtrinsics(int srcCameraId,
int destCameraId,
FloatVectorVector rotationMatrix,
float[] translation) |
void |
setCameraExtrinsics(int srcCameraId,
int destCameraId,
FloatVectorVector rotationMatrix,
float[] translation,
float[] specTranslation) |
void |
setCameraExtrinsics(int srcCameraId,
int destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation) |
void |
setCameraExtrinsics(int srcCameraId,
int destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation,
FloatBuffer specTranslation) |
void |
setCameraExtrinsics(int srcCameraId,
int destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation) |
void |
setCameraExtrinsics(int srcCameraId,
int destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation,
FloatPointer specTranslation) |
void |
setCameraIntrinsics(depthai.CameraBoardSocket cameraId,
FloatVectorVector intrinsics,
int width,
int height)
Set the Camera Intrinsics object
|
void |
setCameraIntrinsics(depthai.CameraBoardSocket cameraId,
FloatVectorVector intrinsics,
Pointer frameSize)
Set the Camera Intrinsics object
|
void |
setCameraIntrinsics(depthai.CameraBoardSocket cameraId,
FloatVectorVector intrinsics,
Size2f frameSize)
Set the Camera Intrinsics object
|
void |
setCameraIntrinsics(int cameraId,
FloatVectorVector intrinsics,
int width,
int height) |
void |
setCameraIntrinsics(int cameraId,
FloatVectorVector intrinsics,
Pointer frameSize) |
void |
setCameraIntrinsics(int cameraId,
FloatVectorVector intrinsics,
Size2f frameSize) |
void |
setCameraType(depthai.CameraBoardSocket cameraId,
depthai.CameraModel cameraModel)
Set the Camera Type object
|
void |
setCameraType(int cameraId,
byte cameraModel) |
void |
setDistortionCoefficients(depthai.CameraBoardSocket cameraId,
float[] distortionCoefficients) |
void |
setDistortionCoefficients(depthai.CameraBoardSocket cameraId,
FloatBuffer distortionCoefficients) |
void |
setDistortionCoefficients(depthai.CameraBoardSocket cameraId,
FloatPointer distortionCoefficients)
Sets the distortion Coefficients obtained from camera calibration
|
void |
setDistortionCoefficients(int cameraId,
float[] distortionCoefficients) |
void |
setDistortionCoefficients(int cameraId,
FloatBuffer distortionCoefficients) |
void |
setDistortionCoefficients(int cameraId,
FloatPointer distortionCoefficients) |
void |
setFov(depthai.CameraBoardSocket cameraId,
float hfov)
Set the Fov of the Camera
|
void |
setFov(int cameraId,
float hfov) |
void |
setImuExtrinsics(depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
float[] translation) |
void |
setImuExtrinsics(depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
float[] translation,
float[] specTranslation) |
void |
setImuExtrinsics(depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation) |
void |
setImuExtrinsics(depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation,
FloatBuffer specTranslation) |
void |
setImuExtrinsics(depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation) |
void |
setImuExtrinsics(depthai.CameraBoardSocket destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation,
FloatPointer specTranslation)
Set the Imu to Camera Extrinsics object
|
void |
setImuExtrinsics(int destCameraId,
FloatVectorVector rotationMatrix,
float[] translation) |
void |
setImuExtrinsics(int destCameraId,
FloatVectorVector rotationMatrix,
float[] translation,
float[] specTranslation) |
void |
setImuExtrinsics(int destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation) |
void |
setImuExtrinsics(int destCameraId,
FloatVectorVector rotationMatrix,
FloatBuffer translation,
FloatBuffer specTranslation) |
void |
setImuExtrinsics(int destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation) |
void |
setImuExtrinsics(int destCameraId,
FloatVectorVector rotationMatrix,
FloatPointer translation,
FloatPointer specTranslation) |
void |
setLensPosition(depthai.CameraBoardSocket cameraId,
byte lensPosition)
Sets the distortion Coefficients obtained from camera calibration
|
void |
setLensPosition(int cameraId,
byte lensPosition) |
void |
setProductName(ByteBuffer productName) |
void |
setProductName(BytePointer productName)
Set the productName which acts as alisas for users to identify the device
|
void |
setProductName(String productName) |
void |
setStereoLeft(depthai.CameraBoardSocket cameraId,
FloatVectorVector rectifiedRotation)
Set the Stereo Left Rectification object
|
void |
setStereoLeft(int cameraId,
FloatVectorVector rectifiedRotation) |
void |
setStereoRight(depthai.CameraBoardSocket cameraId,
FloatVectorVector rectifiedRotation)
Set the Stereo Right Rectification object
|
void |
setStereoRight(int cameraId,
FloatVectorVector rectifiedRotation) |
boolean |
validateCameraArray()
Using left camera as the head it iterates over the camera extrinsics connection
to check if all the camera extrinsics are connected and no loop exists.
|
address, asBuffer, asByteBuffer, availablePhysicalBytes, calloc, capacity, capacity, close, deallocate, deallocate, deallocateReferences, deallocator, deallocator, equals, fill, formatBytes, free, getDirectBufferAddress, getPointer, getPointer, getPointer, hashCode, interruptDeallocatorThread, isNull, isNull, limit, limit, malloc, maxBytes, maxPhysicalBytes, memchr, memcmp, memcpy, memmove, memset, offsetAddress, offsetof, offsetof, parseBytes, physicalBytes, physicalBytesInaccurate, position, put, realloc, referenceCount, releaseReference, retainReference, setNull, sizeof, sizeof, toString, totalBytes, totalCount, totalPhysicalBytes, withDeallocator, zeropublic CalibrationHandler(Pointer p)
Pointer(Pointer).public CalibrationHandler(long size)
Pointer.position(long).public CalibrationHandler()
public CalibrationHandler(@ByVal Path eepromDataPath)
eepromDataPath - takes the full path to the json file containing the calibration and device info.public CalibrationHandler(@ByVal Path calibrationDataPath, @ByVal Path boardConfigPath)
calibrationDataPath - Full Path to the .calib binary file from the gen1 calibration. (Supports only Version 5)boardConfigPath - Full Path to the board config json file containing device information.public CalibrationHandler(@ByVal EepromData eepromData)
eepromData - EepromData data structure containing the calibration data.public CalibrationHandler position(long position)
public CalibrationHandler getPointer(long i)
getPointer in class Pointer@ByVal public static CalibrationHandler fromJson(@ByVal @Cast(value="nlohmann::json*") Pointer eepromDataJson)
eepromDataJson - EepromData as JSON@ByVal public EepromData getEepromData()
@ByVal public FloatVectorVector getCameraIntrinsics(depthai.CameraBoardSocket cameraId, int resizeWidth, int resizeHeight, @ByVal(nullValue="dai::Point2f()") Point2f topLeftPixelId, @ByVal(nullValue="dai::Point2f()") Point2f bottomRightPixelId, @Cast(value="bool") boolean keepAspectRatio)
cameraId - Uses the cameraId to identify which camera intrinsics to returnresizewidth - resized width of the image for which intrinsics is requested. resizewidth = -1 represents width is same as default intrinsicsresizeHeight - resized height of the image for which intrinsics is requested. resizeHeight = -1 represents height is same as default intrinsicstopLeftPixelId - (x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the
respective cropped imagebottomRightPixelId - (x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for
the respective cropped imagekeepAspectRatio - Enabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the
other side \[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVector getCameraIntrinsics(depthai.CameraBoardSocket cameraId)
@ByVal public FloatVectorVector getCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, int resizeWidth, int resizeHeight, @ByVal(nullValue="dai::Point2f()") Point2f topLeftPixelId, @ByVal(nullValue="dai::Point2f()") Point2f bottomRightPixelId, @Cast(value="bool") boolean keepAspectRatio)
@ByVal public FloatVectorVector getCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId)
@ByVal public FloatVectorVector getCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal Size2f destShape, @ByVal(nullValue="dai::Point2f()") Point2f topLeftPixelId, @ByVal(nullValue="dai::Point2f()") Point2f bottomRightPixelId, @Cast(value="bool") boolean keepAspectRatio)
cameraId - Uses the cameraId to identify which camera intrinsics to returndestShape - resized width and height of the image for which intrinsics is requested.topLeftPixelId - (x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the
respective cropped imagebottomRightPixelId - (x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for
the respective cropped imagekeepAspectRatio - Enabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the
other side \[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVector getCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal Size2f destShape)
@ByVal public FloatVectorVector getCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal Size2f destShape, @ByVal(nullValue="dai::Point2f()") Point2f topLeftPixelId, @ByVal(nullValue="dai::Point2f()") Point2f bottomRightPixelId, @Cast(value="bool") boolean keepAspectRatio)
@ByVal public FloatVectorVector getCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal Size2f destShape)
@ByVal public FloatVectorVector getCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal @Cast(value="std::tuple<int,int>*") Pointer destShape, @ByVal(nullValue="dai::Point2f()") Point2f topLeftPixelId, @ByVal(nullValue="dai::Point2f()") Point2f bottomRightPixelId, @Cast(value="bool") boolean keepAspectRatio)
cameraId - Uses the cameraId to identify which camera intrinsics to returndestShape - resized width and height of the image for which intrinsics is requested.topLeftPixelId - (x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the
respective cropped imagebottomRightPixelId - (x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for
the respective cropped imagekeepAspectRatio - Enabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the
other side \[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVector getCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal @Cast(value="std::tuple<int,int>*") Pointer destShape)
@ByVal public FloatVectorVector getCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal @Cast(value="std::tuple<int,int>*") Pointer destShape, @ByVal(nullValue="dai::Point2f()") Point2f topLeftPixelId, @ByVal(nullValue="dai::Point2f()") Point2f bottomRightPixelId, @Cast(value="bool") boolean keepAspectRatio)
@ByVal public FloatVectorVector getCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal @Cast(value="std::tuple<int,int>*") Pointer destShape)
@ByVal public FloatVectorVectorIntIntTuple getDefaultIntrinsics(depthai.CameraBoardSocket cameraId)
cameraId - Uses the cameraId to identify which camera intrinsics to return \[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVectorIntIntTuple getDefaultIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId)
@StdVector public FloatPointer getDistortionCoefficients(depthai.CameraBoardSocket cameraId)
cameraId - Uses the cameraId to identify which distortion Coefficients to return.@StdVector public FloatBuffer getDistortionCoefficients(@Cast(value="dai::CameraBoardSocket") int cameraId)
public float getFov(depthai.CameraBoardSocket cameraId, @Cast(value="bool") boolean useSpec)
cameraId - of the camera of which we are fetching fov.useSpec - Disabling this bool will calculate the fov based on intrinsics (focal length, image width), instead of getting it from the camera specspublic float getFov(depthai.CameraBoardSocket cameraId)
public float getFov(@Cast(value="dai::CameraBoardSocket") int cameraId, @Cast(value="bool") boolean useSpec)
@Cast(value="uint8_t") public byte getLensPosition(depthai.CameraBoardSocket cameraId)
cameraId - of the camera with lens position is requested.@Cast(value="uint8_t") public byte getLensPosition(@Cast(value="dai::CameraBoardSocket") int cameraId)
public depthai.CameraModel getDistortionModel(depthai.CameraBoardSocket cameraId)
cameraId - of the camera with lens position is requested.@Cast(value="dai::CameraModel") public byte getDistortionModel(@Cast(value="dai::CameraBoardSocket") int cameraId)
@ByVal public FloatVectorVector getCameraExtrinsics(depthai.CameraBoardSocket srcCamera, depthai.CameraBoardSocket dstCamera, @Cast(value="bool") boolean useSpecTranslation)
srcCamera - Camera Id of the camera which will be considered as origin.dstCamera - Camera Id of the destination camera to which we are fetching the rotation and translation from the SrcCamerauseSpecTranslation - Enabling this bool uses the translation information from the board design data \[ \text{Transformation Matrix} = \left [ \begin{matrix}
r_{00} & r_{01} & r_{02} & T_x \\
r_{10} & r_{11} & r_{12} & T_y \\
r_{20} & r_{21} & r_{22} & T_z \\
0 & 0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVector getCameraExtrinsics(depthai.CameraBoardSocket srcCamera, depthai.CameraBoardSocket dstCamera)
@ByVal public FloatVectorVector getCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCamera, @Cast(value="dai::CameraBoardSocket") int dstCamera, @Cast(value="bool") boolean useSpecTranslation)
@ByVal public FloatVectorVector getCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCamera, @Cast(value="dai::CameraBoardSocket") int dstCamera)
@StdVector public FloatPointer getCameraTranslationVector(depthai.CameraBoardSocket srcCamera, depthai.CameraBoardSocket dstCamera, @Cast(value="bool") boolean useSpecTranslation)
srcCamera - Camera Id of the camera which will be considered as origin.dstCamera - Camera Id of the destination camera to which we are fetching the translation vector from the SrcCamerauseSpecTranslation - Disabling this bool uses the translation information from the calibration data (not the board design data)@StdVector public FloatPointer getCameraTranslationVector(depthai.CameraBoardSocket srcCamera, depthai.CameraBoardSocket dstCamera)
@StdVector public FloatBuffer getCameraTranslationVector(@Cast(value="dai::CameraBoardSocket") int srcCamera, @Cast(value="dai::CameraBoardSocket") int dstCamera, @Cast(value="bool") boolean useSpecTranslation)
@StdVector public FloatBuffer getCameraTranslationVector(@Cast(value="dai::CameraBoardSocket") int srcCamera, @Cast(value="dai::CameraBoardSocket") int dstCamera)
public float getBaselineDistance(depthai.CameraBoardSocket cam1, depthai.CameraBoardSocket cam2, @Cast(value="bool") boolean useSpecTranslation)
cam1 - First cameracam2 - Second camerauseSpecTranslation - Enabling this bool uses the translation information from the board design data (not the calibration data)public float getBaselineDistance()
public float getBaselineDistance(@Cast(value="dai::CameraBoardSocket") int cam1, @Cast(value="dai::CameraBoardSocket") int cam2, @Cast(value="bool") boolean useSpecTranslation)
@ByVal public FloatVectorVector getCameraToImuExtrinsics(depthai.CameraBoardSocket cameraId, @Cast(value="bool") boolean useSpecTranslation)
cameraId - Camera Id of the camera which will be considered as origin. from which Transformation matrix to the IMU will be founduseSpecTranslation - Enabling this bool uses the translation information from the board design data \[ \text{Transformation Matrix} = \left [ \begin{matrix}
r_{00} & r_{01} & r_{02} & T_x \\
r_{10} & r_{11} & r_{12} & T_y \\
r_{20} & r_{21} & r_{22} & T_z \\
0 & 0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVector getCameraToImuExtrinsics(depthai.CameraBoardSocket cameraId)
@ByVal public FloatVectorVector getCameraToImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @Cast(value="bool") boolean useSpecTranslation)
@ByVal public FloatVectorVector getCameraToImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId)
@ByVal public FloatVectorVector getImuToCameraExtrinsics(depthai.CameraBoardSocket cameraId, @Cast(value="bool") boolean useSpecTranslation)
cameraId - Camera Id of the camera which will be considered as destination. To which Transformation matrix from the IMU will be found.useSpecTranslation - Enabling this bool uses the translation information from the board design data \[ \text{Transformation Matrix} = \left [ \begin{matrix}
r_{00} & r_{01} & r_{02} & T_x \\
r_{10} & r_{11} & r_{12} & T_y \\
r_{20} & r_{21} & r_{22} & T_z \\
0 & 0 & 0 & 1
\end{matrix} \right ] \]@ByVal public FloatVectorVector getImuToCameraExtrinsics(depthai.CameraBoardSocket cameraId)
@ByVal public FloatVectorVector getImuToCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @Cast(value="bool") boolean useSpecTranslation)
@ByVal public FloatVectorVector getImuToCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId)
@ByVal public FloatVectorVector getStereoRightRectificationRotation()
@ByVal public FloatVectorVector getStereoLeftRectificationRotation()
public depthai.CameraBoardSocket getStereoLeftCameraId()
public depthai.CameraBoardSocket getStereoRightCameraId()
@Cast(value="bool") public boolean eepromToJsonFile(@ByVal Path destPath)
destPath - Full path to the json file in which raw calibration data will be stored@ByVal @Cast(value="nlohmann::json*") public Pointer eepromToJson()
public void setBoardInfo(@StdString BytePointer boardName, @StdString BytePointer boardRev)
version - Sets the version of the Calibration data(Current version is 6)boardName - Sets your board name.boardRev - set your board revision id.public void setBoardInfo(@StdString ByteBuffer boardName, @StdString ByteBuffer boardRev)
public void setBoardInfo(@StdString String boardName, @StdString String boardRev)
public void setBoardInfo(@StdString BytePointer productName, @StdString BytePointer boardName, @StdString BytePointer boardRev, @StdString BytePointer boardConf, @StdString BytePointer hardwareConf, @StdString BytePointer batchName, @Cast(value="uint64_t") long batchTime, @Cast(value="uint32_t") int boardOptions, @StdString BytePointer boardCustom)
productName - Sets product name (alias).boardName - Sets board name.boardRev - Sets board revision id.boardConf - Sets board configuration id.hardwareConf - Sets hardware configuration id.batchName - Sets batch name.batchTime - Sets batch time (unix timestamp).boardCustom - Sets a custom board (Default empty string).public void setBoardInfo(@StdString BytePointer productName, @StdString BytePointer boardName, @StdString BytePointer boardRev, @StdString BytePointer boardConf, @StdString BytePointer hardwareConf, @StdString BytePointer batchName, @Cast(value="uint64_t") long batchTime, @Cast(value="uint32_t") int boardOptions)
public void setBoardInfo(@StdString ByteBuffer productName, @StdString ByteBuffer boardName, @StdString ByteBuffer boardRev, @StdString ByteBuffer boardConf, @StdString ByteBuffer hardwareConf, @StdString ByteBuffer batchName, @Cast(value="uint64_t") long batchTime, @Cast(value="uint32_t") int boardOptions, @StdString ByteBuffer boardCustom)
public void setBoardInfo(@StdString ByteBuffer productName, @StdString ByteBuffer boardName, @StdString ByteBuffer boardRev, @StdString ByteBuffer boardConf, @StdString ByteBuffer hardwareConf, @StdString ByteBuffer batchName, @Cast(value="uint64_t") long batchTime, @Cast(value="uint32_t") int boardOptions)
public void setBoardInfo(@StdString String productName, @StdString String boardName, @StdString String boardRev, @StdString String boardConf, @StdString String hardwareConf, @StdString String batchName, @Cast(value="uint64_t") long batchTime, @Cast(value="uint32_t") int boardOptions, @StdString String boardCustom)
public void setBoardInfo(@StdString String productName, @StdString String boardName, @StdString String boardRev, @StdString String boardConf, @StdString String hardwareConf, @StdString String batchName, @Cast(value="uint64_t") long batchTime, @Cast(value="uint32_t") int boardOptions)
public void setProductName(@StdString BytePointer productName)
productName - Sets product name (alias).public void setProductName(@StdString ByteBuffer productName)
public void setProductName(@StdString String productName)
public void setCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal FloatVectorVector intrinsics, @ByVal Size2f frameSize)
cameraId - CameraId of the camera for which Camera intrinsics are being loadedintrinsics - 3x3 intrinsics matrixframeSize - Represents the width and height of the image at which intrinsics are calculated.
Matrix representation of intrinsic matrix
\[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]public void setCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal FloatVectorVector intrinsics, @ByVal Size2f frameSize)
public void setCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal FloatVectorVector intrinsics, int width, int height)
cameraId - CameraId of the camera for which Camera intrinsics are being loadedintrinsics - 3x3 intrinsics matrixwidth - Represents the width of the image at which intrinsics are calculated.height - Represents the height of the image at which intrinsics are calculated.
Matrix representation of intrinsic matrix
\[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]public void setCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal FloatVectorVector intrinsics, int width, int height)
public void setCameraIntrinsics(depthai.CameraBoardSocket cameraId, @ByVal FloatVectorVector intrinsics, @ByVal @Cast(value="std::tuple<int,int>*") Pointer frameSize)
cameraId - CameraId of the camera for which Camera intrinsics are being loadedintrinsics - 3x3 intrinsics matrixframeSize - Represents the width and height of the image at which intrinsics are calculated.
Matrix representation of intrinsic matrix
\[ \text{Intrinsic Matrix} = \left [ \begin{matrix}
f_x & 0 & c_x \\
0 & f_y & c_y \\
0 & 0 & 1
\end{matrix} \right ] \]public void setCameraIntrinsics(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal FloatVectorVector intrinsics, @ByVal @Cast(value="std::tuple<int,int>*") Pointer frameSize)
public void setDistortionCoefficients(depthai.CameraBoardSocket cameraId, @StdVector FloatPointer distortionCoefficients)
cameraId - Camera Id of the camera for which distortion coefficients are computeddistortionCoefficients - Distortion Coefficients of the respective Camera.public void setDistortionCoefficients(@Cast(value="dai::CameraBoardSocket") int cameraId, @StdVector FloatBuffer distortionCoefficients)
public void setDistortionCoefficients(depthai.CameraBoardSocket cameraId, @StdVector float[] distortionCoefficients)
public void setDistortionCoefficients(@Cast(value="dai::CameraBoardSocket") int cameraId, @StdVector FloatPointer distortionCoefficients)
public void setDistortionCoefficients(depthai.CameraBoardSocket cameraId, @StdVector FloatBuffer distortionCoefficients)
public void setDistortionCoefficients(@Cast(value="dai::CameraBoardSocket") int cameraId, @StdVector float[] distortionCoefficients)
public void setFov(depthai.CameraBoardSocket cameraId, float hfov)
cameraId - Camera Id of the camerahfov - Horizontal fov of the camera from Camera Datasheetpublic void setLensPosition(depthai.CameraBoardSocket cameraId, @Cast(value="uint8_t") byte lensPosition)
cameraId - Camera Id of the cameralensPosition - lens posiotion value of the camera at the time of calibrationpublic void setLensPosition(@Cast(value="dai::CameraBoardSocket") int cameraId, @Cast(value="uint8_t") byte lensPosition)
public void setCameraType(depthai.CameraBoardSocket cameraId, depthai.CameraModel cameraModel)
cameraId - CameraId of the camera for which cameraModel Type is being updated.cameraModel - Type of the model the camera representspublic void setCameraType(@Cast(value="dai::CameraBoardSocket") int cameraId, @Cast(value="dai::CameraModel") byte cameraModel)
public void setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId, depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation, @StdVector FloatPointer specTranslation)
srcCameraId - Camera Id of the camera which will be considered as relative origin.destCameraId - Camera Id of the camera which will be considered as destination from srcCameraId.rotationMatrix - Rotation between srcCameraId and destCameraId origins.translation - Translation between srcCameraId and destCameraId origins.specTranslation - Translation between srcCameraId and destCameraId origins from the design.public void setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId, depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation)
public void setCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCameraId, @Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation, @StdVector FloatBuffer specTranslation)
public void setCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCameraId, @Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation)
public void setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId, depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation, @StdVector float[] specTranslation)
public void setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId, depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation)
public void setCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCameraId, @Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation, @StdVector FloatPointer specTranslation)
public void setCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCameraId, @Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation)
public void setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId, depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation, @StdVector FloatBuffer specTranslation)
public void setCameraExtrinsics(depthai.CameraBoardSocket srcCameraId, depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation)
public void setCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCameraId, @Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation, @StdVector float[] specTranslation)
public void setCameraExtrinsics(@Cast(value="dai::CameraBoardSocket") int srcCameraId, @Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation)
public void setImuExtrinsics(depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation, @StdVector FloatPointer specTranslation)
destCameraId - Camera Id of the camera which will be considered as destination from IMU.rotationMatrix - Rotation between srcCameraId and destCameraId origins.translation - Translation between IMU and destCameraId origins.specTranslation - Translation between IMU and destCameraId origins from the design.public void setImuExtrinsics(depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation)
public void setImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation, @StdVector FloatBuffer specTranslation)
public void setImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation)
public void setImuExtrinsics(depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation, @StdVector float[] specTranslation)
public void setImuExtrinsics(depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation)
public void setImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation, @StdVector FloatPointer specTranslation)
public void setImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatPointer translation)
public void setImuExtrinsics(depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation, @StdVector FloatBuffer specTranslation)
public void setImuExtrinsics(depthai.CameraBoardSocket destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector FloatBuffer translation)
public void setImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation, @StdVector float[] specTranslation)
public void setImuExtrinsics(@Cast(value="dai::CameraBoardSocket") int destCameraId, @ByVal FloatVectorVector rotationMatrix, @StdVector float[] translation)
public void setStereoLeft(depthai.CameraBoardSocket cameraId, @ByVal FloatVectorVector rectifiedRotation)
cameraId - CameraId of the camera which will be used as left Camera of stereo SetuprectifiedRotation - Rectification rotation of the left camera required for feature matching
Homography of the Left Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_left)public void setStereoLeft(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal FloatVectorVector rectifiedRotation)
public void setStereoRight(depthai.CameraBoardSocket cameraId, @ByVal FloatVectorVector rectifiedRotation)
cameraId - CameraId of the camera which will be used as left Camera of stereo SetuprectifiedRotation - Rectification rotation of the left camera required for feature matching
Homography of the Right Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_right)public void setStereoRight(@Cast(value="dai::CameraBoardSocket") int cameraId, @ByVal FloatVectorVector rectifiedRotation)
Copyright © 2023. All rights reserved.