Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
testRobotViper650-frames.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
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 http://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  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
44 #include <iostream>
45 #include <visp3/robot/vpRobotViper650.h>
46 
47 #ifdef VISP_HAVE_VIPER650
48 
49 bool pose_equal(const vpHomogeneousMatrix &M1, const vpHomogeneousMatrix &M2, double epsilon=1e-6)
50 {
51  vpTranslationVector t1, t2;
52  M1.extract(t1);
53  M2.extract(t2);
54  vpThetaUVector tu1, tu2;
55  M1.extract(tu1);
56  M2.extract(tu2);
57 
58  for(unsigned int i=0; i<3; i++) {
59  if (std::fabs(t1[i]-t2[i]) > epsilon)
60  return false;
61  if (std::fabs(tu1[i]-tu2[i]) > epsilon)
62  return false;
63  }
64  return true;
65 }
66 
67 bool joint_equal(const vpColVector &q1, const vpColVector &q2, double epsilon=1e-6)
68 {
69  for(unsigned int i=0; i<q1.size(); i++) {
70  if (std::fabs(q1[i]-q2[i]) > epsilon) {
71  return false;
72  }
73  }
74  return true;
75 }
76 
77 int main()
78 {
79  try {
80  //********* Define transformation from end effector to tool frame
82 
83 #if 0
84  // In this case, we set tool frame to the end of the two fingers pneumatic gripper
85  eMt[0][0] = 0;
86  eMt[1][0] = 0;
87  eMt[2][0] = -1;
88 
89  eMt[0][1] = -sqrt(2)/2;
90  eMt[1][1] = -sqrt(2)/2;
91  eMt[2][1] = 0;
92 
93  eMt[0][2] = -sqrt(2)/2;
94  eMt[1][2] = sqrt(2)/2;
95  eMt[2][2] = 0;
96 
97  eMt[0][3] = -0.177;
98  eMt[1][3] = 0.177;
99  eMt[2][3] = 0.077;
100 #else
101  // In this case, we set tool frame to the PTGrey Flea2 camera frame
102  vpTranslationVector etc(-0.04437278107, -0.001192883711, 0.07808296844);
103  vpRxyzVector erxyzc(vpMath::rad(0.7226737722), vpMath::rad(2.103893926), vpMath::rad(-90.46213439));
104  eMt.buildFrom(etc, vpRotationMatrix(erxyzc));
105 #endif
106  std::cout << "eMt:\n" << eMt << std::endl;
107 
108  //********* Init robot
109  std::cout << "Connection to Viper 650 robot" << std::endl;
110  vpRobotViper650 robot;
111  robot.init(vpViper650::TOOL_CUSTOM, eMt);
112 
113  // Move robot to repos position
114  vpColVector repos(6); // q1, q4, q6 = 0
115  repos[1] = vpMath::rad(-90); // q2
116  repos[2] = vpMath::rad(180); // q3
117  repos[4] = vpMath::rad(90); // q5
118 
120 
121  vpColVector q;
123 
124  std::cout << "q: " << q.t() << std::endl;
125 
126  vpHomogeneousMatrix fMw, fMe, fMt, cMe;
127  robot.get_fMw(q, fMw);
128  robot.get_fMe(q, fMe);
129  robot.get_fMc(q, fMt);
130  robot.get_cMe(cMe);
131 
132  std::cout << "fMw:\n" << fMw << std::endl;
133  std::cout << "fMe:\n" << fMe << std::endl;
134  std::cout << "fMt:\n" << fMt << std::endl;
135  std::cout << "eMc:\n" << cMe.inverse() << std::endl;
136 
137  //********* Check if retrieved eMt transformation is the one that was set 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 -1;
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 set
152 
153  std::cout << "eMc:\n" << cMe.inverse() << std::endl;
154  // Compare pose
155  std::cout << "Compare pose eMt and eMc:" << std::endl;
156  if (! pose_equal(eMt, cMe.inverse(), 1e-4)) {
157  std::cout << " Error: Pose eMc differ" << std::endl;
158  std::cout << "\nTest failed" << std::endl;
159  return -1;
160  }
161  std::cout << " They are the same, we can continue" << std::endl;
162  }
163 
164  //********* Check if position in reference frame is equal to fMt
165  if (1) {
166  vpColVector f_pose_t; // translation vector + rxyz vector
167  robot.getPosition(vpRobot::REFERENCE_FRAME, f_pose_t);
168  // Compute homogeneous transformation
169  vpTranslationVector f_t_t;
170  vpRxyzVector f_rxyz_t;
171  for (unsigned int i=0; i<3; i++) {
172  f_t_t[i] = f_pose_t[i];
173  f_rxyz_t[i] = f_pose_t[i+3];
174  }
175  vpHomogeneousMatrix fMt_(f_t_t, vpRotationMatrix(f_rxyz_t));
176  std::cout << "fMt_ (from ref frame):\n" << fMt_ << std::endl;
177 
178  std::cout << "Compare pose fMt and fMt_:" << std::endl;
179  if (! pose_equal(fMt, fMt_, 1e-4)) {
180  std::cout << " Error: Pose fMt differ" << std::endl;
181  std::cout << "\nTest failed" << std::endl;
182  return -1;
183  }
184  std::cout << " They are the same, we can continue" << std::endl;
185  }
186 
187  //********* Test inverse kinematics
188  if (1) {
189  vpColVector q1;
190  robot.getInverseKinematics(fMt, q1);
191 
192  std::cout << "Move robot in joint (the robot should not move)" << std::endl;
195 
196  vpColVector q2;
198  std::cout << "Reach joint position q2: " << q2.t() << std::endl;
199 
200  std::cout << "Compare joint position q and q2:" << std::endl;
201  if (! joint_equal(q, q2, 1e-4)) {
202  std::cout << " Error: Joint position differ" << std::endl;
203  std::cout << "\nTest failed" << std::endl;
204  return -1;
205  }
206  std::cout << " They are the same, we can continue" << std::endl;
207  }
208 
209  //********* Check if fMt position can be set in reference frame
210  if (1) {
211  vpColVector f_pose_t(6);
213  vpRxyzVector f_rxyz_t(fMt.getRotationMatrix());
214  for (unsigned int i=0; i<3; i++) {
215  f_pose_t[i] = f_t_t[i];
216  f_pose_t[i+3] = f_rxyz_t[i];
217  }
218 
219  std::cout << "Move robot in reference frame (the robot should not move)" << std::endl;
220  robot.setPosition(vpRobot::REFERENCE_FRAME, f_pose_t);
221  vpColVector q3;
223  std::cout << "Reach joint position q3: " << q3.t() << std::endl;
224  std::cout << "Compare joint position q and q3:" << std::endl;
225  if (! joint_equal(q, q3, 1e-4)) {
226  std::cout << " Error: Joint position differ" << std::endl;
227  std::cout << "\nTest failed" << std::endl;
228  return -1;
229  }
230  std::cout << " They are the same, we can continue" << std::endl;
231  }
232 
233  //********* Position control in tool frame
234  if (1) {
235  // from the current position move the tool frame
237  //tMt[0][3] = 0.05; // along x_t
238  tMt[1][3] = 0.05; // along y_t
239  // tMt[2][3] = 0.05; // along z_t
240 
241  vpHomogeneousMatrix fMt_ = fMt*tMt; // New position to reach
242  robot.getInverseKinematics(fMt_, q);
243 
244  std::cout << "fMt_:\n" << fMt_ << std::endl;
245 
246  std::cout << "Move robot in joint position to reach fMt_" << std::endl;
249 
250  vpPoseVector fpt_;
252 
253  std::cout << "fpt_:\n" << vpHomogeneousMatrix(fpt_) << std::endl;
254 
255  std::cout << "Compare pose fMt_ and fpt_:" << std::endl;
256  if (! pose_equal(fMt_, vpHomogeneousMatrix(fpt_), 1e-4)) {
257  std::cout << " Error: Pose fMt_ differ" << std::endl;
258  std::cout << "\nTest failed" << std::endl;
259  return -1;
260  }
261  std::cout << " They are the same, we can continue" << std::endl;
262  }
263 
264  //********* Velocity control in tool frame along z
265  if (1){
266  double t_init = vpTime::measureTimeMs();
267  vpColVector v_t(6);
268  v_t = 0;
269  //v_t[2] = 0.01; // translation velocity along z_t
270  v_t[5] = vpMath::rad(5); // rotation velocity along z_t
271 
272  std::cout << "Move robot in camera velocity" << std::endl;
274  while(vpTime::measureTimeMs() - t_init < 6000) {
275  //std::cout << "send vel: " << v_t() << std::endl;
277  }
278  }
279 
280  //********* Velocity control in tool frame along z using joint velocity
281  if (1){
282  // We need to stop the robot before changing velocity control from joint to cartesian
284  vpVelocityTwistMatrix tVe(eMt.inverse());
285  vpMatrix eJe;
286 
287  double t_init = vpTime::measureTimeMs();
288  vpColVector v_t(6), q_dot;
289  v_t = 0;
290  //v_t[2] = -0.01; // translation velocity along z_t
291  v_t[5] = vpMath::rad(-5); // rotation velocity along z_t
292 
293  std::cout << "Move robot in joint velocity" << std::endl;
295  while(vpTime::measureTimeMs() - t_init < 6000) {
296  robot.get_eJe(eJe);
297  vpMatrix tJt = tVe * eJe;
298  q_dot = tJt.pseudoInverse() * v_t;
299  //std::cout << "send vel: " << q_dot.t() << std::endl;
301  }
302  }
303 
304 
305  //********* Velocity control in tool frame along x
306  if (1){
308  double t_init = vpTime::measureTimeMs();
309  vpColVector v_t(6);
310  v_t = 0;
311  v_t[3] = vpMath::rad(5); // rotation velocity along x_t
312 
313  std::cout << "Move robot in camera velocity" << std::endl;
315  while(vpTime::measureTimeMs() - t_init < 3000) {
316  //std::cout << "send vel: " << v_t() << std::endl;
318  }
319  }
320 
321  //********* Velocity control in tool frame along x using joint velocity
322  if (1){
323  // We need to stop the robot before changing velocity control from joint to cartesian
325  vpVelocityTwistMatrix tVe(eMt.inverse());
326  vpMatrix eJe;
327 
328  double t_init = vpTime::measureTimeMs();
329  vpColVector v_t(6), q_dot;
330  v_t = 0;
331  v_t[3] = vpMath::rad(-5); // rotation velocity along x_t
332 
333  std::cout << "Move robot in joint velocity" << std::endl;
335  while(vpTime::measureTimeMs() - t_init < 3000) {
336  robot.get_eJe(eJe);
337  vpMatrix tJt = tVe * eJe;
338  q_dot = tJt.pseudoInverse() * v_t;
339  //std::cout << "send vel: " << q_dot.t() << std::endl;
341  }
342  }
343 
344  //********* Position control in tool frame
345  if (1) {
347  // get current position
349 
350  robot.get_fMc(q, fMt);
351 
352  vpHomogeneousMatrix tMt; // initialized to identity
353  //tMt[0][3] = -0.05; // along x_t
354  tMt[1][3] = -0.05; // along y_t
355  // tMt[2][3] = -0.05; // along z_t
356 
357  robot.getInverseKinematics(fMt*tMt, q);
358 
359  std::cout << "Move robot in joint position" << std::endl;
362  }
363  std::cout << "The end" << std::endl;
364  std::cout << "Test succeed" << std::endl;
365  }
366  catch(vpException &e) {
367  std::cout << "Test failed with exception: " << e.getMessage() << std::endl;
368  }
369 }
370 
371 #else
372 int main()
373 {
374  std::cout << "The real Viper650 robot controller is not available." << std::endl;
375  return 0;
376 }
377 
378 #endif
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw) const
Definition: vpViper.cpp:829
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Control of Irisa's Viper S650 robot named Viper650.
Initialize the position controller.
Definition: vpRobot.h:69
error that can be emited by ViSP classes.
Definition: vpException.h:73
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:156
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:93
Implementation of a rotation matrix and operations on such kind of matrices.
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Initialize the velocity controller.
Definition: vpRobot.h:68
vpRotationMatrix getRotationMatrix() const
vpTranslationVector getTranslationVector() const
vpRowVector t() const
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:616
const char * getMessage(void) const
Definition: vpException.cpp:97
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpViper.cpp:733
Implementation of a velocity twist matrix and operations on such kind of matrices.
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:578
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
Definition: vpMath.h:104
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
vpHomogeneousMatrix inverse() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
Definition: vpMatrix.cpp:1741
void get_cMe(vpHomogeneousMatrix &cMe) const
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void get_eJe(vpMatrix &eJe)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)