Test of eye-in-hand calibration to estimate extrinsic camera parameters, ie hand-eye homogeneous transformation corresponding to the transformation between the robot end-effector and the camera.
Test of eye-in-hand calibration to estimate extrinsic camera parameters, ie hand-eye homogeneous transformation corresponding to the transformation between the robot end-effector and the camera.
#include <iostream>
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_CATCH2)
#include <visp3/core/vpExponentialMap.h>
#include <visp3/vision/vpHandEyeCalibration.h>
#include <catch_amalgamated.hpp>
#if defined(ENABLE_VISP_NAMESPACE)
#endif
{
bool equal = true;
for (unsigned int i = 0; i < 3; ++i) {
std::cout << "Error: Translation " << i << " differ " << std::endl;
equal = false;
}
std::cout << "Error: Theta-u axis-angle rotation " << i << " differ" << std::endl;
equal = false;
}
}
return equal;
}
SCENARIO("Eye-in-hand calibration", "[eye-in-hand]")
{
GIVEN("Eye-in-hand data")
{
std::cout << "-- First part: Eye-in-hand configuration -- " << std::endl;
const unsigned int N = 6;
std::vector<vpHomogeneousMatrix> cMo(N);
std::vector<vpHomogeneousMatrix> rMe(N);
std::cout << "Ground truth hand-eye transformation: eMc " << std::endl;
std::cout << eMc_gt << std::endl;
std::cout << "Theta U rotation: "
<< std::endl;
std::cout << "Ground truth robot reference-object: rMo " << std::endl;
std::cout << rMo_gt << std::endl;
std::cout << "Theta U rotation: "
<< std::endl;
for (unsigned int i = 0; i < N; ++i) {
v_e = 0;
if (i == 0) {
rMe[0].buildFrom(0, 0, 0, 0, 0, 0);
}
else if (i == 1) {
v_e[3] = M_PI / 8;
}
else if (i == 2) {
v_e[4] = M_PI / 8;
}
else if (i == 3) {
v_e[5] = M_PI / 10;
}
else if (i == 4) {
v_e[0] = 0.5;
}
else if (i == 5) {
v_e[1] = 0.8;
}
if (i > 0) {
rMe[
i] = rMe[
i - 1] * eMe;
}
}
if (0) {
for (
unsigned int i = 0;
i < N; ++
i) {
rMo = rMe[
i] * eMc_gt *
cMo[
i];
std::cout << std::endl <<
"rMo[" <<
i <<
"] " << std::endl;
std::cout << rMo << std::endl;
std::cout <<
"cMo[" <<
i <<
"] " << std::endl;
std::cout <<
cMo[
i] << std::endl;
std::cout <<
"rMe[" <<
i <<
"] " << std::endl;
std::cout << rMe[
i] << std::endl;
}
}
WHEN("Estimating eMc and rMo")
{
CHECK(homogeneous_equal(eMc, eMc_gt));
CHECK(homogeneous_equal(rMo, rMo_gt));
}
WHEN("Estimating eMc")
{
CHECK(homogeneous_equal(eMc, eMc_gt));
}
}
}
SCENARIO("Eye-to-hand calibration", "[eye-to-hand]")
{
GIVEN("Eye-to-hand data")
{
std::cout << "\n-- Second part: Eye-to-hand configuration -- " << std::endl;
const unsigned int N = 6;
std::vector<vpHomogeneousMatrix> oMc(N);
std::vector<vpHomogeneousMatrix> rMe(N);
std::cout << "Ground truth end effector to objet transformation : eMo " << std::endl;
std::cout << eMo_gt << std::endl;
<< std::endl;
std::cout << "Ground truth robot reference to camera transformation: rMc " << std::endl;
std::cout << rMc_gt << std::endl;
<< std::endl;
for (
unsigned int i = 0;
i < N; ++
i) {
v_e = 0;
if (i == 0) {
rMe[0].buildFrom(0.1, -0.1, 1.0, 0.1, -0.2, 0.3);
}
else if (i == 1) {
v_e[3] = M_PI / 4;
}
else if (i == 2) {
v_e[4] = -M_PI / 8;
}
else if (i == 3) {
v_e[5] = M_PI / 3;
}
else if (i == 4) {
v_e[0] = -0.5;
}
else if (i == 5) {
v_e[1] = 0.4;
}
if (i > 0) {
rMe[
i] = rMe[
i - 1] * eMe;
}
}
if (0) {
for (
unsigned int i = 0;
i < N; ++
i) {
std::cout <<
"rMe[" <<
i <<
"] " << std::endl;
std::cout << rMe[
i] << std::endl;
std::cout <<
"cMo[" <<
i <<
"] " << std::endl;
std::cout << oMc[
i].inverse() << std::endl;
}
}
WHEN("Estimating eMo and rMc")
{
CHECK(homogeneous_equal(eMo, eMo_gt));
CHECK(homogeneous_equal(rMc, rMc_gt));
}
WHEN("Estimating eMo")
{
CHECK(homogeneous_equal(eMo, eMo_gt));
}
}
}
int main(int argc, char *argv[])
{
Catch::Session session;
session.applyCommandLine(argc, argv);
int numFailed = session.run();
return numFailed;
}
#else
int main()
{
std::cout << "This test needs catch2 that is not enabled..." << std::endl;
}
#endif
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.