63 virtual const std::vector<std::string>&
getSolverNames()
const = 0;
76 virtual bool solve(
const std::vector<Eigen::Isometry3d>& effector_wrt_world,
78 const std::string& solver_name =
"", std::string* error_message =
nullptr) = 0;
97 std::pair<double, double>
getReprojectionError(
const std::vector<Eigen::Isometry3d>& effector_wrt_world,
98 const std::vector<Eigen::Isometry3d>& object_wrt_sensor,
101 auto ret = std::make_pair(std::numeric_limits<double>::quiet_NaN(), std::numeric_limits<double>::quiet_NaN());
102 if (effector_wrt_world.size() != object_wrt_sensor.size())
105 "Different number of optical and kinematic transforms when calculating reprojection error.");
109 if (effector_wrt_world.empty())
114 double rotation_err = 0;
115 double translation_err = 0;
117 const size_t num_motions = effector_wrt_world.size() - 1;
118 for (
size_t i = 0; i < num_motions; ++i)
123 A = effector_wrt_world[i].inverse() * effector_wrt_world[i + 1];
125 A = effector_wrt_world[i] * effector_wrt_world[i + 1].inverse();
126 Eigen::Isometry3d B = object_wrt_sensor[i] * object_wrt_sensor[i + 1].inverse();
128 Eigen::Isometry3d AX =
A * X;
129 Eigen::Isometry3d XB = X * B;
132 double r_err = Eigen::AngleAxisd(AX.rotation().transpose() * XB.rotation()).angle();
133 rotation_err += r_err * r_err;
136 double t_err = ((AX.translation() - XB.translation()).norm() +
137 (AX.inverse().translation() - XB.inverse().translation()).norm()) /
139 translation_err += t_err * t_err;
141 ret = std::make_pair(std::sqrt(rotation_err / num_motions), std::sqrt(translation_err / num_motions));