Industrial Calibration  1.0.0
Loading...
Searching...
No Matches
industrial_calibration::ExtrinsicHandEyeCost< OBS_DIMENSION > Class Template Reference

Base class for hand-eye calibration cost functions.

#include <extrinsic_hand_eye_cost.h>

Public Member Functions

 ExtrinsicHandEyeCost (const Eigen::Matrix< double, OBS_DIMENSION, 1 > &obs, const Eigen::Isometry3d &camera_mount_to_base, const Eigen::Isometry3d &base_to_target_mount, const Eigen::Vector3d &point_in_target)
 A Ceres cost function class that represents a single observation of a 3D camera and target.
 
template<typename T >
bool operator() (const T *pose_camera_to_camera_mount, const T *pose_target_mount_to_target, T *residual) const
 
template<typename T >
void getTargetPointInCamera (const T *pose_camera_to_camera_mount, const T *pose_target_mount_to_target, T *camera_point) const
 

Protected Attributes

Eigen::Matrix< double, OBS_DIMENSION, 1 > obs_
 
Pose6d camera_mount_to_base_
 
Pose6d base_to_target_mount_
 
Eigen::Vector3d target_pt_
 

Constructor & Destructor Documentation

◆ ExtrinsicHandEyeCost()

template<Eigen::Index OBS_DIMENSION>
industrial_calibration::ExtrinsicHandEyeCost< OBS_DIMENSION >::ExtrinsicHandEyeCost ( const Eigen::Matrix< double, OBS_DIMENSION, 1 > &  obs,
const Eigen::Isometry3d &  camera_mount_to_base,
const Eigen::Isometry3d &  base_to_target_mount,
const Eigen::Vector3d &  point_in_target 
)
inline
Parameters
obs- The observation of a feature in the camera frame
camera_mount_to_base- The transform from the camera "mount" frame to the common base frame
base_to_target_mount- The transform from the common base frame to the target "mount" frame
point_in_target- The corresponding feature in the target frame