Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
testRobotViper650-frames.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Test Viper 650 robot.
32  */
33 
40 #include <iostream>
41 #include <visp3/robot/vpRobotViper650.h>
42 
43 #ifdef VISP_HAVE_VIPER650
44 
45 #ifdef ENABLE_VISP_NAMESPACE
46 using namespace VISP_NAMESPACE_NAME;
47 #endif
48 bool pose_equal(const vpHomogeneousMatrix &M1, const vpHomogeneousMatrix &M2, double epsilon = 1e-6)
49 {
50  vpTranslationVector t1, t2;
51  M1.extract(t1);
52  M2.extract(t2);
53  vpThetaUVector tu1, tu2;
54  M1.extract(tu1);
55  M2.extract(tu2);
56 
57  for (unsigned int i = 0; i < 3; i++) {
58  if (std::fabs(t1[i] - t2[i]) > epsilon)
59  return false;
60  if (std::fabs(tu1[i] - tu2[i]) > epsilon)
61  return false;
62  }
63  return true;
64 }
65 
66 bool joint_equal(const vpColVector &q1, const vpColVector &q2, double epsilon = 1e-6)
67 {
68  for (unsigned int i = 0; i < q1.size(); i++) {
69  if (std::fabs(q1[i] - q2[i]) > epsilon) {
70  return false;
71  }
72  }
73  return true;
74 }
75 
76 int main()
77 {
78  try {
79  //********* Define transformation from end effector to tool frame
81 
82 #if 0
83  // In this case, we set tool frame to the end of the two fingers pneumatic gripper
84  eMt[0][0] = 0;
85  eMt[1][0] = 0;
86  eMt[2][0] = -1;
87 
88  eMt[0][1] = -sqrt(2)/2;
89  eMt[1][1] = -sqrt(2)/2;
90  eMt[2][1] = 0;
91 
92  eMt[0][2] = -sqrt(2)/2;
93  eMt[1][2] = sqrt(2)/2;
94  eMt[2][2] = 0;
95 
96  eMt[0][3] = -0.177;
97  eMt[1][3] = 0.177;
98  eMt[2][3] = 0.077;
99 #else
100  // In this case, we set tool frame to the PTGrey Flea2 camera frame
101  vpTranslationVector etc(-0.04437278107, -0.001192883711, 0.07808296844);
102  vpRxyzVector erxyzc(vpMath::rad(0.7226737722), vpMath::rad(2.103893926), vpMath::rad(-90.46213439));
103  eMt.buildFrom(etc, vpRotationMatrix(erxyzc));
104 #endif
105  std::cout << "eMt:\n" << eMt << std::endl;
106 
107  //********* Init robot
108  std::cout << "Connection to Viper 650 robot" << std::endl;
109  vpRobotViper650 robot;
110  robot.init(vpViper650::TOOL_CUSTOM, eMt);
111 
112  // Move robot to repos position
113  vpColVector repos(6); // q1, q4, q6 = 0
114  repos[1] = vpMath::rad(-90); // q2
115  repos[2] = vpMath::rad(180); // q3
116  repos[4] = vpMath::rad(90); // q5
117 
118  robot.setPosition(vpRobot::ARTICULAR_FRAME, repos);
119 
120  vpColVector q;
121  robot.getPosition(vpRobotViper650::ARTICULAR_FRAME, q);
122 
123  std::cout << "q: " << q.t() << std::endl;
124 
125  vpHomogeneousMatrix fMw, fMe, fMt, cMe;
126  robot.get_fMw(q, fMw);
127  robot.get_fMe(q, fMe);
128  robot.get_fMc(q, fMt);
129  robot.get_cMe(cMe);
130 
131  std::cout << "fMw:\n" << fMw << std::endl;
132  std::cout << "fMe:\n" << fMe << std::endl;
133  std::cout << "fMt:\n" << fMt << std::endl;
134  std::cout << "eMc:\n" << cMe.inverse() << std::endl;
135 
136  //********* Check if retrieved eMt transformation is the one that was set
137  // during init
138  if (1) {
139  vpHomogeneousMatrix eMt_ = fMe.inverse() * fMt;
140  std::cout << "eMt_:\n" << eMt_ << std::endl;
141 
142  // Compare pose
143  std::cout << "Compare pose eMt and eMt_:" << std::endl;
144  if (!pose_equal(eMt, eMt_, 1e-4)) {
145  std::cout << " Error: Pose eMt differ" << std::endl;
146  std::cout << "\nTest failed" << std::endl;
147  return EXIT_FAILURE;
148  }
149  std::cout << " They are the same, we can continue" << std::endl;
150 
151  //********* Check if retrieved eMc transformation is the one that was
152  // set
153 
154  std::cout << "eMc:\n" << cMe.inverse() << std::endl;
155  // Compare pose
156  std::cout << "Compare pose eMt and eMc:" << std::endl;
157  if (!pose_equal(eMt, cMe.inverse(), 1e-4)) {
158  std::cout << " Error: Pose eMc differ" << std::endl;
159  std::cout << "\nTest failed" << std::endl;
160  return EXIT_FAILURE;
161  }
162  std::cout << " They are the same, we can continue" << std::endl;
163  }
164 
165  //********* Check if position in reference frame is equal to fMt
166  if (1) {
167  vpColVector f_pose_t; // translation vector + rxyz vector
168  robot.getPosition(vpRobot::REFERENCE_FRAME, f_pose_t);
169  // Compute homogeneous transformation
170  vpTranslationVector f_t_t;
171  vpRxyzVector f_rxyz_t;
172  for (unsigned int i = 0; i < 3; i++) {
173  f_t_t[i] = f_pose_t[i];
174  f_rxyz_t[i] = f_pose_t[i + 3];
175  }
176  vpHomogeneousMatrix fMt_(f_t_t, vpRotationMatrix(f_rxyz_t));
177  std::cout << "fMt_ (from ref frame):\n" << fMt_ << std::endl;
178 
179  std::cout << "Compare pose fMt and fMt_:" << std::endl;
180  if (!pose_equal(fMt, fMt_, 1e-4)) {
181  std::cout << " Error: Pose fMt differ" << std::endl;
182  std::cout << "\nTest failed" << std::endl;
183  return EXIT_FAILURE;
184  }
185  std::cout << " They are the same, we can continue" << std::endl;
186  }
187 
188  //********* Test inverse kinematics
189  if (1) {
190  vpColVector q1;
191  robot.getInverseKinematics(fMt, q1);
192 
193  std::cout << "Move robot in joint (the robot should not move)" << std::endl;
195  robot.setPosition(vpRobotViper650::ARTICULAR_FRAME, q1);
196 
197  vpColVector q2;
198  robot.getPosition(vpRobot::ARTICULAR_FRAME, q2);
199  std::cout << "Reach joint position q2: " << q2.t() << std::endl;
200 
201  std::cout << "Compare joint position q and q2:" << std::endl;
202  if (!joint_equal(q, q2, 1e-4)) {
203  std::cout << " Error: Joint position differ" << std::endl;
204  std::cout << "\nTest failed" << std::endl;
205  return EXIT_FAILURE;
206  }
207  std::cout << " They are the same, we can continue" << std::endl;
208  }
209 
210  //********* Check if fMt position can be set in reference frame
211  if (1) {
212  vpColVector f_pose_t(6);
214  vpRxyzVector f_rxyz_t(fMt.getRotationMatrix());
215  for (unsigned int i = 0; i < 3; i++) {
216  f_pose_t[i] = f_t_t[i];
217  f_pose_t[i + 3] = f_rxyz_t[i];
218  }
219 
220  std::cout << "Move robot in reference frame (the robot should not move)" << std::endl;
221  robot.setPosition(vpRobot::REFERENCE_FRAME, f_pose_t);
222  vpColVector q3;
223  robot.getPosition(vpRobot::ARTICULAR_FRAME, q3);
224  std::cout << "Reach joint position q3: " << q3.t() << std::endl;
225  std::cout << "Compare joint position q and q3:" << std::endl;
226  if (!joint_equal(q, q3, 1e-4)) {
227  std::cout << " Error: Joint position differ" << std::endl;
228  std::cout << "\nTest failed" << std::endl;
229  return EXIT_FAILURE;
230  }
231  std::cout << " They are the same, we can continue" << std::endl;
232  }
233 
234  //********* Position control in tool frame
235  if (1) {
236  // from the current position move the tool frame
238  // tMt[0][3] = 0.05; // along x_t
239  tMt[1][3] = 0.05; // along y_t
240  // tMt[2][3] = 0.05; // along z_t
241 
242  vpHomogeneousMatrix fMt_ = fMt * tMt; // New position to reach
243  robot.getInverseKinematics(fMt_, q);
244 
245  std::cout << "fMt_:\n" << fMt_ << std::endl;
246 
247  std::cout << "Move robot in joint position to reach fMt_" << std::endl;
249  robot.setPosition(vpRobotViper650::ARTICULAR_FRAME, q);
250 
251  vpPoseVector fpt_;
252  robot.getPosition(vpRobot::REFERENCE_FRAME, fpt_);
253 
254  std::cout << "fpt_:\n" << vpHomogeneousMatrix(fpt_) << std::endl;
255 
256  std::cout << "Compare pose fMt_ and fpt_:" << std::endl;
257  if (!pose_equal(fMt_, vpHomogeneousMatrix(fpt_), 1e-4)) {
258  std::cout << " Error: Pose fMt_ differ" << std::endl;
259  std::cout << "\nTest failed" << std::endl;
260  return EXIT_FAILURE;
261  }
262  std::cout << " They are the same, we can continue" << std::endl;
263  }
264 
265  //********* Velocity control in tool frame along z
266  if (1) {
267  double t_init = vpTime::measureTimeMs();
268  vpColVector v_t(6);
269  v_t = 0;
270  // v_t[2] = 0.01; // translation velocity along z_t
271  v_t[5] = vpMath::rad(5); // rotation velocity along z_t
272 
273  std::cout << "Move robot in camera velocity" << std::endl;
275  while (vpTime::measureTimeMs() - t_init < 6000) {
276  // std::cout << "send vel: " << v_t() << std::endl;
278  }
279  }
280 
281  //********* Velocity control in tool frame along z using joint velocity
282  if (1) {
283  // We need to stop the robot before changing velocity control from joint
284  // to cartesian
286  vpVelocityTwistMatrix tVe(eMt.inverse());
287  vpMatrix eJe;
288 
289  double t_init = vpTime::measureTimeMs();
290  vpColVector v_t(6), q_dot;
291  v_t = 0;
292  // v_t[2] = -0.01; // translation velocity along z_t
293  v_t[5] = vpMath::rad(-5); // rotation velocity along z_t
294 
295  std::cout << "Move robot in joint velocity" << std::endl;
297  while (vpTime::measureTimeMs() - t_init < 6000) {
298  robot.get_eJe(eJe);
299  vpMatrix tJt = tVe * eJe;
300  q_dot = tJt.pseudoInverse() * v_t;
301  // std::cout << "send vel: " << q_dot.t() << std::endl;
303  }
304  }
305 
306  //********* Velocity control in tool frame along x
307  if (1) {
309  double t_init = vpTime::measureTimeMs();
310  vpColVector v_t(6);
311  v_t = 0;
312  v_t[3] = vpMath::rad(5); // rotation velocity along x_t
313 
314  std::cout << "Move robot in camera velocity" << std::endl;
316  while (vpTime::measureTimeMs() - t_init < 3000) {
317  // std::cout << "send vel: " << v_t() << std::endl;
319  }
320  }
321 
322  //********* Velocity control in tool frame along x using joint velocity
323  if (1) {
324  // We need to stop the robot before changing velocity control from joint
325  // to cartesian
327  vpVelocityTwistMatrix tVe(eMt.inverse());
328  vpMatrix eJe;
329 
330  double t_init = vpTime::measureTimeMs();
331  vpColVector v_t(6), q_dot;
332  v_t = 0;
333  v_t[3] = vpMath::rad(-5); // rotation velocity along x_t
334 
335  std::cout << "Move robot in joint velocity" << std::endl;
337  while (vpTime::measureTimeMs() - t_init < 3000) {
338  robot.get_eJe(eJe);
339  vpMatrix tJt = tVe * eJe;
340  q_dot = tJt.pseudoInverse() * v_t;
341  // std::cout << "send vel: " << q_dot.t() << std::endl;
343  }
344  }
345 
346  //********* Position control in tool frame
347  if (1) {
349  // get current position
350  robot.getPosition(vpRobotViper650::ARTICULAR_FRAME, q);
351 
352  robot.get_fMc(q, fMt);
353 
354  vpHomogeneousMatrix tMt; // initialized to identity
355  // tMt[0][3] = -0.05; // along x_t
356  tMt[1][3] = -0.05; // along y_t
357  // tMt[2][3] = -0.05; // along z_t
358 
359  robot.getInverseKinematics(fMt * tMt, q);
360 
361  std::cout << "Move robot in joint position" << std::endl;
363  robot.setPosition(vpRobotViper650::ARTICULAR_FRAME, q);
364  }
365  std::cout << "The end" << std::endl;
366  std::cout << "Test succeed" << std::endl;
367  return EXIT_SUCCESS;
368  }
369  catch (const vpException &e) {
370  std::cout << "Test failed with exception: " << e.getMessage() << std::endl;
371  return EXIT_FAILURE;
372  }
373 }
374 
375 #else
376 int main()
377 {
378  std::cout << "The real Viper650 robot controller is not available." << std::endl;
379  return EXIT_SUCCESS;
380 }
381 
382 #endif
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:349
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpRowVector t() const
error that can be emitted by ViSP classes.
Definition: vpException.h:60
const char * getMessage() const
Definition: vpException.cpp:65
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
vpTranslationVector getTranslationVector() const
void extract(vpRotationMatrix &R) const
static double rad(double deg)
Definition: vpMath.h:129
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
Control of Irisa's Viper S650 robot named Viper650.
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
vpHomogeneousMatrix get_cMe() const
Definition: vpUnicycle.h:65
VISP_EXPORT double measureTimeMs()