[][src]Struct azure_kinect::calibration::Calibration

pub struct Calibration<'a> { /* fields omitted */ }

Implementations

impl<'_> Calibration<'_>[src]

pub fn from_raw<'a>(
    factory: &'a Factory,
    raw_calibration: &Vec<u8>,
    target_depth_mode: k4a_depth_mode_t,
    target_color_resolution: k4a_color_resolution_t
) -> Result<Calibration<'a>, Error>
[src]

pub fn convert_3d_to_3d(
    &self,
    source_point3d: &k4a_float3_t,
    source_camera: k4a_calibration_type_t,
    target_camera: k4a_calibration_type_t
) -> Result<k4a_float3_t, Error>
[src]

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: &k4a_float2_t,
    source_depth: f32,
    source_camera: k4a_calibration_type_t,
    target_camera: k4a_calibration_type_t
) -> Result<(k4a_float3_t, bool), Error>
[src]

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: &k4a_float3_t,
    source_camera: k4a_calibration_type_t,
    target_camera: k4a_calibration_type_t
) -> Result<(k4a_float2_t, bool), Error>
[src]

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: &k4a_float2_t,
    source_depth: f32,
    source_camera: k4a_calibration_type_t,
    target_camera: k4a_calibration_type_t
) -> Result<(k4a_float2_t, bool), Error>
[src]

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)

pub fn convert_color_2d_to_depth_2d(
    &self,
    source_point2d: &k4a_float2_t,
    depth_image: &Image
) -> Result<(k4a_float2_t, bool), Error>
[src]

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)

Auto Trait Implementations

impl<'a> !RefUnwindSafe for Calibration<'a>

impl<'a> !Send for Calibration<'a>

impl<'a> !Sync for Calibration<'a>

impl<'a> Unpin for Calibration<'a>

impl<'a> !UnwindSafe for Calibration<'a>

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.