40#include <visp3/core/vpConfig.h>
41#include <visp3/core/vpIoTools.h>
42#include <visp3/vision/vpHandEyeCalibration.h>
44void usage(
const char *argv[],
int error)
46 std::cout <<
"Synopsis" << std::endl
48 <<
" [--data-path <path>]"
49 <<
" [--rPe <generic name>]"
50 <<
" [--cPo <generic name>]"
51 <<
" [--output-ePo <filename>]"
52 <<
" [--output-rPc <filename>]"
53 <<
" [--help, -h]" << std::endl
55 std::cout <<
"Description" << std::endl
56 <<
" Compute eye-to-hand calibration." << std::endl
58 <<
" --data-path <path>" << std::endl
59 <<
" Path to the folder containing pose_rPe_%d.yaml and pose_cPo_%d.yaml data files." << std::endl
60 <<
" Default: \"./\"" << std::endl
62 <<
" --rPe <generic name>" << std::endl
63 <<
" Generic name of the yaml files containing the pose of the end-effector expressed in the robot" << std::endl
64 <<
" base frame and located in the data path folder." << std::endl
65 <<
" Default: pose_rPe_%d.yaml" << std::endl
67 <<
" --cPo <generic name>" << std::endl
68 <<
" Generic name of the yaml files" << std::endl
69 <<
" containing the pose of the calibration grid expressed in the camera frame and located in the" << std::endl
70 <<
" data path folder." << std::endl
71 <<
" Default: pose_cPo_%d.yaml" << std::endl
73 <<
" --output-ePo <filename>" << std::endl
74 <<
" File in yaml format containing the pose of the object" << std::endl
75 <<
" in the end-effector frame (eMo). Data are saved as a pose vector with first the 3 translations" << std::endl
76 <<
" along X,Y,Z in [m] and then the 3 rotations in axis-angle representation (thetaU) in [rad]." << std::endl
77 <<
" Default: ePo.yaml" << std::endl
79 <<
" --output-rPc <filename>" << std::endl
80 <<
" File in yaml format containing the pose of the camera" << std::endl
81 <<
" in the robot reference frame (rMc). Data are saved as a pose vector with first the 3 translations" << std::endl
82 <<
" along X,Y,Z in [m] and then the 3 rotations in axis-angle representation (thetaU) in [rad]." << std::endl
83 <<
" Default: rPc.yaml" << std::endl
85 <<
" --help, -h" << std::endl
86 <<
" Print this helper message." << std::endl
89 std::cout <<
"Error" << std::endl
91 <<
"Unsupported parameter " << argv[
error] << std::endl;
95int main(
int argc,
const char *argv[])
97#if defined(ENABLE_VISP_NAMESPACE)
101 std::string opt_data_path =
"./";
102 std::string opt_rPe_files =
"pose_rPe_%d.yaml";
103 std::string opt_cPo_files =
"pose_cPo_%d.yaml";
104 std::string opt_ePo_file =
"ePo.yaml";
105 std::string opt_rPc_file =
"rPc.yaml";
107 for (
int i = 1;
i < argc;
i++) {
108 if (std::string(argv[i]) ==
"--data-path" && i + 1 < argc) {
109 opt_data_path = std::string(argv[++i]);
111 else if (std::string(argv[i]) ==
"--rPe" && i + 1 < argc) {
112 opt_rPe_files = std::string(argv[++i]);
114 else if (std::string(argv[i]) ==
"--cPo" && i + 1 < argc) {
115 opt_cPo_files = std::string(argv[++i]);
117 else if (std::string(argv[i]) ==
"--output-ePo" && i + 1 < argc) {
118 opt_ePo_file = std::string(argv[++i]);
120 else if (std::string(argv[i]) ==
"--output-rPc" && i + 1 < argc) {
121 opt_rPc_file = std::string(argv[++i]);
123 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
136 std::cout <<
"Create output directory: " << output_parent << std::endl;
140 std::vector<vpHomogeneousMatrix> oMc;
141 std::vector<vpHomogeneousMatrix> rMe;
145 std::map<long, std::string> map_rPe_files;
146 std::map<long, std::string> map_cPo_files;
148 for (
unsigned int i = 0;
i < files.size();
i++) {
151 if (index_rPe != -1) {
152 map_rPe_files[index_rPe] = files[
i];
154 if (index_cPo != -1) {
155 map_cPo_files[index_cPo] = files[
i];
159 if (map_rPe_files.size() == 0) {
160 std::cout <<
"No " << opt_rPe_files
161 <<
" files found. Use --data-path <path> or --rPe <generic name> to be able to read your data." << std::endl;
162 std::cout <<
"Use --help option to see full usage..." << std::endl;
165 if (map_cPo_files.size() == 0) {
166 std::cout <<
"No " << opt_cPo_files
167 <<
" files found. Use --data-path <path> or --cPo <generic name> to be able to read your data." << std::endl;
168 std::cout <<
"Use --help option to see full usage..." << std::endl;
172 for (std::map<long, std::string>::const_iterator it_rPe = map_rPe_files.begin(); it_rPe != map_rPe_files.end();
175 std::map<long, std::string>::const_iterator it_cPo = map_cPo_files.find(it_rPe->first);
176 if (it_cPo != map_cPo_files.end()) {
178 if (rPe.
loadYAML(file_rPe, rPe) ==
false) {
179 std::cout <<
"Unable to read data from " << file_rPe <<
". Skip data" << std::endl;
185 if (cPo.
loadYAML(file_cPo, cPo) ==
false) {
186 std::cout <<
"Unable to read data from " << file_cPo <<
". Skip data" << std::endl;
189 std::cout <<
"Use data from " << opt_data_path <<
"/" << file_rPe <<
" and from " << file_cPo << std::endl;
193 cMo_inv =
cMo.inverse();
199 if (rMe.size() < 3) {
200 std::cout <<
"Not enough data pairs found." << std::endl;
207 std::cout << std::endl <<
"Eye-to-hand calibration succeed" << std::endl;
208 std::cout << std::endl <<
"Estimated hand-object (eMo) transformation:" << std::endl;
209 std::cout <<
"-------------------------------------------" << std::endl;
212 std::cout <<
"- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: " <<
vpPoseVector(eMo).
t() << std::endl;
215 std::cout << std::endl <<
"- Translation [m]: " << eMo[0][3] <<
" " << eMo[1][3] <<
" " << eMo[2][3] << std::endl;
216 std::cout <<
"- Rotation (theta-u representation) [rad]: " << ero.
t() << std::endl;
217 std::cout <<
"- Rotation (theta-u representation) [deg]: " <<
vpMath::deg(ero[0]) <<
" " <<
vpMath::deg(ero[1])
220 std::cout <<
"- Rotation (quaternion representation) [rad]: " << quaternion.t() << std::endl;
222 std::cout <<
"- Rotation (r-x-y-z representation) [rad]: " << rxyz.t() << std::endl;
223 std::cout <<
"- Rotation (r-x-y-z representation) [deg]: " <<
vpMath::deg(rxyz).t() << std::endl;
225 std::cout << std::endl <<
"Estimated robot reference to camera frames (rMc) transformation:" << std::endl;
226 std::cout <<
"----------------------------------------------------------------" << std::endl;
229 std::cout <<
"- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: " <<
vpPoseVector(rMc).
t() << std::endl;
232 std::cout << std::endl <<
"- Translation [m]: " << rMc[0][3] <<
" " << rMc[1][3] <<
" " << rMc[2][3] << std::endl;
233 std::cout <<
"- Rotation (theta-u representation) [rad]: " << wrc.
t() << std::endl;
234 std::cout <<
"- Rotation (theta-u representation) [deg]: " <<
vpMath::deg(wrc[0]) <<
" " <<
vpMath::deg(wrc[1])
237 std::cout <<
"- Rotation (quaternion representation) [rad]: " << quaternion2.t() << std::endl;
239 std::cout <<
"- Rotation (r-x-y-z representation) [rad]: " << rxyz2.t() << std::endl;
240 std::cout <<
"- Rotation (r-x-y-z representation) [deg]: " <<
vpMath::deg(rxyz).t() << std::endl;
245 std::cout << std::endl <<
"Save transformation matrix eMo as an homogeneous matrix in: " << name_we << std::endl;
247#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98)
248 std::ofstream file_eMo(name_we);
250 std::ofstream file_eMo(name_we.c_str());
257 std::cout <<
"Save transformation matrix eMo as a vpPoseVector in : " << output_filename << std::endl;
258 pose_vec.saveYAML(output_filename, pose_vec,
"Robot end-effector to object frames transformation (eMo)");
264 std::cout << std::endl <<
"Save transformation matrix rMc as an homogeneous matrix in: " << name_we << std::endl;
266#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98)
267 std::ofstream file_rMc(name_we);
269 std::ofstream file_rMc(name_we.c_str());
276 std::cout <<
"Save transformation matrix rMc as a vpPoseVector in : " << output_filename << std::endl;
277 pose_vec.saveYAML(output_filename, pose_vec,
"Robot reference to camera frames transformation (rMc)");
281 std::cout << std::endl <<
"** Eye-to-hand calibration failed" << std::endl;
282 std::cout << std::endl <<
"Check your input data and ensure they are covering the half sphere over the Apriltag." << std::endl;
283 std::cout << std::endl <<
"See https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-calibration-extrinsic-eye-to-hand.html" << std::endl;
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
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.