pub struct HandEyeParams {
pub cameras: Vec<PinholeCamera>,
pub cam_to_rig: Vec<Iso3>,
pub handeye: Iso3,
pub target_poses: Vec<Iso3>,
}Expand description
Initial values for hand-eye calibration.
cam_to_rig: camera pose in the rig frame (T_C_R)handeye:EyeInHand: gripper pose in the rig frame (T_G_R)EyeToHand: rig pose in the base frame (T_R_B)
target_poses: fixed target pose(s) depending on the selected mode
Fields§
§cameras: Vec<PinholeCamera>Per-camera intrinsics and distortion.
cam_to_rig: Vec<Iso3>Per-camera extrinsics (camera-to-rig transforms).
handeye: Iso3Hand-eye transform (mode-dependent).
EyeInHand:handeye = gripper_from_rig(T_G_R)EyeToHand:handeye = rig_from_base(T_R_B)
target_poses: Vec<Iso3>Calibration target poses.
- Default (fixed target):
EyeInHand: the first pose is used as the initialbase_from_target(T_B_T)EyeToHand: the first pose is used as the initialgripper_from_target(T_G_T)
- Legacy (
relax_target_poses = true): one pose per view is required.
Trait Implementations§
Source§impl Clone for HandEyeParams
impl Clone for HandEyeParams
Source§fn clone(&self) -> HandEyeParams
fn clone(&self) -> HandEyeParams
Returns a duplicate of the value. Read more
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from
source. Read moreSource§impl Debug for HandEyeParams
impl Debug for HandEyeParams
Source§impl<'de> Deserialize<'de> for HandEyeParams
impl<'de> Deserialize<'de> for HandEyeParams
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Deserialize this value from the given Serde deserializer. Read more
Auto Trait Implementations§
impl Freeze for HandEyeParams
impl RefUnwindSafe for HandEyeParams
impl Send for HandEyeParams
impl Sync for HandEyeParams
impl Unpin for HandEyeParams
impl UnsafeUnpin for HandEyeParams
impl UnwindSafe for HandEyeParams
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<T> DistributionExt for Twhere
T: ?Sized,
impl<T> DistributionExt for Twhere
T: ?Sized,
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
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 moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
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 moreSource§impl<T> Pointable for T
impl<T> Pointable for T
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
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
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
fn from_subset(element: &SS) -> SP
The inclusion map: converts
self to the equivalent element of its superset.