App that allows to perform eye-to-hand calibration.
#include <map>
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpIoTools.h>
#include <visp3/vision/vpHandEyeCalibration.h>
void usage(const char *argv[], int error)
{
std::cout << "Synopsis" << std::endl
<< " " << argv[0]
<< " [--data-path <path>]"
<< " [--rPe <generic name>]"
<< " [--cPo <generic name>]"
<< " [--output-ePo <filename>]"
<< " [--output-rPc <filename>]"
<< " [--help, -h]" << std::endl
<< std::endl;
std::cout << "Description" << std::endl
<< " Compute eye-to-hand calibration." << std::endl
<< std::endl
<< " --data-path <path>" << std::endl
<< " Path to the folder containing pose_rPe_%d.yaml and pose_cPo_%d.yaml data files." << std::endl
<< " Default: \"./\"" << std::endl
<< std::endl
<< " --rPe <generic name>" << std::endl
<< " Generic name of the yaml files containing the pose of the end-effector expressed in the robot" << std::endl
<< " base frame and located in the data path folder." << std::endl
<< " Default: pose_rPe_%d.yaml" << std::endl
<< std::endl
<< " --cPo <generic name>" << std::endl
<< " Generic name of the yaml files" << std::endl
<< " containing the pose of the calibration grid expressed in the camera frame and located in the" << std::endl
<< " data path folder." << std::endl
<< " Default: pose_cPo_%d.yaml" << std::endl
<< std::endl
<< " --output-ePo <filename>" << std::endl
<< " File in yaml format containing the pose of the object" << std::endl
<< " in the end-effector frame (eMo). Data are saved as a pose vector with first the 3 translations" << std::endl
<< " along X,Y,Z in [m] and then the 3 rotations in axis-angle representation (thetaU) in [rad]." << std::endl
<< " Default: ePo.yaml" << std::endl
<< std::endl
<< " --output-rPc <filename>" << std::endl
<< " File in yaml format containing the pose of the camera" << std::endl
<< " in the robot reference frame (rMc). Data are saved as a pose vector with first the 3 translations" << std::endl
<< " along X,Y,Z in [m] and then the 3 rotations in axis-angle representation (thetaU) in [rad]." << std::endl
<< " Default: rPc.yaml" << std::endl
<< std::endl
<< " --help, -h" << std::endl
<< " Print this helper message." << std::endl
<< std::endl;
if (error) {
std::cout << "Error" << std::endl
<< " "
<< "Unsupported parameter " << argv[error] << std::endl;
}
}
int main(int argc, const char *argv[])
{
#if defined(ENABLE_VISP_NAMESPACE)
#endif
std::string opt_data_path = "./";
std::string opt_rPe_files = "pose_rPe_%d.yaml";
std::string opt_cPo_files = "pose_cPo_%d.yaml";
std::string opt_ePo_file = "ePo.yaml";
std::string opt_rPc_file = "rPc.yaml";
for (int i = 1; i < argc; i++) {
if (std::string(argv[i]) == "--data-path" && i + 1 < argc) {
opt_data_path = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--rPe" && i + 1 < argc) {
opt_rPe_files = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--cPo" && i + 1 < argc) {
opt_cPo_files = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--output-ePo" && i + 1 < argc) {
opt_ePo_file = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--output-rPc" && i + 1 < argc) {
opt_rPc_file = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
usage(argv, 0);
return EXIT_SUCCESS;
}
else {
usage(argv, i);
return EXIT_FAILURE;
}
}
std::cout << "Create output directory: " << output_parent << std::endl;
}
std::vector<vpHomogeneousMatrix> oMc;
std::vector<vpHomogeneousMatrix> rMe;
std::map<long, std::string> map_rPe_files;
std::map<long, std::string> map_cPo_files;
for (unsigned int i = 0; i < files.size(); i++) {
if (index_rPe != -1) {
map_rPe_files[index_rPe] = files[i];
}
if (index_cPo != -1) {
map_cPo_files[index_cPo] = files[i];
}
}
if (map_rPe_files.size() == 0) {
std::cout << "No " << opt_rPe_files
<< " files found. Use --data-path <path> or --rPe <generic name> to be able to read your data." << std::endl;
std::cout << "Use --help option to see full usage..." << std::endl;
return EXIT_FAILURE;
}
if (map_cPo_files.size() == 0) {
std::cout << "No " << opt_cPo_files
<< " files found. Use --data-path <path> or --cPo <generic name> to be able to read your data." << std::endl;
std::cout << "Use --help option to see full usage..." << std::endl;
return EXIT_FAILURE;
}
for (std::map<long, std::string>::const_iterator it_rPe = map_rPe_files.begin(); it_rPe != map_rPe_files.end();
++it_rPe) {
std::map<long, std::string>::const_iterator it_cPo = map_cPo_files.find(it_rPe->first);
if (it_cPo != map_cPo_files.end()) {
if (rPe.
loadYAML(file_rPe, rPe) ==
false) {
std::cout << "Unable to read data from " << file_rPe << ". Skip data" << std::endl;
continue;
}
if (cPo.
loadYAML(file_cPo, cPo) ==
false) {
std::cout << "Unable to read data from " << file_cPo << ". Skip data" << std::endl;
continue;
}
std::cout << "Use data from " << opt_data_path << "/" << file_rPe << " and from " << file_cPo << std::endl;
}
}
if (rMe.size() < 3) {
std::cout << "Not enough data pairs found." << std::endl;
return EXIT_FAILURE;
}
if (ret == 0) {
std::cout << std::endl << "Eye-to-hand calibration succeed" << std::endl;
std::cout << std::endl << "Estimated hand-object (eMo) transformation:" << std::endl;
std::cout << "-------------------------------------------" << std::endl;
std::cout <<
"- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: " <<
vpPoseVector(eMo).
t() << std::endl;
std::cout << std::endl << "- Translation [m]: " << eMo[0][3] << " " << eMo[1][3] << " " << eMo[2][3] << std::endl;
std::cout <<
"- Rotation (theta-u representation) [rad]: " << ero.
t() << std::endl;
std::cout <<
"- Rotation (theta-u representation) [deg]: " <<
vpMath::deg(ero[0]) <<
" " <<
vpMath::deg(ero[1])
std::cout << "- Rotation (quaternion representation) [rad]: " << quaternion.t() << std::endl;
std::cout << "- Rotation (r-x-y-z representation) [rad]: " << rxyz.t() << std::endl;
std::cout <<
"- Rotation (r-x-y-z representation) [deg]: " <<
vpMath::deg(rxyz).t() << std::endl;
std::cout << std::endl << "Estimated robot reference to camera frames (rMc) transformation:" << std::endl;
std::cout << "----------------------------------------------------------------" << std::endl;
std::cout <<
"- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: " <<
vpPoseVector(rMc).
t() << std::endl;
std::cout << std::endl << "- Translation [m]: " << rMc[0][3] << " " << rMc[1][3] << " " << rMc[2][3] << std::endl;
std::cout <<
"- Rotation (theta-u representation) [rad]: " << wrc.
t() << std::endl;
std::cout <<
"- Rotation (theta-u representation) [deg]: " <<
vpMath::deg(wrc[0]) <<
" " <<
vpMath::deg(wrc[1])
std::cout << "- Rotation (quaternion representation) [rad]: " << quaternion2.t() << std::endl;
std::cout << "- Rotation (r-x-y-z representation) [rad]: " << rxyz2.t() << std::endl;
std::cout <<
"- Rotation (r-x-y-z representation) [deg]: " <<
vpMath::deg(rxyz).t() << std::endl;
{
std::cout << std::endl << "Save transformation matrix eMo as an homogeneous matrix in: " << name_we << std::endl;
#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98)
std::ofstream file_eMo(name_we);
#else
std::ofstream file_eMo(name_we.c_str());
#endif
std::cout << "Save transformation matrix eMo as a vpPoseVector in : " << output_filename << std::endl;
pose_vec.saveYAML(output_filename, pose_vec, "Robot end-effector to object frames transformation (eMo)");
}
{
std::cout << std::endl << "Save transformation matrix rMc as an homogeneous matrix in: " << name_we << std::endl;
#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98)
std::ofstream file_rMc(name_we);
#else
std::ofstream file_rMc(name_we.c_str());
#endif
std::cout << "Save transformation matrix rMc as a vpPoseVector in : " << output_filename << std::endl;
pose_vec.saveYAML(output_filename, pose_vec, "Robot reference to camera frames transformation (rMc)");
}
}
else {
std::cout << std::endl << "** Eye-to-hand calibration failed" << std::endl;
std::cout << std::endl << "Check your input data and ensure they are covering the half sphere over the Apriltag." << std::endl;
std::cout << std::endl << "See https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-calibration-extrinsic-eye-to-hand.html" << std::endl;
}
return EXIT_SUCCESS;
}
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
vpArray2D< Type > t() const
Compute the transpose of the array.
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.
vpRotationMatrix getRotationMatrix() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void save(std::ofstream &f) const
static double deg(double rad)
Implementation of a matrix and operations on matrices.
int print(std::ostream &s, unsigned int length, const std::string &intro="") const
Implementation of a pose vector and operations on poses.
Implementation of a rotation vector as quaternion angle minimal representation.
Implementation of a rotation vector as Euler angle minimal representation.
Implementation of a rotation vector as axis-angle minimal representation.