Skip to main content

RigHandeyeProblem

Struct RigHandeyeProblem 

Source
pub struct RigHandeyeProblem;
Expand description

Multi-camera rig hand-eye calibration problem.

Calibrates a multi-camera rig mounted on a robot arm, including:

  • Per-camera intrinsics and distortion
  • Per-camera extrinsics (camera-to-rig transforms)
  • Rig hand-eye transform (gripper-to-rig)
  • Static target pose in robot base frame

§Conventions

  • cam_se3_rig = T_C_R (transform from rig to camera frame)
  • EyeInHand export: gripper_se3_rig (T_G_R), base_se3_target (T_B_T)
  • EyeToHand export: rig_se3_base (T_R_B), gripper_se3_target (T_G_T)
  • Reference camera has identity extrinsics (defines rig frame)

§Example

use vision_calibration_pipeline::session::CalibrationSession;
use vision_calibration_pipeline::rig_handeye::{
    RigHandeyeProblem, step_intrinsics_init_all, step_intrinsics_optimize_all,
    step_rig_init, step_rig_optimize, step_handeye_init, step_handeye_optimize,
};

let mut session = CalibrationSession::<RigHandeyeProblem>::new();
session.set_input(rig_dataset)?;

step_intrinsics_init_all(&mut session, None)?;
step_intrinsics_optimize_all(&mut session, None)?;
step_rig_init(&mut session)?;
step_rig_optimize(&mut session, None)?;
step_handeye_init(&mut session, None)?;
step_handeye_optimize(&mut session, None)?;

let export = session.export()?;

Trait Implementations§

Source§

impl Debug for RigHandeyeProblem

Source§

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

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

impl ProblemType for RigHandeyeProblem

Source§

type Config = RigHandeyeConfig

Configuration parameters that control calibration behavior. Read more
Source§

type Input = RigDataset<RobotPoseMeta>

Input observations (embedded in session). Read more
Source§

type State = RigHandeyeState

Problem-specific workspace for intermediate results. Read more
Source§

type Output = HandEyeEstimate

Final calibration output (single result). Read more
Source§

type Export = RigHandeyeExport

Export format for external consumption. Read more
Source§

fn name() -> &'static str

Unique identifier for this problem type. Read more
Source§

fn schema_version() -> u32

Schema version for forward compatibility. Read more
Source§

fn validate_input( input: &<RigHandeyeProblem as ProblemType>::Input, ) -> Result<(), Error>

Validate input data after setting. Read more
Source§

fn validate_config( config: &<RigHandeyeProblem as ProblemType>::Config, ) -> Result<(), Error>

Validate configuration. Read more
Source§

fn validate_input_config( input: &<RigHandeyeProblem as ProblemType>::Input, config: &<RigHandeyeProblem as ProblemType>::Config, ) -> Result<(), Error>

Cross-validate input and config together. Read more
Source§

fn on_input_change() -> InvalidationPolicy

Policy for what to clear when input changes. Read more
Source§

fn on_config_change() -> InvalidationPolicy

Policy for what to clear when config changes. Read more
Source§

fn export( output: &<RigHandeyeProblem as ProblemType>::Output, config: &<RigHandeyeProblem as ProblemType>::Config, ) -> Result<<RigHandeyeProblem as ProblemType>::Export, Error>

Convert output to export format. Read more

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> 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, 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