53 #if VISP_VERSION_INT >= (3<<16 | 2<<8 | 0)
54 # include <visp3/vision/vpHandEyeCalibration.h>
56 # include <visp3/vision/vpCalibration.h>
58 #include <visp3/core/vpHomogeneousMatrix.h>
65 ROS_DEBUG(
"new cMo: [%f,%f,%f -- %f,%f,%f,%f]", trans->translation.x,trans->translation.y,trans->translation.z,trans->rotation.x,trans->rotation.y,trans->rotation.z,trans->rotation.w);
66 vpHomogeneousMatrix cMo;
73 ROS_DEBUG(
"new wMe: [%f,%f,%f -- %f,%f,%f,%f]", trans->translation.x,trans->translation.y,trans->translation.z,trans->rotation.x,trans->rotation.y,trans->rotation.z,trans->rotation.w);
74 vpHomogeneousMatrix wMe;
80 visp_hand2eye_calibration::compute_effector_camera::Request &req,
81 visp_hand2eye_calibration::compute_effector_camera::Response &res)
85 ROS_ERROR(
"transformation vectors have different sizes or contain too few elements");
90 vpHomogeneousMatrix eMc;
92 #if VISP_VERSION_INT >= (3<<16 | 2<<8 | 0)
94 #elif VISP_VERSION_INT > (2<<16 | 6<<8 | 1)
99 geometry_msgs::Transform trans;
102 res.effector_camera = trans;
107 visp_hand2eye_calibration::compute_effector_camera_quick::Request &req,
108 visp_hand2eye_calibration::compute_effector_camera_quick::Response &res)
110 visp_hand2eye_calibration::TransformArray camera_object = req.camera_object;
111 visp_hand2eye_calibration::TransformArray world_effector = req.world_effector;
112 std::vector<vpHomogeneousMatrix> cMo_vec;
113 std::vector<vpHomogeneousMatrix> wMe_vec;
114 for(
unsigned int i=0;i<camera_object.transforms.size();i++){
118 if (camera_object.transforms.size() != world_effector.transforms.size() || world_effector.transforms.size() < 2)
120 ROS_ERROR(
"transformation vectors have different sizes or contain too few elements");
125 vpHomogeneousMatrix eMc;
126 #if VISP_VERSION_INT >= (3<<16 | 2<<8 | 0)
127 vpHandEyeCalibration::calibrate(cMo_vec, wMe_vec, eMc);
128 #elif VISP_VERSION_INT > (2<<16 | 6<<8 | 1)
129 vpCalibration::calibrationTsai(cMo_vec, wMe_vec, eMc);
131 vpCalibration::calibrationTsai(cMo_vec.size(), &(cMo_vec[0]), &(wMe_vec[0]),eMc);
133 geometry_msgs::Transform trans;
135 res.effector_camera = trans;
140 visp_hand2eye_calibration::reset::Response &res)
166 compute_effector_camera_callback);
169 compute_effector_camera_quick_callback);
182 camera_object_callback);
184 world_effector_callback);