Struct azure_kinect::calibration::Calibration [−][src]
pub struct Calibration<'a> { /* fields omitted */ }
Implementations
pub fn from_raw(
factory: &'a Factory,
raw_calibration: &Vec<u8>,
target_depth_mode: DepthMode,
target_color_resolution: ColorResolution
) -> Result<Calibration<'a>, Error>
Factory::calibration_get_from_raw
pub fn convert_3d_to_3d(
&self,
source_point3d: &Float3,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<Float3, Error>
pub fn convert_3d_to_3d(
&self,
source_point3d: &Float3,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<Float3, Error>
Transform a 3d point of a source coordinate system into a 3d point of the target coordinate system.
pub fn convert_2d_to_3d(
&self,
source_point2d: &Float2,
source_depth: f32,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<(Float3, bool), Error>
pub fn convert_2d_to_3d(
&self,
source_point2d: &Float2,
source_depth: f32,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<(Float3, bool), Error>
Transform a 2d pixel coordinate with an associated depth value of the source camera into a 3d point of the target coordinate system. Returns false if the point is invalid in the target coordinate system (and therefore target_point3d should not be used)
pub fn convert_3d_to_2d(
&self,
source_point3d: &Float3,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<(Float2, bool), Error>
pub fn convert_3d_to_2d(
&self,
source_point3d: &Float3,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<(Float2, bool), Error>
Transform a 3d point of a source coordinate system into a 2d pixel coordinate of the target camera. Returns false if the point is invalid in the target coordinate system (and therefore target_point2d should not be used)
pub fn convert_2d_to_2d(
&self,
source_point2d: &Float2,
source_depth: f32,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<(Float2, bool), Error>
pub fn convert_2d_to_2d(
&self,
source_point2d: &Float2,
source_depth: f32,
source_camera: CalibrationType,
target_camera: CalibrationType
) -> Result<(Float2, bool), Error>
Transform a 2d pixel coordinate with an associated depth value of the source camera into a 2d pixel coordinate of the target camera Returns false if the point is invalid in the target coordinate system (and therefore target_point2d should not be used)
Transform a 2D pixel coordinate from color camera into a 2D pixel coordinate of the depth camera. This function searches along an epipolar line in the depth image to find the corresponding depth pixel. Returns false if the point is invalid in the target coordinate system (and therefore target_point2d should not be used)