Skip to main content

FactorKind

Enum FactorKind 

Source
pub enum FactorKind {
    ReprojPointPinhole4 {
        pw: [f64; 3],
        uv: [f64; 2],
        w: f64,
    },
    ReprojPointPinhole4Dist5 {
        pw: [f64; 3],
        uv: [f64; 2],
        w: f64,
    },
    ReprojPointPinhole4Dist5Scheimpflug2 {
        pw: [f64; 3],
        uv: [f64; 2],
        w: f64,
    },
    ReprojPointPinhole4Dist5TwoSE3 {
        pw: [f64; 3],
        uv: [f64; 2],
        w: f64,
    },
    ReprojPointPinhole4Dist5HandEye {
        pw: [f64; 3],
        uv: [f64; 2],
        w: f64,
        base_to_gripper_se3: [f64; 7],
        mode: HandEyeMode,
    },
    ReprojPointPinhole4Dist5HandEyeRobotDelta {
        pw: [f64; 3],
        uv: [f64; 2],
        w: f64,
        base_to_gripper_se3: [f64; 7],
        mode: HandEyeMode,
    },
    LaserPlanePixel {
        laser_pixel: [f64; 2],
        w: f64,
    },
    LaserLineDist2D {
        laser_pixel: [f64; 2],
        w: f64,
    },
    Prior,
    Se3TangentPrior {
        sqrt_info: [f64; 6],
    },
    ReprojPointWithDistortion,
}
Expand description

Backend-agnostic factor kinds.

Each factor kind implies its parameter layout and residual dimension.

Variants§

§

ReprojPointPinhole4

Reprojection residual for a pinhole camera with 4 intrinsics and an SE3 pose.

Fields

§pw: [f64; 3]

World/target point coordinates.

§uv: [f64; 2]

Observed pixel coordinates.

§w: f64

Residual weight.

§

ReprojPointPinhole4Dist5

Reprojection residual with pinhole intrinsics, Brown-Conrady distortion, and SE3 pose.

Fields

§pw: [f64; 3]

World/target point coordinates.

§uv: [f64; 2]

Observed pixel coordinates.

§w: f64

Residual weight.

§

ReprojPointPinhole4Dist5Scheimpflug2

Reprojection with pinhole, distortion, Scheimpflug sensor, and SE3 pose.

Fields

§pw: [f64; 3]

World/target point coordinates.

§uv: [f64; 2]

Observed pixel coordinates.

§w: f64

Residual weight.

§

ReprojPointPinhole4Dist5TwoSE3

Reprojection with two composed SE3 transforms for rig extrinsics.

Parameters: [intrinsics, distortion, extr_camera_to_rig, pose_target_to_rig] Transform chain: P_camera = extr^-1 * pose * P_world

Fields

§pw: [f64; 3]

World/target point coordinates.

§uv: [f64; 2]

Observed pixel coordinates.

§w: f64

Residual weight.

§

ReprojPointPinhole4Dist5HandEye

Reprojection for hand-eye calibration with robot pose as measurement.

Parameters: [intrinsics, distortion, extr, handeye, target] Robot pose (base_se3_gripper, gripper in base frame) is stored in the factor as known data.

Fields

§pw: [f64; 3]

World/target point coordinates.

§uv: [f64; 2]

Observed pixel coordinates.

§w: f64

Residual weight.

§base_to_gripper_se3: [f64; 7]

Measured robot pose T_B_G packed as [qx,qy,qz,qw,tx,ty,tz].

§mode: HandEyeMode

Hand-eye mode defining transform chain.

§

ReprojPointPinhole4Dist5HandEyeRobotDelta

Reprojection for hand-eye calibration with per-view robot pose correction.

Parameters: [intrinsics, distortion, extr, handeye, target, robot_delta] Robot pose (base_se3_gripper) is stored in the factor as known data. robot_delta is a 6D se(3) tangent correction applied via exp(delta) * T_B_E.

Fields

§pw: [f64; 3]

World/target point coordinates.

§uv: [f64; 2]

Observed pixel coordinates.

§w: f64

Residual weight.

§base_to_gripper_se3: [f64; 7]

Measured robot pose T_B_G packed as [qx,qy,qz,qw,tx,ty,tz].

§mode: HandEyeMode

Hand-eye mode defining transform chain.

§

LaserPlanePixel

Laser line pixel constrained to lie on laser plane.

Parameters: [intrinsics, distortion, sensor, pose_cam_to_target, plane_normal, plane_distance] Residual: point-to-plane distance for ray-target intersection point. Note: Target is always planar (Z=0), so 3D point is computed as ray intersection.

Fields

§laser_pixel: [f64; 2]

Observed laser pixel coordinates.

§w: f64

Residual weight.

§

LaserLineDist2D

Laser line pixel constrained by line-distance in normalized plane.

Parameters: [intrinsics, distortion, sensor, pose_cam_to_target, plane_normal, plane_distance] Residual: perpendicular distance from normalized pixel to projected laser-target intersection line, scaled by sqrt(fx*fy). Note: Alternative to LaserPlanePixel using normalized plane geometry.

Fields

§laser_pixel: [f64; 2]

Observed laser pixel coordinates.

§w: f64

Residual weight.

§

Prior

Placeholder for future prior factors.

§

Se3TangentPrior

Zero-mean prior on a 6D se(3) tangent vector.

Parameters: [se3_delta] (6D Euclidean).

Fields

§sqrt_info: [f64; 6]

Diagonal square-root information for [rx, ry, rz, tx, ty, tz].

§

ReprojPointWithDistortion

Placeholder for future distortion-aware reprojection.

Implementations§

Source§

impl FactorKind

Source

pub fn residual_dim(&self) -> usize

Residual dimension implied by the factor.

Trait Implementations§

Source§

impl Clone for FactorKind

Source§

fn clone(&self) -> FactorKind

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for FactorKind

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl PartialEq for FactorKind

Source§

fn eq(&self, other: &FactorKind) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl StructuralPartialEq for FactorKind

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> ByRef<T> for T

Source§

fn by_ref(&self) -> &T

Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> DistributionExt for T
where T: ?Sized,

Source§

fn rand<T>(&self, rng: &mut (impl Rng + ?Sized)) -> T
where Self: Distribution<T>,

Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts self into a Left variant of Either<Self, Self> if into_left is true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts self into a Left variant of Either<Self, Self> if into_left(&self) returns true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
Source§

impl<T> Pointable for T

Source§

const ALIGN: usize

The alignment of pointer.
Source§

type Init = T

The type for initializers.
Source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
Source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
Source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
Source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

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

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,