42#include <visp3/core/vpConfig.h>
44#if defined(VISP_HAVE_CATCH2)
46#include <visp3/core/vpExponentialMap.h>
47#include <visp3/vision/vpHandEyeCalibration.h>
49#include <catch_amalgamated.hpp>
51#if defined(ENABLE_VISP_NAMESPACE)
62 for (
unsigned int i = 0;
i < 3; ++
i) {
64 std::cout <<
"Error: Translation " <<
i <<
" differ " << std::endl;
68 std::cout <<
"Error: Theta-u axis-angle rotation " <<
i <<
" differ" << std::endl;
75SCENARIO(
"Eye-in-hand calibration",
"[eye-in-hand]")
77 GIVEN(
"Eye-in-hand data")
79 std::cout <<
"-- First part: Eye-in-hand configuration -- " << std::endl;
81 const unsigned int N = 6;
84 std::vector<vpHomogeneousMatrix>
cMo(N);
86 std::vector<vpHomogeneousMatrix> rMe(N);
101 std::cout <<
"Ground truth hand-eye transformation: eMc " << std::endl;
102 std::cout << eMc_gt << std::endl;
103 std::cout <<
"Theta U rotation: "
116 std::cout <<
"Ground truth robot reference-object: rMo " << std::endl;
117 std::cout << rMo_gt << std::endl;
118 std::cout <<
"Theta U rotation: "
125 for (
unsigned int i = 0;
i < N; ++
i) {
129 rMe[0].buildFrom(0, 0, 0, 0, 0, 0);
153 rMe[
i] = rMe[
i - 1] * eMe;
160 for (
unsigned int i = 0;
i < N; ++
i) {
162 rMo = rMe[
i] * eMc_gt *
cMo[
i];
163 std::cout << std::endl <<
"rMo[" <<
i <<
"] " << std::endl;
164 std::cout << rMo << std::endl;
165 std::cout <<
"cMo[" <<
i <<
"] " << std::endl;
166 std::cout <<
cMo[
i] << std::endl;
167 std::cout <<
"rMe[" <<
i <<
"] " << std::endl;
168 std::cout << rMe[
i] << std::endl;
172 WHEN(
"Estimating eMc and rMo")
183 CHECK(homogeneous_equal(eMc, eMc_gt));
184 CHECK(homogeneous_equal(rMo, rMo_gt));
186 WHEN(
"Estimating eMc")
195 CHECK(homogeneous_equal(eMc, eMc_gt));
200SCENARIO(
"Eye-to-hand calibration",
"[eye-to-hand]")
202 GIVEN(
"Eye-to-hand data")
204 std::cout <<
"\n-- Second part: Eye-to-hand configuration -- " << std::endl;
211 const unsigned int N = 6;
213 std::vector<vpHomogeneousMatrix> oMc(N);
216 std::vector<vpHomogeneousMatrix> rMe(N);
230 std::cout <<
"Ground truth end effector to objet transformation : eMo " << std::endl;
231 std::cout << eMo_gt << std::endl;
242 std::cout <<
"Ground truth robot reference to camera transformation: rMc " << std::endl;
243 std::cout << rMc_gt << std::endl;
248 for (
unsigned int i = 0;
i < N; ++
i) {
252 rMe[0].buildFrom(0.1, -0.1, 1.0, 0.1, -0.2, 0.3);
276 rMe[
i] = rMe[
i - 1] * eMe;
280 oMc[
i] =
cMo.inverse();
284 for (
unsigned int i = 0;
i < N; ++
i) {
285 std::cout <<
"rMe[" <<
i <<
"] " << std::endl;
286 std::cout << rMe[
i] << std::endl;
287 std::cout <<
"cMo[" <<
i <<
"] " << std::endl;
288 std::cout << oMc[
i].inverse() << std::endl;
292 WHEN(
"Estimating eMo and rMc")
303 CHECK(homogeneous_equal(eMo, eMo_gt));
304 CHECK(homogeneous_equal(rMc, rMc_gt));
306 WHEN(
"Estimating eMo")
315 CHECK(homogeneous_equal(eMo, eMo_gt));
320int main(
int argc,
char *argv[])
322 Catch::Session session;
323 session.applyCommandLine(argc, argv);
324 int numFailed = session.run();
331 std::cout <<
"This test needs catch2 that is not enabled..." << std::endl;
Implementation of column vector and the associated operations.
static vpHomogeneousMatrix direct(const vpColVector &v)
static int calibrate(const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &rMo)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpThetaUVector getThetaUVector() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
static double rad(double deg)
static bool equal(double x, double y, double threshold=0.001)
static double deg(double rad)
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.