[−][src]Trait cv::CameraModel
Allows conversion between the point on an image and the internal projection which can describe the bearing of the projection out of the camera.
Associated Types
type Projection: Bearing
Required methods
fn calibrate<P>(&self, point: P) -> Self::Projection where
P: ImagePoint,
P: ImagePoint,
Extracts a projection from a pixel location in an image.
fn uncalibrate(&self, projection: Self::Projection) -> KeyPoint
Extracts the pixel location in the image from the projection.
Implementations on Foreign Types
impl CameraModel for CameraIntrinsics
[src]
type Projection = NormalizedKeyPoint
fn calibrate<P>(&self, point: P) -> NormalizedKeyPoint where
P: ImagePoint,
[src]
P: ImagePoint,
Takes in a point from an image in pixel coordinates and
converts it to a [NormalizedKeyPoint
].
let intrinsics = CameraIntrinsics { focals: Vector2::new(800.0, 900.0), principal_point: Point2::new(500.0, 600.0), skew: 1.7, }; let kp = KeyPoint(Point2::new(471.0, 322.0)); let nkp = intrinsics.calibrate(kp); let calibration_matrix = intrinsics.matrix(); let distance = (kp.to_homogeneous() - calibration_matrix * nkp.to_homogeneous()).norm(); assert!(distance < 0.1);
fn uncalibrate(&self, projection: NormalizedKeyPoint) -> KeyPoint
[src]
Converts a [NormalizedKeyPoint
] back into pixel coordinates.
let intrinsics = CameraIntrinsics { focals: Vector2::new(800.0, 900.0), principal_point: Point2::new(500.0, 600.0), skew: 1.7, }; let kp = KeyPoint(Point2::new(471.0, 322.0)); let nkp = intrinsics.calibrate(kp); let ukp = intrinsics.uncalibrate(nkp); assert!((kp.0 - ukp.0).norm() < 1e-6);
impl CameraModel for CameraIntrinsicsK1Distortion
[src]
type Projection = NormalizedKeyPoint
fn calibrate<P>(&self, point: P) -> NormalizedKeyPoint where
P: ImagePoint,
[src]
P: ImagePoint,
Takes in a point from an image in pixel coordinates and
converts it to a [NormalizedKeyPoint
].
let intrinsics = CameraIntrinsics { focals: Vector2::new(800.0, 900.0), principal_point: Point2::new(500.0, 600.0), skew: 1.7, }; let k1 = -0.164624; let intrinsics = CameraIntrinsicsK1Distortion::new( intrinsics, k1, ); let kp = KeyPoint(Point2::new(471.0, 322.0)); let nkp = intrinsics.calibrate(kp); let simple_nkp = intrinsics.simple_intrinsics.calibrate(kp); let distance = (nkp.0.coords - (simple_nkp.0.coords / (1.0 + k1 * simple_nkp.0.coords.norm_squared()))).norm(); assert!(distance < 0.1);
fn uncalibrate(&self, projection: NormalizedKeyPoint) -> KeyPoint
[src]
Converts a [NormalizedKeyPoint
] back into pixel coordinates.
let intrinsics = CameraIntrinsics { focals: Vector2::new(800.0, 900.0), principal_point: Point2::new(500.0, 600.0), skew: 1.7, }; let intrinsics = CameraIntrinsicsK1Distortion::new( intrinsics, -0.164624, ); let kp = KeyPoint(Point2::new(471.0, 322.0)); let nkp = intrinsics.calibrate(kp); let ukp = intrinsics.uncalibrate(nkp); assert!((kp.0 - ukp.0).norm() < 1e-6, "{:?}", (kp.0 - ukp.0).norm());