51 #include <geometry_msgs/Transform.h>
52 #include "visp_hand2eye_calibration/TransformArray.h"
56 #include <visp/vpCalibration.h>
57 #include <visp/vpExponentialMap.h>
71 =
n_.
serviceClient<visp_hand2eye_calibration::compute_effector_camera> (
74 =
n_.
serviceClient<visp_hand2eye_calibration::compute_effector_camera_quick> (
91 vpHomogeneousMatrix cMo;
92 vpHomogeneousMatrix wMe;
93 vpHomogeneousMatrix eMc;
96 vpTranslationVector etc(0.1, 0.2, 0.3);
98 erc[0] = vpMath::rad(10);
99 erc[1] = vpMath::rad(-10);
100 erc[2] = vpMath::rad(25);
102 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
105 eMc.buildFrom(etc, erc);
112 for (
int i = 0; i < N; i++)
118 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
119 cMo.build(0, 0, 0.5, 0, 0, 0);
120 wMe.build(0, 0, 0, 0, 0, 0);
122 cMo.buildFrom(0, 0, 0.5, 0, 0, 0);
123 wMe.buildFrom(0, 0, 0, 0, 0, 0);
137 vpHomogeneousMatrix cMc;
138 cMc = vpExponentialMap::direct(v_c);
142 cMo = cMc.inverse() * cMo;
143 wMe = wMe * eMc * cMc * eMc.inverse();
147 geometry_msgs::Transform pose_c_o;
149 geometry_msgs::Transform pose_w_e;
153 emc_quick_comm.request.camera_object.transforms.push_back(pose_c_o);
154 emc_quick_comm.request.world_effector.transforms.push_back(pose_w_e);
163 vpHomogeneousMatrix eMc;
178 vpHomogeneousMatrix eMc;