Struct opencv_ros_camera::RosOpenCvIntrinsics [−][src]
pub struct RosOpenCvIntrinsics<R: RealField> {
pub is_opencv_compatible: bool,
pub p: SMatrix<R, 3, 4>,
pub k: SMatrix<R, 3, 3>,
pub distortion: Distortion<R>,
pub rect: SMatrix<R, 3, 3>,
// some fields omitted
}Expand description
A perspective camera model with distortion compatible with OpenCV and ROS.
This camera model is compatible with OpenCV and ROS, including stereo
rectification and Brown-Conrady
distortion. To load
from a ROS YAML file, see the from_ros_yaml
function.
See this page for an expanded definition of the parameters.
To convert from a
NamedIntrinsicParameters struct,
use its
intrinsics
field.
Fields
is_opencv_compatible: boolIf these intrinsics have zero skew, they are “opencv compatible” and this is true.
p: SMatrix<R, 3, 4>The intrinsic parameter matrix P.
k: SMatrix<R, 3, 3>The intrinsic parameter matrix K. Scaled from P.
distortion: Distortion<R>The non-linear distortion parameters D specifying image warping.
rect: SMatrix<R, 3, 3>The stereo rectification matrix.
Implementations
pub fn from_components(
p: SMatrix<R, 3, 4>,
k: SMatrix<R, 3, 3>,
distortion: Distortion<R>,
rect: SMatrix<R, 3, 3>
) -> Result<Self>
pub fn from_components(
p: SMatrix<R, 3, 4>,
k: SMatrix<R, 3, 3>,
distortion: Distortion<R>,
rect: SMatrix<R, 3, 3>
) -> Result<Self>
Construct intrinsics from raw components.
Returns Err(Error::InvalidInput) if rect cannot be inverted.
Construct intrinsics from individual parameters with no distortion.
fx and fy are the horizontal and vertical focal lengths. skew is
the pixel skew (typically near zero). cx and cy is the center of the
optical axis in pixel coordinates.
pub fn from_params_with_distortion(
fx: R,
skew: R,
fy: R,
cx: R,
cy: R,
distortion: Distortion<R>
) -> Self
pub fn from_params_with_distortion(
fx: R,
skew: R,
fy: R,
cx: R,
cy: R,
distortion: Distortion<R>
) -> Self
Construct intrinsics from individual parameters.
fx and fy are the horizontal and vertical focal lengths. skew is
the pixel skew (typically near zero). cx and cy is the center of the
optical axis in pixel coordinates. distortion is a vector of the
distortion terms.
Convert undistorted pixel coordinates to distorted pixel coordinates.
This will take coordinates from, e.g. a linear camera model, warp them into their distorted counterparts. This distortion thus models the action of a real lens.
Convert distorted pixel coordinates to undistorted pixel coordinates.
This will take distorted coordinates from, e.g. detections from a real camera image, and undo the effect of the distortion model. This “undistortion” thus converts coordinates from a real lens into coordinates that can be used with a linear camera model.
This method calls undistort_ext using the default termination criteria.
pub fn undistort_ext<NPTS, IN>(
&self,
distorted: &Pixels<R, NPTS, IN>,
criteria: impl Into<Option<TermCriteria>>
) -> UndistortedPixels<R, NPTS, Owned<R, NPTS, U2>> where
NPTS: Dim,
IN: Storage<R, NPTS, U2>,
DefaultAllocator: Allocator<R, NPTS, U2>,
pub fn undistort_ext<NPTS, IN>(
&self,
distorted: &Pixels<R, NPTS, IN>,
criteria: impl Into<Option<TermCriteria>>
) -> UndistortedPixels<R, NPTS, Owned<R, NPTS, U2>> where
NPTS: Dim,
IN: Storage<R, NPTS, U2>,
DefaultAllocator: Allocator<R, NPTS, U2>,
Convert distorted pixel coordinates to undistorted pixel coordinates.
This will take distorted coordinates from, e.g. detections from a real camera image, and undo the effect of the distortion model. This “undistortion” thus converts coordinates from a real lens into coordinates that can be used with a linear camera model.
If the termination criteria are not specified, the default of five iterations is used.
pub fn camera_to_undistorted_pixel<IN, NPTS>(
&self,
camera: &Points<CameraFrame, R, NPTS, IN>
) -> UndistortedPixels<R, NPTS, Owned<R, NPTS, U2>> where
IN: Storage<R, NPTS, U3>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U2>,
DefaultAllocator: Allocator<R, U1, U2>,
pub fn camera_to_undistorted_pixel<IN, NPTS>(
&self,
camera: &Points<CameraFrame, R, NPTS, IN>
) -> UndistortedPixels<R, NPTS, Owned<R, NPTS, U2>> where
IN: Storage<R, NPTS, U3>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U2>,
DefaultAllocator: Allocator<R, U1, U2>,
Convert 3D coordinates in CameraFrame to undistorted pixel coords.
pub fn undistorted_pixel_to_camera<IN, NPTS>(
&self,
undistorteds: &UndistortedPixels<R, NPTS, IN>
) -> RayBundle<CameraFrame, SharedOriginRayBundle<R>, R, NPTS, Owned<R, NPTS, U3>> where
IN: Storage<R, NPTS, U2>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U3>,
DefaultAllocator: Allocator<R, U1, U2>,
pub fn undistorted_pixel_to_camera<IN, NPTS>(
&self,
undistorteds: &UndistortedPixels<R, NPTS, IN>
) -> RayBundle<CameraFrame, SharedOriginRayBundle<R>, R, NPTS, Owned<R, NPTS, U3>> where
IN: Storage<R, NPTS, U2>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U3>,
DefaultAllocator: Allocator<R, U1, U2>,
Convert undistorted pixel coordinates to 3D coords in the CameraFrame.
Trait Implementations
Deserialize this value from the given Serde deserializer. Read more
Performs the conversion.
type BundleType = SharedOriginRayBundle<R>
type BundleType = SharedOriginRayBundle<R>
What type of ray bundle is returned when projecting pixels to rays.
fn pixel_to_camera<IN, NPTS>(
&self,
pixels: &Pixels<R, NPTS, IN>
) -> RayBundle<CameraFrame, Self::BundleType, R, NPTS, Owned<R, NPTS, U3>> where
Self::BundleType: Bundle<R>,
IN: Storage<R, NPTS, U2>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U2>,
DefaultAllocator: Allocator<R, NPTS, U3>,
DefaultAllocator: Allocator<R, U1, U2>,
fn pixel_to_camera<IN, NPTS>(
&self,
pixels: &Pixels<R, NPTS, IN>
) -> RayBundle<CameraFrame, Self::BundleType, R, NPTS, Owned<R, NPTS, U3>> where
Self::BundleType: Bundle<R>,
IN: Storage<R, NPTS, U2>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U2>,
DefaultAllocator: Allocator<R, NPTS, U3>,
DefaultAllocator: Allocator<R, U1, U2>,
project pixels to camera coords
fn camera_to_pixel<IN, NPTS>(
&self,
camera: &Points<CameraFrame, R, NPTS, IN>
) -> Pixels<R, NPTS, Owned<R, NPTS, U2>> where
IN: Storage<R, NPTS, U3>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U2>,
fn camera_to_pixel<IN, NPTS>(
&self,
camera: &Points<CameraFrame, R, NPTS, IN>
) -> Pixels<R, NPTS, Owned<R, NPTS, U2>> where
IN: Storage<R, NPTS, U3>,
NPTS: Dim,
DefaultAllocator: Allocator<R, NPTS, U2>,
project camera coords to pixel coordinates
This method tests for self and other values to be equal, and is used
by ==. Read more
This method tests for !=.
Auto Trait Implementations
impl<R> RefUnwindSafe for RosOpenCvIntrinsics<R> where
R: RefUnwindSafe,
impl<R> Send for RosOpenCvIntrinsics<R>
impl<R> Sync for RosOpenCvIntrinsics<R>
impl<R> Unpin for RosOpenCvIntrinsics<R> where
R: Unpin,
impl<R> UnwindSafe for RosOpenCvIntrinsics<R> where
R: UnwindSafe,
Blanket Implementations
Mutably borrows from an owned value. Read more
type Output = T
type Output = T
Should always be Self
The inverse inclusion map: attempts to construct self from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self is actually part of its subset T (and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub fn from_subset(element: &SS) -> SP
The inclusion map: converts self to the equivalent element of its superset.