Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpSimulatorViper850.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  * Class which provides a simulator for the robot Viper850.
32  *
33  * Authors:
34  * Nicolas Melchior
35  *
36  *****************************************************************************/
37 
38 
39 
40 #include <visp3/robot/vpSimulatorViper850.h>
41 
42 #if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD))
43 
44 #include <visp3/core/vpTime.h>
45 #include <visp3/core/vpImagePoint.h>
46 #include <visp3/core/vpPoint.h>
47 #include <visp3/core/vpMeterPixelConversion.h>
48 #include <visp3/core/vpIoTools.h>
49 #include <cmath> // std::fabs
50 #include <limits> // numeric_limits
51 #include <string>
52 
53 #include "../wireframe-simulator/vpBound.h"
54 #include "../wireframe-simulator/vpVwstack.h"
55 #include "../wireframe-simulator/vpRfstack.h"
56 #include "../wireframe-simulator/vpScene.h"
57 
59 
65  q_prev_getdis(), first_time_getdis(true), positioningVelocity(defaultPositioningVelocity),
66  zeroPos(), reposPos(), toolCustom(false), arm_dir()
67 {
68  init();
69  initDisplay();
70 
72 
73  #if defined(_WIN32)
74 # ifdef WINRT_8_1
75  mutex_fMi = CreateMutexEx(NULL, NULL, 0, NULL);
76  mutex_artVel = CreateMutexEx(NULL, NULL, 0, NULL);
77  mutex_artCoord = CreateMutexEx(NULL, NULL, 0, NULL);
78  mutex_velocity = CreateMutexEx(NULL, NULL, 0, NULL);
79  mutex_display = CreateMutexEx(NULL, NULL, 0, NULL);
80 # else
81  mutex_fMi = CreateMutex(NULL, FALSE, NULL);
82  mutex_artVel = CreateMutex(NULL, FALSE, NULL);
83  mutex_artCoord = CreateMutex(NULL, FALSE, NULL);
84  mutex_velocity = CreateMutex(NULL, FALSE, NULL);
85  mutex_display = CreateMutex(NULL, FALSE, NULL);
86 # endif
87 
88 
89  DWORD dwThreadIdArray;
90  hThread = CreateThread(
91  NULL, // default security attributes
92  0, // use default stack size
93  launcher, // thread function name
94  this, // argument to thread function
95  0, // use default creation flags
96  &dwThreadIdArray); // returns the thread identifier
97  #elif defined (VISP_HAVE_PTHREAD)
98  pthread_mutex_init(&mutex_fMi, NULL);
99  pthread_mutex_init(&mutex_artVel, NULL);
100  pthread_mutex_init(&mutex_artCoord, NULL);
101  pthread_mutex_init(&mutex_velocity, NULL);
102  pthread_mutex_init(&mutex_display, NULL);
103 
104  pthread_attr_init(&attr);
105  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
106 
107  pthread_create(&thread, NULL, launcher, (void *)this);
108  #endif
109 
110  compute_fMi();
111 }
112 
120  : vpRobotWireFrameSimulator(do_display),
121  q_prev_getdis(), first_time_getdis(true), positioningVelocity(defaultPositioningVelocity),
122  zeroPos(), reposPos(), toolCustom(false), arm_dir()
123 {
124  init();
125  initDisplay();
126 
128 
129  #if defined(_WIN32)
130 # ifdef WINRT_8_1
131  mutex_fMi = CreateMutexEx(NULL, NULL, 0, NULL);
132  mutex_artVel = CreateMutexEx(NULL, NULL, 0, NULL);
133  mutex_artCoord = CreateMutexEx(NULL, NULL, 0, NULL);
134  mutex_velocity = CreateMutexEx(NULL, NULL, 0, NULL);
135  mutex_display = CreateMutexEx(NULL, NULL, 0, NULL);
136 # else
137  mutex_fMi = CreateMutex(NULL,FALSE,NULL);
138  mutex_artVel = CreateMutex(NULL,FALSE,NULL);
139  mutex_artCoord = CreateMutex(NULL,FALSE,NULL);
140  mutex_velocity = CreateMutex(NULL,FALSE,NULL);
141  mutex_display = CreateMutex(NULL,FALSE,NULL);
142 # endif
143 
144  DWORD dwThreadIdArray;
145  hThread = CreateThread(
146  NULL, // default security attributes
147  0, // use default stack size
148  launcher, // thread function name
149  this, // argument to thread function
150  0, // use default creation flags
151  &dwThreadIdArray); // returns the thread identifier
152  #elif defined(VISP_HAVE_PTHREAD)
153  pthread_mutex_init(&mutex_fMi, NULL);
154  pthread_mutex_init(&mutex_artVel, NULL);
155  pthread_mutex_init(&mutex_artCoord, NULL);
156  pthread_mutex_init(&mutex_velocity, NULL);
157  pthread_mutex_init(&mutex_display, NULL);
158 
159  pthread_attr_init(&attr);
160  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
161 
162  pthread_create(&thread, NULL, launcher, (void *)this);
163  #endif
164 
165  compute_fMi();
166 }
167 
172 {
173  robotStop = true;
174 
175  #if defined(_WIN32)
176 # if defined(WINRT_8_1)
177  WaitForSingleObjectEx(hThread, INFINITE, FALSE);
178 # else // pure win32
179  WaitForSingleObject(hThread, INFINITE);
180 # endif
181  CloseHandle(hThread);
182  CloseHandle(mutex_fMi);
183  CloseHandle(mutex_artVel);
184  CloseHandle(mutex_artCoord);
185  CloseHandle(mutex_velocity);
186  CloseHandle(mutex_display);
187  #elif defined(VISP_HAVE_PTHREAD)
188  pthread_attr_destroy(&attr);
189  pthread_join(thread, NULL);
190  pthread_mutex_destroy(&mutex_fMi);
191  pthread_mutex_destroy(&mutex_artVel);
192  pthread_mutex_destroy(&mutex_artCoord);
193  pthread_mutex_destroy(&mutex_velocity);
194  pthread_mutex_destroy(&mutex_display);
195  #endif
196 
197  if (robotArms != NULL)
198  {
199  // free_Bound_scene (&(camera));
200  for(int i = 0; i < 6; i++)
201  free_Bound_scene (&(robotArms[i]));
202  }
203 
204  delete[] robotArms;
205  delete[] fMi;
206 }
207 
216 void
218 {
219  // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
220  // VISP_ROBOT_ARMS_DIR may contain multiple locations separated by ";"
221  std::vector<std::string> arm_dirs = vpIoTools::splitChain(std::string(VISP_ROBOT_ARMS_DIR), std::string(";"));
222  bool armDirExists = false;
223  for(size_t i=0; i < arm_dirs.size(); i++)
224  if (vpIoTools::checkDirectory(arm_dirs[i]) == true) { // directory exists
225  arm_dir = arm_dirs[i];
226  armDirExists = true;
227  break;
228  }
229  if (! armDirExists) {
230  try {
231  arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
232  std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
233  }
234  catch (...) {
235  std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
236  }
237  }
238 
240  toolCustom = false;
241 
242  size_fMi = 8;
243  fMi = new vpHomogeneousMatrix[8];
246 
247  zeroPos.resize(njoint);
248  zeroPos = 0;
249  zeroPos[1] = -M_PI/2; zeroPos[2] = M_PI;
250  reposPos.resize(njoint);
251  reposPos = 0;
252  reposPos[1] = -M_PI/2; reposPos[2] = M_PI; reposPos[4] = M_PI/2;
253 
254  artCoord = reposPos;
255  artVel = 0;
256 
257  q_prev_getdis.resize(njoint);
258  q_prev_getdis = 0;
259  first_time_getdis = true;
260 
261  positioningVelocity = defaultPositioningVelocity ;
262 
265 
266  // Software joint limits in radians
267  //joint_min.resize(njoint);
268  joint_min[0] = vpMath::rad(-50);
269  joint_min[1] = vpMath::rad(-135);
270  joint_min[2] = vpMath::rad(-40);
271  joint_min[3] = vpMath::rad(-190);
272  joint_min[4] = vpMath::rad(-110);
273  joint_min[5] = vpMath::rad(-184);
274  //joint_max.resize(njoint);
275  joint_max[0] = vpMath::rad(50);
276  joint_max[1] = vpMath::rad(-40);
277  joint_max[2] = vpMath::rad(215);
278  joint_max[3] = vpMath::rad(190);
279  joint_max[4] = vpMath::rad(110);
280  joint_max[5] = vpMath::rad(184);
281 }
282 
286 void
288 {
289  robotArms = NULL;
290  robotArms = new Bound_scene[6];
291  initArms();
293  cameraParam.initPersProjWithoutDistortion (558.5309599, 556.055053, 320, 240);
295  vpCameraParameters tmp;
296  getCameraParameters(tmp,640,480);
297  px_int = tmp.get_px();
298  py_int = tmp.get_py();
299  sceneInitialized = true;
300 }
301 
302 
318 void
321 {
322  this->projModel = proj_model;
323 
324  // Use here default values of the robot constant parameters.
325  switch (tool) {
327  erc[0] = vpMath::rad(0.07); // rx
328  erc[1] = vpMath::rad(2.76); // ry
329  erc[2] = vpMath::rad(-91.50); // rz
330  etc[0] = -0.0453; // tx
331  etc[1] = 0.0005; // ty
332  etc[2] = 0.0728; // tz
333 
334  setCameraParameters(vpCameraParameters(1232.0, 1233.0, 320, 240));
335  break;
336  }
338  erc[0] = vpMath::rad(0.1527764261); // rx
339  erc[1] = vpMath::rad(1.285092455); // ry
340  erc[2] = vpMath::rad(-90.75777848); // rz
341  etc[0] = -0.04558630174; // tx
342  etc[1] = -0.00134326752; // ty
343  etc[2] = 0.001000828017; // tz
344 
345  setCameraParameters(vpCameraParameters(868.0, 869.0, 320, 240));
346  break;
347  }
351  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
352  break;
353  }
354  }
355 
356  vpRotationMatrix eRc(erc);
357  this->eMc.buildFrom(etc, eRc);
358 
359  setToolType(tool);
360  return ;
361 }
362 
373 void
375  const unsigned int &image_width,
376  const unsigned int &image_height)
377 {
378  if (toolCustom)
379  {
380  vpCameraParameters(px_int,py_int,image_width/2,image_height/2);
381  }
382  // Set default parameters
383  switch (getToolType()) {
385  // Set default intrinsic camera parameters for 640x480 images
386  if (image_width == 640 && image_height == 480)
387  {
388  std::cout << "Get default camera parameters for camera \""
389  << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl;
390  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240);
391  }
392  else {
393  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
394  }
395  break;
396  }
398  // Set default intrinsic camera parameters for 640x480 images
399  if (image_width == 640 && image_height == 480) {
400  std::cout << "Get default camera parameters for camera \""
401  << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl;
402  cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240);
403  }
404  else {
405  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
406  }
407  break;
408  }
412  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
413  break;
414  }
415  }
416  return;
417 }
418 
427 void
429  const vpImage<unsigned char> &I_)
430 {
431  getCameraParameters(cam,I_.getWidth(),I_.getHeight());
432 }
433 
442 void
444  const vpImage<vpRGBa> &I_)
445 {
446  getCameraParameters(cam,I_.getWidth(),I_.getHeight());
447 }
448 
449 
455 void
457 {
458  px_int = cam.get_px();
459  py_int = cam.get_py();
460  toolCustom = true;
461 }
462 
463 
467 void
469 {
470  double tcur_1 = tcur;// temporary variable used to store the last time since the last command
471 
472  while (!robotStop)
473  {
474  //Get current time
475  tprev = tcur_1;
477 
478 
480  setVelocityCalled = false;
482 
483  double ellapsedTime = (tcur - tprev) * 1e-3;
484  if(constantSamplingTimeMode){//if we want a constant velocity, we force the ellapsed time to the given samplingTime
485  ellapsedTime = getSamplingTime(); // in second
486  }
487 
488  vpColVector articularCoordinates = get_artCoord();
489  vpColVector articularVelocities = get_artVel();
490 
491  if (jointLimit)
492  {
493  double art = articularCoordinates[jointLimitArt-1] + ellapsedTime*articularVelocities[jointLimitArt-1];
494  if (art <= joint_min[jointLimitArt-1] || art >= joint_max[jointLimitArt-1]) {
495  if (verbose_) {
496  std::cout << "Joint " << jointLimitArt-1
497  << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt-1]) << " < " << vpMath::deg(art) << " < " << vpMath::deg(joint_max[jointLimitArt-1]) << std::endl;
498  }
499  articularVelocities = 0.0;
500  }
501  else
502  jointLimit = false;
503  }
504 
505  articularCoordinates[0] = articularCoordinates[0] + ellapsedTime*articularVelocities[0];
506  articularCoordinates[1] = articularCoordinates[1] + ellapsedTime*articularVelocities[1];
507  articularCoordinates[2] = articularCoordinates[2] + ellapsedTime*articularVelocities[2];
508  articularCoordinates[3] = articularCoordinates[3] + ellapsedTime*articularVelocities[3];
509  articularCoordinates[4] = articularCoordinates[4] + ellapsedTime*articularVelocities[4];
510  articularCoordinates[5] = articularCoordinates[5] + ellapsedTime*articularVelocities[5];
511 
512  int jl = isInJointLimit();
513 
514  if (jl != 0 && jointLimit == false)
515  {
516  if (jl < 0)
517  ellapsedTime = (joint_min[(unsigned int)(-jl-1)] - articularCoordinates[(unsigned int)(-jl-1)])/(articularVelocities[(unsigned int)(-jl-1)]);
518  else
519  ellapsedTime = (joint_max[(unsigned int)(jl-1)] - articularCoordinates[(unsigned int)(jl-1)])/(articularVelocities[(unsigned int)(jl-1)]);
520 
521  for (unsigned int i = 0; i < 6; i++)
522  articularCoordinates[i] = articularCoordinates[i] + ellapsedTime*articularVelocities[i];
523 
524  jointLimit = true;
525  jointLimitArt = (unsigned int)fabs((double)jl);
526  }
527 
528  set_artCoord(articularCoordinates);
529  set_artVel(articularVelocities);
530 
531  compute_fMi();
532 
533  if (displayAllowed)
534  {
538  }
539 
541  {
542  while (get_displayBusy()) vpTime::wait(2);
544  set_displayBusy(false);
545  }
546 
547 
549  {
550  vpHomogeneousMatrix fMit[8];
551  get_fMi(fMit);
552 
553  //vpDisplay::displayFrame(I,getExternalCameraPosition ()*fMi[6],cameraParam,0.2,vpColor::none);
554 
555  vpImagePoint iP, iP_1;
556  vpPoint pt(0,0,0);
557 
560  pt.track(getExternalCameraPosition ()*fMit[0]);
563  for (int k = 1; k < 7; k++)
564  {
565  pt.track(getExternalCameraPosition ()*fMit[k-1]);
567 
568  pt.track(getExternalCameraPosition ()*fMit[k]);
570 
572  }
574  }
575 
577 
578  vpTime::wait( tcur, 1000 * getSamplingTime() );
579  tcur_1 = tcur;
580  }else{
582  }
583  }
584 }
585 
596 void
598 {
599  //vpColVector q = get_artCoord();
600  vpColVector q(6);//; = get_artCoord();
601  q = get_artCoord();
602 
603  vpHomogeneousMatrix fMit[8];
604 
605  double q1 = q[0];
606  double q2 = q[1];
607  double q3 = q[2];
608  double q4 = q[3];
609  double q5 = q[4];
610  double q6 = q[5];
611 
612  double c1 = cos(q1);
613  double s1 = sin(q1);
614  double c2 = cos(q2);
615  double s2 = sin(q2);
616  double c23 = cos(q2+q3);
617  double s23 = sin(q2+q3);
618  double c4 = cos(q4);
619  double s4 = sin(q4);
620  double c5 = cos(q5);
621  double s5 = sin(q5);
622  double c6 = cos(q6);
623  double s6 = sin(q6);
624 
625  fMit[0][0][0] = c1;
626  fMit[0][1][0] = s1;
627  fMit[0][2][0] = 0;
628  fMit[0][0][1] = 0;
629  fMit[0][1][1] = 0;
630  fMit[0][2][1] = -1;
631  fMit[0][0][2] = -s1;
632  fMit[0][1][2] = c1;
633  fMit[0][2][2] = 0;
634  fMit[0][0][3] = a1*c1;
635  fMit[0][1][3] = a1*s1;
636  fMit[0][2][3] = d1;
637 
638  fMit[1][0][0] = c1*c2;
639  fMit[1][1][0] = s1*c2;
640  fMit[1][2][0] = -s2;
641  fMit[1][0][1] = -c1*s2;
642  fMit[1][1][1] = -s1*s2;
643  fMit[1][2][1] = -c2;
644  fMit[1][0][2] = -s1;
645  fMit[1][1][2] = c1;
646  fMit[1][2][2] = 0;
647  fMit[1][0][3] = c1*(a2*c2+a1);
648  fMit[1][1][3] = s1*(a2*c2+a1);
649  fMit[1][2][3] = d1-a2*s2;
650 
651  double quickcomp1 = a3*c23-a2*c2-a1;
652 
653  fMit[2][0][0] = -c1*c23;
654  fMit[2][1][0] = -s1*c23;
655  fMit[2][2][0] = s23;
656  fMit[2][0][1] = s1;
657  fMit[2][1][1] = -c1;
658  fMit[2][2][1] = 0;
659  fMit[2][0][2] = c1*s23;
660  fMit[2][1][2] = s1*s23;
661  fMit[2][2][2] = c23;
662  fMit[2][0][3] = -c1*quickcomp1;
663  fMit[2][1][3] = -s1*quickcomp1;
664  fMit[2][2][3] = a3*s23-a2*s2+d1;
665 
666  double quickcomp2 = c1*(s23*d4 - quickcomp1);
667  double quickcomp3 = s1*(s23*d4 - quickcomp1);
668 
669  fMit[3][0][0] = -c1*c23*c4+s1*s4;
670  fMit[3][1][0] = -s1*c23*c4-c1*s4;
671  fMit[3][2][0] = s23*c4;
672  fMit[3][0][1] = c1*s23;
673  fMit[3][1][1] = s1*s23;
674  fMit[3][2][1] = c23;
675  fMit[3][0][2] = -c1*c23*s4-s1*c4;
676  fMit[3][1][2] = -s1*c23*s4+c1*c4;
677  fMit[3][2][2] = s23*s4;
678  fMit[3][0][3] = quickcomp2;
679  fMit[3][1][3] = quickcomp3;
680  fMit[3][2][3] = c23*d4+a3*s23-a2*s2+d1;
681 
682  fMit[4][0][0] = c1*(s23*s5-c5*c23*c4)+s1*c5*s4;
683  fMit[4][1][0] = s1*(s23*s5-c5*c23*c4)-c1*c5*s4;
684  fMit[4][2][0] = s23*c4*c5+c23*s5;
685  fMit[4][0][1] = c1*c23*s4+s1*c4;
686  fMit[4][1][1] = s1*c23*s4-c1*c4;
687  fMit[4][2][1] = -s23*s4;
688  fMit[4][0][2] = c1*(s23*c5+s5*c23*c4)-s1*s5*s4;
689  fMit[4][1][2] = s1*(s23*c5+s5*c23*c4)+c1*s5*s4;
690  fMit[4][2][2] = -s23*c4*s5+c23*c5;
691  fMit[4][0][3] = quickcomp2;
692  fMit[4][1][3] = quickcomp3;
693  fMit[4][2][3] = c23*d4+a3*s23-a2*s2+d1;
694 
695  fMit[5][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
696  fMit[5][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
697  fMit[5][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
698  fMit[5][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
699  fMit[5][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
700  fMit[5][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
701  fMit[5][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
702  fMit[5][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
703  fMit[5][2][2] = -s23*c4*s5+c23*c5;
704  fMit[5][0][3] = quickcomp2;
705  fMit[5][1][3] = quickcomp3;
706  fMit[5][2][3] = s23*a3+c23*d4-a2*s2+d1;
707 
708  fMit[6][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
709  fMit[6][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
710  fMit[6][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
711  fMit[6][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
712  fMit[6][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
713  fMit[6][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
714  fMit[6][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
715  fMit[6][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
716  fMit[6][2][2] = -s23*c4*s5+c23*c5;
717  fMit[6][0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
718  fMit[6][1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
719  fMit[6][2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
720 
722  get_cMe(cMe);
723  cMe = cMe.inverse();
724 // fMit[7] = fMit[6] * cMe;
725  vpViper::get_fMc(q,fMit[7]);
726 
727  #if defined(_WIN32)
728 # if defined(WINRT_8_1)
729  WaitForSingleObjectEx(mutex_fMi, INFINITE, FALSE);
730 # else // pure win32
731  WaitForSingleObject(mutex_fMi, INFINITE);
732 # endif
733  for (int i = 0; i < 8; i++)
734  fMi[i] = fMit[i];
735  ReleaseMutex(mutex_fMi);
736  #elif defined(VISP_HAVE_PTHREAD)
737  pthread_mutex_lock (&mutex_fMi);
738  for (int i = 0; i < 8; i++)
739  fMi[i] = fMit[i];
740  pthread_mutex_unlock (&mutex_fMi);
741  #endif
742 }
743 
744 
752 {
753  switch (newState) {
754  case vpRobot::STATE_STOP: {
755  // Start primitive STOP only if the current state is Velocity
757  stopMotion();
758  }
759  break;
760  }
763  std::cout << "Change the control mode from velocity to position control.\n";
764  stopMotion();
765  }
766  else {
767  //std::cout << "Change the control mode from stop to position control.\n";
768  }
769  break;
770  }
773  std::cout << "Change the control mode from stop to velocity control.\n";
774  }
775  break;
776  }
778  default:
779  break ;
780  }
781 
782  return vpRobot::setRobotState (newState);
783 }
784 
854 void
856 {
858  vpERROR_TRACE ("Cannot send a velocity to the robot "
859  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
861  "Cannot send a velocity to the robot "
862  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
863  }
864 
865  vpColVector vel_sat(6);
866 
867  double scale_sat = 1;
868  double vel_trans_max = getMaxTranslationVelocity();
869  double vel_rot_max = getMaxRotationVelocity();
870 
871  double vel_abs; // Absolute value
872 
873  // Velocity saturation
874  switch(frame)
875  {
876  // saturation in cartesian space
877  case vpRobot::CAMERA_FRAME :
879  {
880  if (vel.getRows() != 6)
881  {
882  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
883  throw;
884  }
885 
886  for (unsigned int i = 0 ; i < 3; ++ i)
887  {
888  vel_abs = fabs (vel[i]);
889  if (vel_abs > vel_trans_max && !jointLimit)
890  {
891  vel_trans_max = vel_abs;
892  vpERROR_TRACE ("Excess velocity %g m/s in TRANSLATION "
893  "(axis nr. %d).", vel[i], i+1);
894  }
895 
896  vel_abs = fabs (vel[i+3]);
897  if (vel_abs > vel_rot_max && !jointLimit) {
898  vel_rot_max = vel_abs;
899  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
900  "(axis nr. %d).", vel[i+3], i+4);
901  }
902  }
903 
904  double scale_trans_sat = 1;
905  double scale_rot_sat = 1;
906  if (vel_trans_max > getMaxTranslationVelocity())
907  scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
908 
909  if (vel_rot_max > getMaxRotationVelocity())
910  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
911 
912  if ( (scale_trans_sat < 1) || (scale_rot_sat < 1) )
913  {
914  if (scale_trans_sat < scale_rot_sat)
915  scale_sat = scale_trans_sat;
916  else
917  scale_sat = scale_rot_sat;
918  }
919  break;
920  }
921 
922  // saturation in joint space
924  {
925  if (vel.getRows() != 6)
926  {
927  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
928  throw;
929  }
930  for (unsigned int i = 0 ; i < 6; ++ i)
931  {
932  vel_abs = fabs (vel[i]);
933  if (vel_abs > vel_rot_max && !jointLimit)
934  {
935  vel_rot_max = vel_abs;
936  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
937  "(axis nr. %d).", vel[i], i+1);
938  }
939  }
940  double scale_rot_sat = 1;
941  if (vel_rot_max > getMaxRotationVelocity())
942  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
943  if ( scale_rot_sat < 1 )
944  scale_sat = scale_rot_sat;
945  break;
946  }
947  case vpRobot::MIXT_FRAME :
948  {
949  break;
950  }
951  }
952 
953  set_velocity (vel * scale_sat);
954  setRobotFrame (frame);
955  setVelocityCalled = true;
956 }
957 
958 
962 void
964 {
966 
967  double vel_rot_max = getMaxRotationVelocity();
968 
969  vpColVector articularCoordinates = get_artCoord();
970  vpColVector velocityframe = get_velocity();
971  vpColVector articularVelocity;
972 
973  switch(frame)
974  {
975  case vpRobot::CAMERA_FRAME :
976  {
977  vpMatrix eJe_;
979  vpViper850::get_eJe(articularCoordinates,eJe_);
980  eJe_ = eJe_.pseudoInverse();
982  singularityTest(articularCoordinates,eJe_);
983  articularVelocity = eJe_*eVc*velocityframe;
984  set_artVel (articularVelocity);
985  break;
986  }
988  {
989  vpMatrix fJe_;
990  vpViper850::get_fJe(articularCoordinates,fJe_);
991  fJe_ = fJe_.pseudoInverse();
993  singularityTest(articularCoordinates,fJe_);
994  articularVelocity = fJe_*velocityframe;
995  set_artVel (articularVelocity);
996  break;
997  }
999  {
1000  articularVelocity = velocityframe;
1001  set_artVel (articularVelocity);
1002  break;
1003  }
1004  case vpRobot::MIXT_FRAME :
1005  {
1006  break;
1007  }
1008  }
1009 
1010  switch(frame)
1011  {
1012  case vpRobot::CAMERA_FRAME :
1014  {
1015  for (unsigned int i = 0 ; i < 6; ++ i)
1016  {
1017  double vel_abs = fabs (articularVelocity[i]);
1018  if (vel_abs > vel_rot_max && !jointLimit)
1019  {
1020  vel_rot_max = vel_abs;
1021  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
1022  "(axis nr. %d).", articularVelocity[i], i+1);
1023  }
1024  }
1025  double scale_rot_sat = 1;
1026  double scale_sat = 1;
1027 
1028  if (vel_rot_max > getMaxRotationVelocity())
1029  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
1030  if ( scale_rot_sat < 1 )
1031  scale_sat = scale_rot_sat;
1032 
1033  set_artVel(articularVelocity * scale_sat);
1034  break;
1035  }
1037  case vpRobot::MIXT_FRAME :
1038  {
1039  break;
1040  }
1041  }
1042 }
1043 
1044 
1091 void
1093 {
1094  vel.resize(6);
1095 
1096  vpColVector articularCoordinates = get_artCoord();
1097  vpColVector articularVelocity = get_artVel();
1098 
1099  switch(frame)
1100  {
1101  case vpRobot::CAMERA_FRAME :
1102  {
1103  vpMatrix eJe_;
1105  vpViper850::get_eJe(articularCoordinates,eJe_);
1106  vel = cVe*eJe_*articularVelocity;
1107  break ;
1108  }
1109  case vpRobot::ARTICULAR_FRAME :
1110  {
1111  vel = articularVelocity;
1112  break ;
1113  }
1114  case vpRobot::REFERENCE_FRAME :
1115  {
1116  vpMatrix fJe_;
1117  vpViper850::get_fJe(articularCoordinates,fJe_);
1118  vel = fJe_*articularVelocity;
1119  break ;
1120  }
1121  case vpRobot::MIXT_FRAME :
1122  {
1123  break ;
1124  }
1125  default:
1126  {
1127  vpERROR_TRACE ("Error in spec of vpRobot. "
1128  "Case not taken in account.");
1129  return;
1130  }
1131  }
1132 }
1133 
1150 void
1152 {
1153  timestamp = vpTime::measureTimeSecond();
1154  getVelocity(frame, vel);
1155 }
1156 
1201 {
1202  vpColVector vel(6);
1203  getVelocity (frame, vel);
1204 
1205  return vel;
1206 }
1207 
1222 {
1223  timestamp = vpTime::measureTimeSecond();
1224  vpColVector vel(6);
1225  getVelocity (frame, vel);
1226 
1227  return vel;
1228 }
1229 
1230 void
1232 {
1233  double vel_rot_max = getMaxRotationVelocity();
1234  double velmax = fabs(q[0]);
1235  for (unsigned int i = 1; i < 6; i++)
1236  {
1237  if (velmax < fabs(q[i]))
1238  velmax = fabs(q[i]);
1239  }
1240 
1241  double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax*100);
1242  q = q * alpha;
1243 }
1244 
1319 void
1321 {
1323  {
1324  vpERROR_TRACE ("Robot was not in position-based control\n"
1325  "Modification of the robot state");
1326  // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1327  }
1328 
1329  vpColVector articularCoordinates = get_artCoord();
1330 
1331  vpColVector error(6);
1332  double errsqr = 0;
1333  switch(frame)
1334  {
1335  case vpRobot::CAMERA_FRAME :
1336  {
1337  unsigned int nbSol;
1338  vpColVector qdes(6);
1339 
1340  vpTranslationVector txyz;
1341  vpRxyzVector rxyz;
1342  for (unsigned int i=0; i < 3; i++)
1343  {
1344  txyz[i] = q[i];
1345  rxyz[i] = q[i+3];
1346  }
1347 
1348  vpRotationMatrix cRc2(rxyz);
1349  vpHomogeneousMatrix cMc2(txyz, cRc2);
1350 
1351  vpHomogeneousMatrix fMc_;
1352  vpViper850::get_fMc(articularCoordinates, fMc_);
1353 
1354  vpHomogeneousMatrix fMc2 = fMc_ * cMc2;
1355 
1356  do
1357  {
1358  articularCoordinates = get_artCoord();
1359  qdes = articularCoordinates;
1360  nbSol = getInverseKinematics(fMc2, qdes, verbose_);
1361  setVelocityCalled = true;
1362  if (nbSol > 0)
1363  {
1364  error = qdes - articularCoordinates;
1365  errsqr = error.sumSquare();
1366  //findHighestPositioningSpeed(error);
1367  set_artVel(error);
1368  if (errsqr < 1e-4)
1369  {
1370  set_artCoord (qdes);
1371  error = 0;
1372  set_artVel(error);
1373  set_velocity(error);
1374  break;
1375  }
1376  }
1377  else
1378  {
1379  vpERROR_TRACE ("Positionning error.");
1381  "Position out of range.");
1382  }
1383  }while (errsqr > 1e-8 && nbSol > 0);
1384 
1385  break ;
1386  }
1387 
1389  {
1390  do
1391  {
1392  articularCoordinates = get_artCoord();
1393  error = q - articularCoordinates;
1394  errsqr = error.sumSquare();
1395  //findHighestPositioningSpeed(error);
1396  set_artVel(error);
1397  setVelocityCalled = true;
1398  if (errsqr < 1e-4)
1399  {
1400  set_artCoord (q);
1401  error = 0;
1402  set_artVel(error);
1403  set_velocity(error);
1404  break;
1405  }
1406  }while (errsqr > 1e-8);
1407  break ;
1408  }
1409 
1411  {
1412  unsigned int nbSol;
1413  vpColVector qdes(6);
1414 
1415  vpTranslationVector txyz;
1416  vpRxyzVector rxyz;
1417  for (unsigned int i=0; i < 3; i++)
1418  {
1419  txyz[i] = q[i];
1420  rxyz[i] = q[i+3];
1421  }
1422 
1423  vpRotationMatrix fRc(rxyz);
1424  vpHomogeneousMatrix fMc_(txyz, fRc);
1425 
1426  do
1427  {
1428  articularCoordinates = get_artCoord();
1429  qdes = articularCoordinates;
1430  nbSol = getInverseKinematics(fMc_, qdes, verbose_);
1431  if (nbSol > 0)
1432  {
1433  error = qdes - articularCoordinates;
1434  errsqr = error.sumSquare();
1435  //findHighestPositioningSpeed(error);
1436  set_artVel(error);
1437  setVelocityCalled = true;
1438  if (errsqr < 1e-4)
1439  {
1440  set_artCoord (qdes);
1441  error = 0;
1442  set_artVel(error);
1443  set_velocity(error);
1444  break;
1445  }
1446  }
1447  else
1448  vpERROR_TRACE ("Positionning error. Position unreachable");
1449  }while (errsqr > 1e-8 && nbSol > 0);
1450  break ;
1451  }
1452  case vpRobot::MIXT_FRAME:
1453  {
1454  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1456  "Positionning error: "
1457  "Mixt frame not implemented.");
1458  }
1459  }
1460 }
1461 
1526  const double pos1,
1527  const double pos2,
1528  const double pos3,
1529  const double pos4,
1530  const double pos5,
1531  const double pos6)
1532 {
1533  try{
1534  vpColVector position(6) ;
1535  position[0] = pos1 ;
1536  position[1] = pos2 ;
1537  position[2] = pos3 ;
1538  position[3] = pos4 ;
1539  position[4] = pos5 ;
1540  position[5] = pos6 ;
1541 
1542  setPosition(frame, position) ;
1543  }
1544  catch(...)
1545  {
1546  vpERROR_TRACE("Error caught");
1547  throw ;
1548  }
1549 }
1550 
1586 void vpSimulatorViper850::setPosition(const char *filename)
1587 {
1588  vpColVector q;
1589  bool ret;
1590 
1591  ret = this->readPosFile(filename, q);
1592 
1593  if (ret == false) {
1594  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1596  "Bad position in filename.");
1597  }
1600 }
1601 
1661 void
1663 {
1664  q.resize(6);
1665 
1666  switch(frame)
1667  {
1668  case vpRobot::CAMERA_FRAME :
1669  {
1670  q = 0;
1671  break ;
1672  }
1673 
1675  {
1676  q = get_artCoord();
1677  break ;
1678  }
1679 
1681  {
1682  vpHomogeneousMatrix fMc_;
1683  vpViper::get_fMc (get_artCoord(), fMc_);
1684 
1685  vpRotationMatrix fRc;
1686  fMc_.extract(fRc);
1687  vpRxyzVector rxyz(fRc);
1688 
1689  vpTranslationVector txyz;
1690  fMc_.extract(txyz);
1691 
1692  for (unsigned int i=0; i <3; i++)
1693  {
1694  q[i] = txyz[i];
1695  q[i+3] = rxyz[i];
1696  }
1697  break ;
1698  }
1699 
1700  case vpRobot::MIXT_FRAME:
1701  {
1702  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1704  "Positionning error: "
1705  "Mixt frame not implemented.");
1706  }
1707  }
1708 }
1709 
1736 void
1738 {
1739  timestamp = vpTime::measureTimeSecond();
1740  getPosition(frame, q);
1741 }
1742 
1743 
1754 void
1756  vpPoseVector &position)
1757 {
1758  vpColVector posRxyz;
1759  //recupere position en Rxyz
1760  this->getPosition(frame,posRxyz);
1761 
1762  //recupere le vecteur thetaU correspondant
1763  vpThetaUVector RtuVect(vpRxyzVector(posRxyz[3],posRxyz[4],posRxyz[5]));
1764 
1765  //remplit le vpPoseVector avec translation et rotation ThetaU
1766  for(unsigned int j=0;j<3;j++)
1767  {
1768  position[j]=posRxyz[j];
1769  position[j+3]=RtuVect[j];
1770  }
1771 }
1772 
1783 void
1785  vpPoseVector &position, double &timestamp)
1786 {
1787  timestamp = vpTime::measureTimeSecond();
1788  getPosition(frame, position);
1789 }
1790 
1797 void
1799 {
1800  if (limitMin.getRows() != 6 || limitMax.getRows() != 6)
1801  {
1802  vpTRACE("Joint limit vector has not a size of 6 !");
1803  return;
1804  }
1805 
1806  joint_min[0] = limitMin[0];
1807  joint_min[1] = limitMin[1];
1808  joint_min[2] = limitMin[2];
1809  joint_min[3] = limitMin[3];
1810  joint_min[4] = limitMin[4];
1811  joint_min[5] = limitMin[5];
1812 
1813  joint_max[0] = limitMax[0];
1814  joint_max[1] = limitMax[1];
1815  joint_max[2] = limitMax[2];
1816  joint_max[3] = limitMax[3];
1817  joint_max[4] = limitMax[4];
1818  joint_max[5] = limitMax[5];
1819 
1820 }
1821 
1827 bool
1829 {
1830  double q2 = q[1];
1831  double q3 = q[2];
1832  double q5 = q[4];
1833 
1834  double c2 = cos(q2);
1835  double c3 = cos(q3);
1836  double s3 = sin(q3);
1837  double c23 = cos(q2+q3);
1838  double s23 = sin(q2+q3);
1839  double s5 = sin(q5);
1840 
1841  bool cond1 = fabs(s5) < 1e-1;
1842  bool cond2 = fabs(a3*s3+c3*d4) < 1e-1;
1843  bool cond3 = fabs(a2*c2-a3*c23+s23*d4+a1) < 1e-1;
1844 
1845  if(cond1)
1846  {
1847  J[3][0] = 0;
1848  J[5][0] = 0;
1849  J[3][1] = 0;
1850  J[5][1] = 0;
1851  J[3][2] = 0;
1852  J[5][2] = 0;
1853  J[3][3] = 0;
1854  J[5][3] = 0;
1855  J[3][4] = 0;
1856  J[5][4] = 0;
1857  J[3][5] = 0;
1858  J[5][5] = 0;
1859  return true;
1860  }
1861 
1862  if(cond2)
1863  {
1864  J[1][0] = 0; J[2][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1865  J[1][1] = 0; J[2][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1866  J[1][2] = 0; J[2][2] = 0; J[3][2] = 0; J[4][2] = 0; J[5][2] = 0;
1867  return true;
1868  }
1869 
1870  if(cond3)
1871  {
1872  J[0][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1873  J[0][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1874  }
1875 
1876  return false;
1877 }
1878 
1882 int
1884 {
1885  int artNumb = 0;
1886  double diff = 0;
1887  double difft = 0;
1888 
1889  vpColVector articularCoordinates = get_artCoord();
1890 
1891  for (unsigned int i = 0; i < 6; i++)
1892  {
1893  if (articularCoordinates[i] <= joint_min[i])
1894  {
1895  difft = joint_min[i] - articularCoordinates[i];
1896  if (difft > diff)
1897  {
1898  diff = difft;
1899  artNumb = -(int)i-1;
1900  }
1901  }
1902  }
1903 
1904  for (unsigned int i = 0; i < 6; i++)
1905  {
1906  if (articularCoordinates[i] >= joint_max[i])
1907  {
1908  difft = articularCoordinates[i] - joint_max[i];
1909  if (difft > diff)
1910  {
1911  diff = difft;
1912  artNumb = (int)(i+1);
1913  }
1914  }
1915  }
1916 
1917  if (artNumb != 0)
1918  std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" <<std::endl;
1919 
1920  return artNumb;
1921 }
1922 
1934 void
1935 vpSimulatorViper850::getCameraDisplacement(vpColVector &displacement)
1936 {
1937  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
1938 }
1939 
1949 void
1950 vpSimulatorViper850::getArticularDisplacement(vpColVector &displacement)
1951 {
1953 }
1954 
1973 void
1975  vpColVector &displacement)
1976 {
1977  displacement.resize (6);
1978  displacement = 0;
1979  vpColVector q_cur(6);
1980 
1981  q_cur = get_artCoord();
1982 
1983  if ( ! first_time_getdis )
1984  {
1985  switch (frame)
1986  {
1987  case vpRobot::CAMERA_FRAME:
1988  {
1989  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
1990  return;
1991  }
1992 
1994  {
1995  displacement = q_cur - q_prev_getdis;
1996  break ;
1997  }
1998 
2000  {
2001  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2002  return;
2003  }
2004 
2005  case vpRobot::MIXT_FRAME:
2006  {
2007  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2008  return;
2009  }
2010  }
2011  }
2012  else
2013  {
2014  first_time_getdis = false;
2015  }
2016 
2017  // Memorize the joint position for the next call
2018  q_prev_getdis = q_cur;
2019 }
2020 
2082 bool
2083 vpSimulatorViper850::readPosFile(const std::string &filename, vpColVector &q)
2084 {
2085  std::ifstream fd(filename.c_str(), std::ios::in);
2086 
2087  if(! fd.is_open()) {
2088  return false;
2089  }
2090 
2091  std::string line;
2092  std::string key("R:");
2093  std::string id("#Viper850 - Position");
2094  bool pos_found = false;
2095  int lineNum = 0;
2096 
2097  q.resize(njoint);
2098 
2099  while(std::getline(fd, line)) {
2100  lineNum ++;
2101  if (lineNum == 1) {
2102  if(! (line.compare(0, id.size(), id) == 0)) { // check if Viper850 position file
2103  std::cout << "Error: this position file " << filename << " is not for Viper850 robot" << std::endl;
2104  return false;
2105  }
2106  }
2107  if((line.compare(0, 1, "#") == 0)) { // skip comment
2108  continue;
2109  }
2110  if((line.compare(0, key.size(), key) == 0)) { // decode position
2111  // check if there are at least njoint values in the line
2112  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2113  if (chain.size() < njoint+1) // try to split with tab separator
2114  chain = vpIoTools::splitChain(line, std::string("\t"));
2115  if(chain.size() < njoint+1)
2116  continue;
2117 
2118  std::istringstream ss(line);
2119  std::string key_;
2120  ss >> key_;
2121  for (unsigned int i=0; i< njoint; i++)
2122  ss >> q[i];
2123  pos_found = true;
2124  break;
2125  }
2126  }
2127 
2128  // converts rotations from degrees into radians
2129  q.deg2rad();
2130 
2131  fd.close();
2132 
2133  if (!pos_found) {
2134  std::cout << "Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2135  return false;
2136  }
2137 
2138  return true;
2139 }
2140 
2162 bool
2163 vpSimulatorViper850::savePosFile(const std::string &filename, const vpColVector &q)
2164 {
2165 
2166  FILE * fd ;
2167  fd = fopen(filename.c_str(), "w") ;
2168  if (fd == NULL)
2169  return false;
2170 
2171  fprintf(fd, "\
2172 #Viper - Position - Version 1.0\n\
2173 #\n\
2174 # R: A B C D E F\n\
2175 # Joint position in degrees\n\
2176 #\n\
2177 #\n\n");
2178 
2179  // Save positions in mm and deg
2180  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2181  vpMath::deg(q[0]),
2182  vpMath::deg(q[1]),
2183  vpMath::deg(q[2]),
2184  vpMath::deg(q[3]),
2185  vpMath::deg(q[4]),
2186  vpMath::deg(q[5]));
2187 
2188  fclose(fd) ;
2189  return (true);
2190 }
2191 
2199 void
2200 vpSimulatorViper850::move(const char *filename)
2201 {
2202  vpColVector q;
2203 
2204  try
2205  {
2206  this->readPosFile(filename, q);
2209  }
2210  catch(...)
2211  {
2212  throw;
2213  }
2214 }
2215 
2225 void
2227 {
2228  vpViper850::get_cMe(cMe) ;
2229 }
2230 
2238 void
2240 {
2241  vpHomogeneousMatrix cMe ;
2242  vpViper850::get_cMe(cMe) ;
2243 
2244  cVe.buildFrom(cMe) ;
2245 }
2246 
2256 void
2258 {
2259  try
2260  {
2262  }
2263  catch(...)
2264  {
2265  vpERROR_TRACE("catch exception ") ;
2266  throw ;
2267  }
2268 }
2269 
2280 void
2282 {
2283  try
2284  {
2285  vpColVector articularCoordinates = get_artCoord();
2286  vpViper850::get_fJe(articularCoordinates, fJe_) ;
2287  }
2288  catch(...)
2289  {
2290  vpERROR_TRACE("Error caught");
2291  throw ;
2292  }
2293 }
2294 
2298 void
2300 {
2302  return;
2303 
2304  vpColVector stop(6);
2305  stop = 0;
2306  set_artVel(stop);
2307  set_velocity(stop);
2309 }
2310 
2311 
2312 
2313 /**********************************************************************************/
2314 /**********************************************************************************/
2315 /**********************************************************************************/
2316 /**********************************************************************************/
2317 
2326 void
2328 {
2329  // set scene_dir from #define VISP_SCENE_DIR if it exists
2330  // VISP_SCENES_DIR may contain multiple locations separated by ";"
2331  std::string scene_dir_;
2332  std::vector<std::string> scene_dirs = vpIoTools::splitChain(std::string(VISP_SCENES_DIR), std::string(";"));
2333  bool sceneDirExists = false;
2334  for(size_t i=0; i < scene_dirs.size(); i++)
2335  if (vpIoTools::checkDirectory(scene_dirs[i]) == true) { // directory exists
2336  scene_dir_ = scene_dirs[i];
2337  sceneDirExists = true;
2338  break;
2339  }
2340  if (! sceneDirExists) {
2341  try {
2342  scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR");
2343  std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2344  }
2345  catch (...) {
2346  std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2347  }
2348  }
2349 
2350  unsigned int name_length = 30; // the size of this kind of string "/viper850_arm2.bnd"
2351  if (scene_dir_.size() > FILENAME_MAX)
2352  throw vpException (vpException::dimensionError, "Cannot initialize Viper850 simulator");
2353 
2354  unsigned int full_length = (unsigned int)scene_dir_.size() + name_length;
2355  if (full_length > FILENAME_MAX)
2356  throw vpException (vpException::dimensionError, "Cannot initialize Viper850 simulator");
2357 
2358  char *name_cam = new char [full_length];
2359 
2360  strcpy(name_cam, scene_dir_.c_str());
2361  strcat(name_cam,"/camera.bnd");
2362  set_scene(name_cam,&camera,cameraFactor);
2363 
2364  if (arm_dir.size() > FILENAME_MAX)
2365  throw vpException (vpException::dimensionError, "Cannot initialize Viper850 simulator");
2366  full_length = (unsigned int)arm_dir.size() + name_length;
2367  if (full_length > FILENAME_MAX)
2368  throw vpException (vpException::dimensionError, "Cannot initialize Viper850 simulator");
2369 
2370  char *name_arm = new char [full_length];
2371  strcpy(name_arm, arm_dir.c_str());
2372  strcat(name_arm,"/viper850_arm1.bnd");
2373  set_scene(name_arm, robotArms, 1.0);
2374  strcpy(name_arm, arm_dir.c_str());
2375  strcat(name_arm,"/viper850_arm2.bnd");
2376  set_scene(name_arm, robotArms+1, 1.0);
2377  strcpy(name_arm, arm_dir.c_str());
2378  strcat(name_arm,"/viper850_arm3.bnd");
2379  set_scene(name_arm, robotArms+2, 1.0);
2380  strcpy(name_arm, arm_dir.c_str());
2381  strcat(name_arm,"/viper850_arm4.bnd");
2382  set_scene(name_arm, robotArms+3, 1.0);
2383  strcpy(name_arm, arm_dir.c_str());
2384  strcat(name_arm,"/viper850_arm5.bnd");
2385  set_scene(name_arm, robotArms+4, 1.0);
2386  strcpy(name_arm, arm_dir.c_str());
2387  strcat(name_arm,"/viper850_arm6.bnd");
2388  set_scene(name_arm, robotArms+5, 1.0);
2389 
2390 // set_scene("./arm2.bnd", robotArms+1, 1.0);
2391 // set_scene("./arm3.bnd", robotArms+2, 1.0);
2392 // set_scene("./arm4.bnd", robotArms+3, 1.0);
2393 // set_scene("./arm5.bnd", robotArms+4, 1.0);
2394 // set_scene("./arm6.bnd", robotArms+5, 1.0);
2395 
2396  add_rfstack(IS_BACK);
2397 
2398  add_vwstack ("start","depth", 0.0, 100.0);
2399  add_vwstack ("start","window", -0.1,0.1,-0.1,0.1);
2400  add_vwstack ("start","type", PERSPECTIVE);
2401 //
2402 // sceneInitialized = true;
2403 // displayObject = true;
2404  displayCamera = true;
2405 
2406  delete [] name_cam;
2407  delete [] name_arm;
2408 }
2409 
2410 
2411 void
2413 {
2414  bool changed = false;
2415  vpHomogeneousMatrix displacement = navigation(I_,changed);
2416 
2417  //if (displacement[2][3] != 0)
2418  if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2419  camMf2 = camMf2*displacement;
2420 
2421  f2Mf = camMf2.inverse()*camMf;
2422 
2423  camMf = camMf2* displacement * f2Mf;
2424 
2425  double u;
2426  double v;
2427  //if(px_ext != 1 && py_ext != 1)
2428  // we assume px_ext and py_ext > 0
2429  if( (std::fabs(px_ext-1.) > vpMath::maximum(px_ext,1.)*std::numeric_limits<double>::epsilon())
2430  && (std::fabs(py_ext-1) > vpMath::maximum(py_ext,1.)*std::numeric_limits<double>::epsilon()))
2431  {
2432  u = (double)I_.getWidth()/(2*px_ext);
2433  v = (double)I_.getHeight()/(2*py_ext);
2434  }
2435  else
2436  {
2437  u = (double)I_.getWidth()/(vpMath::minimum(I_.getWidth(),I_.getHeight()));
2438  v = (double)I_.getHeight()/(vpMath::minimum(I_.getWidth(),I_.getHeight()));
2439  }
2440 
2441  float w44o[4][4],w44cext[4][4],x,y,z;
2442 
2443  vp2jlc_matrix(camMf.inverse(),w44cext);
2444 
2445  add_vwstack ("start","cop", w44cext[3][0],w44cext[3][1],w44cext[3][2]);
2446  x = w44cext[2][0] + w44cext[3][0];
2447  y = w44cext[2][1] + w44cext[3][1];
2448  z = w44cext[2][2] + w44cext[3][2];
2449  add_vwstack ("start","vrp", x,y,z);
2450  add_vwstack ("start","vpn", w44cext[2][0],w44cext[2][1],w44cext[2][2]);
2451  add_vwstack ("start","vup", w44cext[1][0],w44cext[1][1],w44cext[1][2]);
2452  add_vwstack ("start","window", -u, u, -v, v);
2453 
2454  vpHomogeneousMatrix fMit[8];
2455  get_fMi(fMit);
2456 
2457  vp2jlc_matrix(vpHomogeneousMatrix(0,0,0,0,0,0),w44o);
2458  display_scene(w44o,robotArms[0],I_, curColor);
2459 
2460  vp2jlc_matrix(fMit[0],w44o);
2461  display_scene(w44o,robotArms[1],I_, curColor);
2462 
2463  vp2jlc_matrix(fMit[1],w44o);
2464  display_scene(w44o,robotArms[2],I_, curColor);
2465 
2466  vp2jlc_matrix(fMit[2],w44o);
2467  display_scene(w44o,robotArms[3],I_, curColor);
2468 
2469  vp2jlc_matrix(fMit[3],w44o);
2470  display_scene(w44o,robotArms[4],I_, curColor);
2471 
2472  vp2jlc_matrix(fMit[6],w44o);
2473  display_scene(w44o,robotArms[5],I_, curColor);
2474 
2475  if (displayCamera)
2476  {
2477  vpHomogeneousMatrix cMe;
2478  get_cMe(cMe);
2479  cMe = cMe.inverse();
2480  cMe = fMit[6] * cMe;
2481  vp2jlc_matrix(cMe,w44o);
2482  display_scene(w44o,camera, I_, camColor);
2483  }
2484 
2485  if (displayObject)
2486  {
2487  vp2jlc_matrix(fMo,w44o);
2488  display_scene(w44o,scene,I_, curColor);
2489  }
2490 }
2491 
2507 bool
2509 {
2510  vpColVector stop(6);
2511  bool status = true;
2512  stop = 0;
2513  set_artVel(stop);
2514  set_velocity(stop);
2515  vpHomogeneousMatrix fMc_;
2516  fMc_ = fMo * cMo_.inverse();
2517 
2518  vpColVector articularCoordinates = get_artCoord();
2519  unsigned int nbSol = getInverseKinematics(fMc_, articularCoordinates, verbose_);
2520 
2521  if (nbSol == 0) {
2522  status = false;
2523  vpERROR_TRACE ("Positionning error. Position unreachable");
2524  }
2525 
2526  if (verbose_)
2527  std::cout << "Used joint coordinates (rad): " << articularCoordinates.t() << std::endl;
2528 
2529  set_artCoord(articularCoordinates);
2530 
2531  compute_fMi();
2532 
2533  return status;
2534 }
2535 
2548 void
2550 {
2551  vpColVector stop(6);
2552  stop = 0;
2553  set_artVel(stop);
2554  set_velocity(stop);
2555  vpHomogeneousMatrix fMit[8];
2556  get_fMi(fMit);
2557  fMo = fMit[7] * cMo_;
2558 }
2559 
2560 #elif !defined(VISP_BUILD_SHARED_LIBS)
2561 // Work arround to avoid warning: libvisp_robot.a(vpSimulatorViper850.cpp.o) has no symbols
2562 void dummy_vpSimulatorViper850() {};
2563 #endif
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:1002
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:157
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
bool singularityTest(const vpColVector q, vpMatrix &J)
double a3
for joint 3
Definition: vpViper.h:162
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:154
Error that can be emited by the vpRobot class and its derivates.
static bool checkDirectory(const char *dirname)
Definition: vpIoTools.cpp:358
void get_fMi(vpHomogeneousMatrix *fMit)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:137
unsigned int getWidth() const
Definition: vpImage.h:226
void get_cMe(vpHomogeneousMatrix &cMe)
double getSamplingTime() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void * launcher(void *arg)
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
Point coordinates conversion from normalized coordinates in meter to pixel coordinates ...
#define vpERROR_TRACE
Definition: vpDebug.h:391
VISP_EXPORT double measureTimeSecond()
Definition: vpTime.cpp:255
void getExternalImage(vpImage< vpRGBa > &I)
bool constantSamplingTimeMode
Flag used to force the sampling time in the thread computing the robot's displacement to a constant v...
static std::string getenv(const char *env)
Definition: vpIoTools.cpp:244
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
static const vpColor none
Definition: vpColor.h:175
Initialize the position controller.
Definition: vpRobot.h:69
error that can be emited by ViSP classes.
Definition: vpException.h:73
void track(const vpHomogeneousMatrix &cMo)
void get_fJe(vpMatrix &fJe)
vpControlFrameType
Definition: vpRobot.h:76
vpRxyzVector erc
Definition: vpViper.h:157
double get_py() const
double get_y() const
Get the point y coordinate in the image plane.
Definition: vpPoint.cpp:458
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition: vpViper850.h:122
static const vpColor green
Definition: vpColor.h:166
vpHomogeneousMatrix fMo
double a2
for joint 2
Definition: vpViper.h:161
static void flush(const vpImage< unsigned char > &I)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
static bool savePosFile(const std::string &filename, const vpColVector &q)
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:93
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
Class that defines what is a point.
Definition: vpPoint.h:59
void deg2rad()
Definition: vpColVector.h:127
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:140
Implementation of a rotation matrix and operations on such kind of matrices.
double d1
for joint 1
Definition: vpViper.h:160
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
double a1
Definition: vpViper.h:160
void move(const char *filename)
Initialize the velocity controller.
Definition: vpRobot.h:68
vpRobotStateType
Definition: vpRobot.h:64
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition: vpViper850.h:176
void setExternalCameraPosition(const vpHomogeneousMatrix camMf_)
vpTranslationVector etc
Definition: vpViper.h:156
Initialize the acceleration controller.
Definition: vpRobot.h:70
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
#define vpTRACE
Definition: vpDebug.h:414
vpHomogeneousMatrix f2Mf
void set_displayBusy(const bool &status)
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
static void display(const vpImage< unsigned char > &I)
vpRowVector t() const
vpColVector joint_max
Definition: vpViper.h:169
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:128
Generic class defining intrinsic camera parameters.
vpHomogeneousMatrix getExternalCameraPosition() const
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement)
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:103
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:616
double get_x() const
Get the point x coordinate in the image plane.
Definition: vpPoint.cpp:456
vpToolType getToolType() const
Get the current tool type.
Definition: vpViper850.h:165
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1596
static Type minimum(const Type &a, const Type &b)
Definition: vpMath.h:151
static bool readPosFile(const std::string &filename, vpColVector &q)
Implementation of a velocity twist matrix and operations on such kind of matrices.
unsigned int getRows() const
Return the number of rows of the 2D array.
Definition: vpArray2D.h:152
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:578
void set_velocity(const vpColVector &vel)
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
double get_px() const
static double rad(double deg)
Definition: vpMath.h:104
void setExternalCameraParameters(const vpCameraParameters &cam)
vpControlFrameType getRobotFrame(void) const
Definition: vpRobot.h:170
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1194
This class aims to be a basis used to create all the simulators of robots.
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
double sumSquare() const
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:948
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, vpImagePoint offset=vpImagePoint(0, 0))
bool setVelocityCalled
Flag used to specify to the thread managing the robot displacements that the setVelocity() method has...
void display_scene(Matrix mat, Bound_scene &sc, const vpImage< vpRGBa > &I, const vpColor &color)
vpHomogeneousMatrix camMf
vpHomogeneousMatrix navigation(const vpImage< vpRGBa > &I, bool &changed)
static double deg(double rad)
Definition: vpMath.h:97
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
void setCameraParameters(const vpCameraParameters &cam)
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:141
unsigned int getHeight() const
Definition: vpImage.h:175
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
double d4
for joint 4
Definition: vpViper.h:163
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
Definition: vpMatrix.cpp:1741
void findHighestPositioningSpeed(vpColVector &q)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
void set_artCoord(const vpColVector &coord)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1)
void get_cVe(vpVelocityTwistMatrix &cVe)
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper850.h:185
VISP_EXPORT double getMinTimeForUsleepCall()
Definition: vpTime.cpp:82
void set_artVel(const vpColVector &vel)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
static const double defaultPositioningVelocity
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
double getPositioningVelocity(void)
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:151
vpHomogeneousMatrix camMf2
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition: vpViper850.h:123
void get_eJe(vpMatrix &eJe)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:225
double d6
for joint 6
Definition: vpViper.h:164
vpColVector joint_min
Definition: vpViper.h:170