Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpSimulatorAfma6.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 Afma6.
32  *
33  * Authors:
34  * Nicolas Melchior
35  *
36  *****************************************************************************/
37 
38 
39 
40 #include <visp3/core/vpConfig.h>
41 #if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD))
42 #include <visp3/robot/vpSimulatorAfma6.h>
43 #include <visp3/core/vpTime.h>
44 #include <visp3/core/vpImagePoint.h>
45 #include <visp3/core/vpPoint.h>
46 #include <visp3/core/vpMeterPixelConversion.h>
47 #include <visp3/robot/vpRobotException.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  DWORD dwThreadIdArray;
89  hThread = CreateThread(
90  NULL, // default security attributes
91  0, // use default stack size
92  launcher, // thread function name
93  this, // argument to thread function
94  0, // use default creation flags
95  &dwThreadIdArray); // returns the thread identifier
96  #elif defined (VISP_HAVE_PTHREAD)
97  pthread_mutex_init(&mutex_fMi, NULL);
98  pthread_mutex_init(&mutex_artVel, NULL);
99  pthread_mutex_init(&mutex_artCoord, NULL);
100  pthread_mutex_init(&mutex_velocity, NULL);
101  pthread_mutex_init(&mutex_display, NULL);
102 
103  pthread_attr_init(&attr);
104  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
105 
106  pthread_create(&thread, NULL, launcher, (void *)this);
107  #endif
108 
109  compute_fMi();
110 }
111 
119  : vpRobotWireFrameSimulator(do_display),
120  q_prev_getdis(), first_time_getdis(true), positioningVelocity(defaultPositioningVelocity),
121  zeroPos(), reposPos(), toolCustom(false), arm_dir()
122 {
123  init();
124  initDisplay();
125 
127 
128  #if defined(_WIN32)
129 #ifdef WINRT_8_1
130  mutex_fMi = CreateMutexEx(NULL, NULL, 0, NULL);
131  mutex_artVel = CreateMutexEx(NULL, NULL, 0, NULL);
132  mutex_artCoord = CreateMutexEx(NULL, NULL, 0, NULL);
133  mutex_velocity = CreateMutexEx(NULL, NULL, 0, NULL);
134  mutex_display = CreateMutexEx(NULL, NULL, 0, NULL);
135 #else
136  mutex_fMi = CreateMutex(NULL, FALSE, NULL);
137  mutex_artVel = CreateMutex(NULL, FALSE, NULL);
138  mutex_artCoord = CreateMutex(NULL, FALSE, NULL);
139  mutex_velocity = CreateMutex(NULL, FALSE, NULL);
140  mutex_display = CreateMutex(NULL, FALSE, NULL);
141 #endif
142 
143  DWORD dwThreadIdArray;
144  hThread = CreateThread(
145  NULL, // default security attributes
146  0, // use default stack size
147  launcher, // thread function name
148  this, // argument to thread function
149  0, // use default creation flags
150  &dwThreadIdArray); // returns the thread identifier
151  #elif defined(VISP_HAVE_PTHREAD)
152  pthread_mutex_init(&mutex_fMi, NULL);
153  pthread_mutex_init(&mutex_artVel, NULL);
154  pthread_mutex_init(&mutex_artCoord, NULL);
155  pthread_mutex_init(&mutex_velocity, NULL);
156  pthread_mutex_init(&mutex_display, NULL);
157 
158  pthread_attr_init(&attr);
159  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
160 
161  pthread_create(&thread, NULL, launcher, (void *)this);
162  #endif
163 
164  compute_fMi();
165 }
166 
171 {
172  robotStop = true;
173 
174  #if defined(_WIN32)
175 # if defined(WINRT_8_1)
176  WaitForSingleObjectEx(hThread, INFINITE, FALSE);
177 # else // pure win32
178  WaitForSingleObject(hThread, INFINITE);
179 # endif
180  CloseHandle(hThread);
181  CloseHandle(mutex_fMi);
182  CloseHandle(mutex_artVel);
183  CloseHandle(mutex_artCoord);
184  CloseHandle(mutex_velocity);
185  CloseHandle(mutex_display);
186  #elif defined(VISP_HAVE_PTHREAD)
187  pthread_attr_destroy(&attr);
188  pthread_join(thread, NULL);
189  pthread_mutex_destroy(&mutex_fMi);
190  pthread_mutex_destroy(&mutex_artVel);
191  pthread_mutex_destroy(&mutex_artCoord);
192  pthread_mutex_destroy(&mutex_velocity);
193  pthread_mutex_destroy(&mutex_display);
194  #endif
195 
196  if (robotArms != NULL)
197  {
198  for(int i = 0; i < 6; i++)
199  free_Bound_scene (&(robotArms[i]));
200  }
201 
202  delete[] robotArms;
203  delete[] fMi;
204 }
205 
214 void
216 {
217  // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
218  // VISP_ROBOT_ARMS_DIR may contain multiple locations separated by ";"
219  std::vector<std::string> arm_dirs = vpIoTools::splitChain(std::string(VISP_ROBOT_ARMS_DIR), std::string(";"));
220  bool armDirExists = false;
221  for(size_t i=0; i < arm_dirs.size(); i++)
222  if (vpIoTools::checkDirectory(arm_dirs[i]) == true) { // directory exists
223  arm_dir = arm_dirs[i];
224  armDirExists = true;
225  break;
226  }
227  if (! armDirExists) {
228  try {
229  arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
230  std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
231  }
232  catch (...) {
233  std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
234  }
235  }
236 
237  this->init(vpAfma6::TOOL_CCMOP);
238  toolCustom = false;
239 
240  size_fMi = 8;
241  fMi = new vpHomogeneousMatrix[8];
244 
245  zeroPos.resize(njoint);
246  zeroPos = 0;
247  reposPos.resize(njoint);
248  reposPos = 0;
249  reposPos[1] = -M_PI/2; reposPos[2] = M_PI; reposPos[4] = M_PI/2;
250 
251  artCoord = zeroPos;
252  artVel = 0;
253 
254  q_prev_getdis.resize(njoint);
255  q_prev_getdis = 0;
256  first_time_getdis = true;
257 
258  positioningVelocity = defaultPositioningVelocity ;
259 
262 
263  // Software joint limits in radians
264  //_joint_min.resize(njoint);
265  _joint_min[0] = -0.6501;
266  _joint_min[1] = -0.6001;
267  _joint_min[2] = -0.5001;
268  _joint_min[3] = -2.7301;
269  _joint_min[4] = -0.1001;
270  _joint_min[5] = -1.5901;
271  //_joint_max.resize(njoint);
272  _joint_max[0] = 0.7001;
273  _joint_max[1] = 0.5201;
274  _joint_max[2] = 0.4601;
275  _joint_max[3] = 2.7301;
276  _joint_max[4] = 2.4801;
277  _joint_max[5] = 1.5901;
278 }
279 
283 void
285 {
286  robotArms = NULL;
287  robotArms = new Bound_scene[6];
288  initArms();
290  cameraParam.initPersProjWithoutDistortion (558.5309599, 556.055053, 320, 240);
292  vpCameraParameters tmp;
293  getCameraParameters(tmp,640,480);
294  px_int = tmp.get_px();
295  py_int = tmp.get_py();
296  sceneInitialized = true;
297 }
298 
299 
315 void
318 {
319  this->projModel = proj_model;
320  unsigned int name_length = 30; // the size of this kind of string "/afma6_tool_vacuum.bnd"
321  if (arm_dir.size() > FILENAME_MAX)
322  throw vpException (vpException::dimensionError, "Cannot initialize Afma6 simulator");
323  unsigned int full_length = (unsigned int)arm_dir.size() + name_length;
324  if (full_length > FILENAME_MAX)
325  throw vpException (vpException::dimensionError, "Cannot initialize Afma6 simulator");
326 
327  // Use here default values of the robot constant parameters.
328  switch (tool) {
329  case vpAfma6::TOOL_CCMOP: {
330  _erc[0] = vpMath::rad(164.35); // rx
331  _erc[1] = vpMath::rad( 89.64); // ry
332  _erc[2] = vpMath::rad(-73.05); // rz
333  _etc[0] = 0.0117; // tx
334  _etc[1] = 0.0033; // ty
335  _etc[2] = 0.2272; // tz
336 
337  setCameraParameters(vpCameraParameters(1109.5735473989, 1112.1520168160, 320, 240));
338 
339  if (robotArms != NULL)
340  {
341  while (get_displayBusy()) vpTime::wait(2);
342  free_Bound_scene (&(robotArms[5]));
343  char *name_arm = new char [full_length];
344  strcpy(name_arm, arm_dir.c_str());
345  strcat(name_arm,"/afma6_tool_ccmop.bnd");
346  set_scene(name_arm, robotArms+5, 1.0);
347  set_displayBusy(false);
348  delete [] name_arm;
349  }
350  break;
351  }
352  case vpAfma6::TOOL_GRIPPER: {
353  _erc[0] = vpMath::rad( 88.33); // rx
354  _erc[1] = vpMath::rad( 72.07); // ry
355  _erc[2] = vpMath::rad( 2.53); // rz
356  _etc[0] = 0.0783; // tx
357  _etc[1] = 0.1234; // ty
358  _etc[2] = 0.1638; // tz
359 
360  setCameraParameters(vpCameraParameters(852.6583228197, 854.8084224761, 320, 240));
361 
362  if (robotArms != NULL)
363  {
364  while (get_displayBusy()) vpTime::wait(2);
365  free_Bound_scene (&(robotArms[5]));
366  char *name_arm = new char [full_length];
367  strcpy(name_arm, arm_dir.c_str());
368  strcat(name_arm,"/afma6_tool_gripper.bnd");
369  set_scene(name_arm, robotArms+5, 1.0);
370  set_displayBusy(false);
371  delete [] name_arm;
372  }
373  break;
374  }
375  case vpAfma6::TOOL_VACUUM: {
376  _erc[0] = vpMath::rad( 90.40); // rx
377  _erc[1] = vpMath::rad( 75.11); // ry
378  _erc[2] = vpMath::rad( 0.18); // rz
379  _etc[0] = 0.0038; // tx
380  _etc[1] = 0.1281; // ty
381  _etc[2] = 0.1658; // tz
382 
383  setCameraParameters(vpCameraParameters(853.4876600807, 856.0339170706, 320, 240));
384 
385  if (robotArms != NULL)
386  {
387  while (get_displayBusy()) vpTime::wait(2);
388  free_Bound_scene (&(robotArms[5]));
389 
390  char *name_arm = new char [full_length];
391 
392  strcpy(name_arm, arm_dir.c_str());
393  strcat(name_arm,"/afma6_tool_vacuum.bnd");
394  set_scene(name_arm, robotArms+5, 1.0);
395  set_displayBusy(false);
396  delete [] name_arm;
397  }
398  break;
399  }
402  std::cout << "The generic camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
403  }
404  }
405 
406  vpRotationMatrix eRc(_erc);
407  this->_eMc.buildFrom(_etc, eRc);
408 
409  setToolType(tool);
410  return ;
411 }
412 
423 void
425  const unsigned int &image_width,
426  const unsigned int &image_height)
427 {
428  if (toolCustom)
429  {
430  vpCameraParameters(px_int,py_int,image_width/2,image_height/2);
431  }
432  // Set default parameters
433  switch (getToolType()) {
434  case vpAfma6::TOOL_CCMOP: {
435  // Set default intrinsic camera parameters for 640x480 images
436  if (image_width == 640 && image_height == 480)
437  {
438  std::cout << "Get default camera parameters for camera \""
439  << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl;
440  cam.initPersProjWithoutDistortion(1109.5735473989, 1112.1520168160, 320, 240);
441  }
442  else {
443  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
444  }
445  break;
446  }
447  case vpAfma6::TOOL_GRIPPER: {
448  // Set default intrinsic camera parameters for 640x480 images
449  if (image_width == 640 && image_height == 480) {
450  std::cout << "Get default camera parameters for camera \""
451  << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl;
452  cam.initPersProjWithoutDistortion(852.6583228197, 854.8084224761, 320, 240);
453  }
454  else {
455  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
456  }
457  break;
458  }
461  case vpAfma6::TOOL_VACUUM: {
462  std::cout << "The generic camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
463  break;
464  }
465  default:
466  vpERROR_TRACE ("This error should not occur!");
467  break;
468  }
469  return;
470 }
471 
480 void
482  const vpImage<unsigned char> &I_)
483 {
484  getCameraParameters(cam,I_.getWidth(),I_.getHeight());
485 }
486 
495 void
497  const vpImage<vpRGBa> &I_)
498 {
499  getCameraParameters(cam,I_.getWidth(),I_.getHeight());
500 }
501 
502 
508 void
510 {
511  px_int = cam.get_px();
512  py_int = cam.get_py();
513  toolCustom = true;
514 }
515 
516 
520 void
522 {
523  double tcur_1 = tcur;// temporary variable used to store the last time since the last command
524 
525  while (!robotStop)
526  {
527  //Get current time
528  tprev = tcur_1;
530 
532  setVelocityCalled = false;
533 
535 
536  double ellapsedTime = (tcur - tprev) * 1e-3;
537  if(constantSamplingTimeMode){//if we want a constant velocity, we force the ellapsed time to the given samplingTime
538  ellapsedTime = getSamplingTime(); // in second
539  }
540 
541  vpColVector articularCoordinates = get_artCoord();
542  vpColVector articularVelocities = get_artVel();
543 
544  if (jointLimit)
545  {
546  double art = articularCoordinates[jointLimitArt-1] + ellapsedTime*articularVelocities[jointLimitArt-1];
547  if (art <= _joint_min[jointLimitArt-1] || art >= _joint_max[jointLimitArt-1]) {
548  if (verbose_) {
549  std::cout << "Joint " << jointLimitArt-1
550  << " reaches a limit: " << vpMath::deg(_joint_min[jointLimitArt-1]) << " < "
551  << vpMath::deg(art) << " < " << vpMath::deg(_joint_max[jointLimitArt-1]) << std::endl;
552  }
553 
554  articularVelocities = 0.0;
555  }
556  else
557  jointLimit = false;
558  }
559 
560  articularCoordinates[0] = articularCoordinates[0] + ellapsedTime*articularVelocities[0];
561  articularCoordinates[1] = articularCoordinates[1] + ellapsedTime*articularVelocities[1];
562  articularCoordinates[2] = articularCoordinates[2] + ellapsedTime*articularVelocities[2];
563  articularCoordinates[3] = articularCoordinates[3] + ellapsedTime*articularVelocities[3];
564  articularCoordinates[4] = articularCoordinates[4] + ellapsedTime*articularVelocities[4];
565  articularCoordinates[5] = articularCoordinates[5] + ellapsedTime*articularVelocities[5];
566 
567  int jl = isInJointLimit();
568 
569  if (jl != 0 && jointLimit == false)
570  {
571  if (jl < 0)
572  ellapsedTime = (_joint_min[(unsigned int)(-jl-1)] - articularCoordinates[(unsigned int)(-jl-1)])/(articularVelocities[(unsigned int)(-jl-1)]);
573  else
574  ellapsedTime = (_joint_max[(unsigned int)(jl-1)] - articularCoordinates[(unsigned int)(jl-1)])/(articularVelocities[(unsigned int)(jl-1)]);
575 
576  for (unsigned int i = 0; i < 6; i++)
577  articularCoordinates[i] = articularCoordinates[i] + ellapsedTime*articularVelocities[i];
578 
579  jointLimit = true;
580  jointLimitArt = (unsigned int)fabs((double)jl);
581  }
582 
583  set_artCoord(articularCoordinates);
584  set_artVel(articularVelocities);
585 
586  compute_fMi();
587 
588  if (displayAllowed)
589  {
593  }
594 
596  {
597  while (get_displayBusy()) vpTime::wait(2);
599  set_displayBusy(false);
600  }
601 
602 
603  if (0/*displayType == MODEL_DH && displayAllowed*/)
604  {
605  vpHomogeneousMatrix fMit[8];
606  get_fMi(fMit);
607 
608  //vpDisplay::displayFrame(I,getExternalCameraPosition ()*fMi[6],cameraParam,0.2,vpColor::none);
609 
610  vpImagePoint iP, iP_1;
611  vpPoint pt(0,0,0);
612 
615  pt.track(getExternalCameraPosition ()*fMit[0]);
618  for (unsigned int k = 1; k < 7; k++)
619  {
620  pt.track(getExternalCameraPosition ()*fMit[k-1]);
622 
623  pt.track(getExternalCameraPosition ()*fMit[k]);
625 
627  }
629  }
630 
632 
633 
634  vpTime::wait( tcur, 1000*getSamplingTime() );
635  tcur_1 = tcur;
636  }else{
638  }
639  }
640 }
641 
649 void
651 {
652  //vpColVector q = get_artCoord();
653  vpColVector q(6);//; = get_artCoord();
654  q = get_artCoord();
655 
656  vpHomogeneousMatrix fMit[8];
657 
658  double q1 = q[0];
659  double q2 = q[1];
660  double q3 = q[2];
661  double q4 = q[3];
662  double q5 = q[4];
663  double q6 = q[5];
664 
665  double c4 = cos(q4);
666  double s4 = sin(q4);
667  double c5 = cos(q5);
668  double s5 = sin(q5);
669  double c6 = cos(q6);
670  double s6 = sin(q6);
671 
672  fMit[0][0][0] = 1;
673  fMit[0][1][0] = 0;
674  fMit[0][2][0] = 0;
675  fMit[0][0][1] = 0;
676  fMit[0][1][1] = 1;
677  fMit[0][2][1] = 0;
678  fMit[0][0][2] = 0;
679  fMit[0][1][2] = 0;
680  fMit[0][2][2] = 1;
681  fMit[0][0][3] = q1;
682  fMit[0][1][3] = 0;
683  fMit[0][2][3] = 0;
684 
685  fMit[1][0][0] = 1;
686  fMit[1][1][0] = 0;
687  fMit[1][2][0] = 0;
688  fMit[1][0][1] = 0;
689  fMit[1][1][1] = 1;
690  fMit[1][2][1] = 0;
691  fMit[1][0][2] = 0;
692  fMit[1][1][2] = 0;
693  fMit[1][2][2] = 1;
694  fMit[1][0][3] = q1;
695  fMit[1][1][3] = q2;
696  fMit[1][2][3] = 0;
697 
698  fMit[2][0][0] = 1;
699  fMit[2][1][0] = 0;
700  fMit[2][2][0] = 0;
701  fMit[2][0][1] = 0;
702  fMit[2][1][1] = 1;
703  fMit[2][2][1] = 0;
704  fMit[2][0][2] = 0;
705  fMit[2][1][2] = 0;
706  fMit[2][2][2] = 1;
707  fMit[2][0][3] = q1;
708  fMit[2][1][3] = q2;
709  fMit[2][2][3] = q3;
710 
711  fMit[3][0][0] = s4;
712  fMit[3][1][0] = -c4;
713  fMit[3][2][0] = 0;
714  fMit[3][0][1] = c4;
715  fMit[3][1][1] = s4;
716  fMit[3][2][1] = 0;
717  fMit[3][0][2] = 0;
718  fMit[3][1][2] = 0;
719  fMit[3][2][2] = 1;
720  fMit[3][0][3] = q1;
721  fMit[3][1][3] = q2;
722  fMit[3][2][3] = q3;
723 
724  fMit[4][0][0] = s4*s5;
725  fMit[4][1][0] = -c4*s5;
726  fMit[4][2][0] = c5;
727  fMit[4][0][1] = s4*c5;
728  fMit[4][1][1] = -c4*c5;
729  fMit[4][2][1] = -s5;
730  fMit[4][0][2] = c4;
731  fMit[4][1][2] = s4;
732  fMit[4][2][2] = 0;
733  fMit[4][0][3] = c4*this->_long_56+q1;
734  fMit[4][1][3] = s4*this->_long_56+q2;
735  fMit[4][2][3] = q3;
736 
737  fMit[5][0][0] = s4*s5*c6+c4*s6;
738  fMit[5][1][0] = -c4*s5*c6+s4*s6;
739  fMit[5][2][0] = c5*c6;
740  fMit[5][0][1] = -s4*s5*s6+c4*c6;
741  fMit[5][1][1] = c4*s5*s6+s4*c6;
742  fMit[5][2][1] = -c5*s6;
743  fMit[5][0][2] = -s4*c5;
744  fMit[5][1][2] = c4*c5;
745  fMit[5][2][2] = s5;
746  fMit[5][0][3] = c4*this->_long_56+q1;
747  fMit[5][1][3] = s4*this->_long_56+q2;
748  fMit[5][2][3] = q3;
749 
750  fMit[6][0][0] = fMit[5][0][0];
751  fMit[6][1][0] = fMit[5][1][0];
752  fMit[6][2][0] = fMit[5][2][0];
753  fMit[6][0][1] = fMit[5][0][1];
754  fMit[6][1][1] = fMit[5][1][1];
755  fMit[6][2][1] = fMit[5][2][1];
756  fMit[6][0][2] = fMit[5][0][2];
757  fMit[6][1][2] = fMit[5][1][2];
758  fMit[6][2][2] = fMit[5][2][2];
759  fMit[6][0][3] = fMit[5][0][3];
760  fMit[6][1][3] = fMit[5][1][3];
761  fMit[6][2][3] = fMit[5][2][3];
762 
763 // vpHomogeneousMatrix cMe;
764 // get_cMe(cMe);
765 // cMe = cMe.inverse();
766 // fMit[7] = fMit[6] * cMe;
767  vpAfma6::get_fMc(q,fMit[7]);
768 
769  #if defined(_WIN32)
770 # if defined(WINRT_8_1)
771  WaitForSingleObjectEx(mutex_fMi, INFINITE, FALSE);
772 # else // pure win32
773  WaitForSingleObject(mutex_fMi, INFINITE);
774 # endif
775  for (int i = 0; i < 8; i++)
776  fMi[i] = fMit[i];
777  ReleaseMutex(mutex_fMi);
778  #elif defined(VISP_HAVE_PTHREAD)
779  pthread_mutex_lock (&mutex_fMi);
780  for (int i = 0; i < 8; i++)
781  fMi[i] = fMit[i];
782  pthread_mutex_unlock (&mutex_fMi);
783  #endif
784 }
785 
786 
794 {
795  switch (newState) {
796  case vpRobot::STATE_STOP: {
797  // Start primitive STOP only if the current state is Velocity
799  stopMotion();
800  }
801  break;
802  }
805  std::cout << "Change the control mode from velocity to position control.\n";
806  stopMotion();
807  }
808  else {
809  //std::cout << "Change the control mode from stop to position control.\n";
810  }
811  break;
812  }
815  std::cout << "Change the control mode from stop to velocity control.\n";
816  }
817  break;
818  }
820  default:
821  break ;
822  }
823 
824  return vpRobot::setRobotState (newState);
825 }
826 
896 void
898 {
900  vpERROR_TRACE ("Cannot send a velocity to the robot "
901  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
903  "Cannot send a velocity to the robot "
904  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
905  }
906 
907  vpColVector vel_sat(6);
908 
909  double scale_sat = 1;
910  double vel_trans_max = getMaxTranslationVelocity();
911  double vel_rot_max = getMaxRotationVelocity();
912 
913  double vel_abs; // Absolute value
914 
915  // Velocity saturation
916  switch(frame)
917  {
918  // saturation in cartesian space
919  case vpRobot::CAMERA_FRAME :
921  {
922  if (vel.getRows() != 6)
923  {
924  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
925  throw;
926  }
927 
928  for (unsigned int i = 0 ; i < 3; ++ i)
929  {
930  vel_abs = fabs (vel[i]);
931  if (vel_abs > vel_trans_max && !jointLimit)
932  {
933  vel_trans_max = vel_abs;
934  vpERROR_TRACE ("Excess velocity %g m/s in TRANSLATION "
935  "(axis nr. %d).", vel[i], i+1);
936  }
937 
938  vel_abs = fabs (vel[i+3]);
939  if (vel_abs > vel_rot_max && !jointLimit) {
940  vel_rot_max = vel_abs;
941  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
942  "(axis nr. %d).", vel[i+3], i+4);
943  }
944  }
945 
946  double scale_trans_sat = 1;
947  double scale_rot_sat = 1;
948  if (vel_trans_max > getMaxTranslationVelocity())
949  scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
950 
951  if (vel_rot_max > getMaxRotationVelocity())
952  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
953 
954  if ( (scale_trans_sat < 1) || (scale_rot_sat < 1) )
955  {
956  if (scale_trans_sat < scale_rot_sat)
957  scale_sat = scale_trans_sat;
958  else
959  scale_sat = scale_rot_sat;
960  }
961  break;
962  }
963 
964  // saturation in joint space
966  {
967  if (vel.getRows() != 6)
968  {
969  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
970  throw;
971  }
972  for (unsigned int i = 0 ; i < 6; ++ i)
973  {
974  vel_abs = fabs (vel[i]);
975  if (vel_abs > vel_rot_max && !jointLimit)
976  {
977  vel_rot_max = vel_abs;
978  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
979  "(axis nr. %d).", vel[i], i+1);
980  }
981  }
982  double scale_rot_sat = 1;
983  if (vel_rot_max > getMaxRotationVelocity())
984  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
985  if ( scale_rot_sat < 1 )
986  scale_sat = scale_rot_sat;
987  break;
988  }
989  case vpRobot::MIXT_FRAME :
990  {
991  break;
992  }
993  }
994 
995  set_velocity (vel * scale_sat);
996  setRobotFrame (frame);
997  setVelocityCalled = true;
998 }
999 
1000 
1004 void
1006 {
1008 
1009  double vel_rot_max = getMaxRotationVelocity();
1010 
1011  vpColVector articularCoordinates = get_artCoord();
1012  vpColVector velocityframe = get_velocity();
1013  vpColVector articularVelocity;
1014 
1015  switch(frame)
1016  {
1017  case vpRobot::CAMERA_FRAME :
1018  {
1019  vpMatrix eJe_;
1021  vpAfma6::get_eJe(articularCoordinates,eJe_);
1022  eJe_ = eJe_.pseudoInverse();
1024  singularityTest(articularCoordinates,eJe_);
1025  articularVelocity = eJe_*eVc*velocityframe;
1026  set_artVel (articularVelocity);
1027  break;
1028  }
1030  {
1031  vpMatrix fJe_;
1032  vpAfma6::get_fJe(articularCoordinates,fJe_);
1033  fJe_ = fJe_.pseudoInverse();
1035  singularityTest(articularCoordinates,fJe_);
1036  articularVelocity = fJe_*velocityframe;
1037  set_artVel (articularVelocity);
1038  break;
1039  }
1041  {
1042  articularVelocity = velocityframe;
1043  set_artVel (articularVelocity);
1044  break;
1045  }
1046  case vpRobot::MIXT_FRAME :
1047  {
1048  break;
1049  }
1050  }
1051 
1052  switch(frame)
1053  {
1054  case vpRobot::CAMERA_FRAME :
1056  {
1057  for (unsigned int i = 0 ; i < 6; ++ i)
1058  {
1059  double vel_abs = fabs (articularVelocity[i]);
1060  if (vel_abs > vel_rot_max && !jointLimit)
1061  {
1062  vel_rot_max = vel_abs;
1063  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
1064  "(axis nr. %d).", articularVelocity[i], i+1);
1065  }
1066  }
1067  double scale_rot_sat = 1;
1068  double scale_sat = 1;
1069  if (vel_rot_max > getMaxRotationVelocity())
1070  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
1071  if ( scale_rot_sat < 1 )
1072  scale_sat = scale_rot_sat;
1073 
1074  set_artVel(articularVelocity * scale_sat);
1075  break;
1076  }
1078  case vpRobot::MIXT_FRAME :
1079  {
1080  break;
1081  }
1082  }
1083 }
1084 
1085 
1132 void
1134 {
1135  vel.resize(6);
1136 
1137  vpColVector articularCoordinates = get_artCoord();
1138  vpColVector articularVelocity = get_artVel();
1139 
1140  switch(frame)
1141  {
1142  case vpRobot::CAMERA_FRAME :
1143  {
1144  vpMatrix eJe_;
1146  vpAfma6::get_eJe(articularCoordinates,eJe_);
1147  vel = cVe*eJe_*articularVelocity;
1148  break ;
1149  }
1150  case vpRobot::ARTICULAR_FRAME :
1151  {
1152  vel = articularVelocity;
1153  break ;
1154  }
1155  case vpRobot::REFERENCE_FRAME :
1156  {
1157  vpMatrix fJe_;
1158  vpAfma6::get_fJe(articularCoordinates,fJe_);
1159  vel = fJe_*articularVelocity;
1160  break ;
1161  }
1162  case vpRobot::MIXT_FRAME :
1163  {
1164  break ;
1165  }
1166  default:
1167  {
1168  vpERROR_TRACE ("Error in spec of vpRobot. "
1169  "Case not taken in account.");
1170  return;
1171  }
1172  }
1173 }
1174 
1191 void
1193 {
1194  timestamp = vpTime::measureTimeSecond();
1195  getVelocity(frame, vel);
1196 }
1197 
1242 {
1243  vpColVector vel(6);
1244  getVelocity (frame, vel);
1245 
1246  return vel;
1247 }
1248 
1263 {
1264  timestamp = vpTime::measureTimeSecond();
1265  vpColVector vel(6);
1266  getVelocity (frame, vel);
1267 
1268  return vel;
1269 }
1270 
1271 void
1273 {
1274  double vel_rot_max = getMaxRotationVelocity();
1275  double velmax = fabs(q[0]);
1276  for (unsigned int i = 1; i < 6; i++)
1277  {
1278  if (velmax < fabs(q[i]))
1279  velmax = fabs(q[i]);
1280  }
1281 
1282  double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax*100);
1283  q = q * alpha;
1284 }
1285 
1360 void
1362 {
1364  {
1365  vpERROR_TRACE ("Robot was not in position-based control\n"
1366  "Modification of the robot state");
1367  // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1368  }
1369 
1370  vpColVector articularCoordinates = get_artCoord();
1371 
1372  vpColVector error(6);
1373  double errsqr = 0;
1374  switch(frame)
1375  {
1376  case vpRobot::CAMERA_FRAME :
1377  {
1378  int nbSol;
1379  vpColVector qdes(6);
1380 
1381  vpTranslationVector txyz;
1382  vpRxyzVector rxyz;
1383  for (unsigned int i=0; i < 3; i++)
1384  {
1385  txyz[i] = q[i];
1386  rxyz[i] = q[i+3];
1387  }
1388 
1389  vpRotationMatrix cRc2(rxyz);
1390  vpHomogeneousMatrix cMc2(txyz, cRc2);
1391 
1392  vpHomogeneousMatrix fMc_;
1393  vpAfma6::get_fMc(articularCoordinates, fMc_);
1394 
1395  vpHomogeneousMatrix fMc2 = fMc_ * cMc2;
1396 
1397  do
1398  {
1399  articularCoordinates = get_artCoord();
1400  qdes = articularCoordinates;
1401  nbSol = getInverseKinematics(fMc2, qdes, true, verbose_);
1402  setVelocityCalled = true;
1403  if (nbSol > 0)
1404  {
1405  error = qdes - articularCoordinates;
1406  errsqr = error.sumSquare();
1407  //findHighestPositioningSpeed(error);
1408  set_artVel(error);
1409  if (errsqr < 1e-4)
1410  {
1411  set_artCoord (qdes);
1412  error = 0;
1413  set_artVel(error);
1414  set_velocity(error);
1415  break;
1416  }
1417  }
1418  else
1419  {
1420  vpERROR_TRACE ("Positionning error.");
1422  "Position out of range.");
1423  }
1424  }while (errsqr > 1e-8 && nbSol > 0);
1425 
1426  break ;
1427  }
1428 
1430  {
1431  do
1432  {
1433  articularCoordinates = get_artCoord();
1434  error = q - articularCoordinates;
1435  errsqr = error.sumSquare();
1436  //findHighestPositioningSpeed(error);
1437  set_artVel(error);
1438  setVelocityCalled = true;
1439  if (errsqr < 1e-4)
1440  {
1441  set_artCoord (q);
1442  error = 0;
1443  set_artVel(error);
1444  set_velocity(error);
1445  break;
1446  }
1447  }while (errsqr > 1e-8);
1448  break ;
1449  }
1450 
1452  {
1453  int nbSol;
1454  vpColVector qdes(6);
1455 
1456  vpTranslationVector txyz;
1457  vpRxyzVector rxyz;
1458  for (unsigned int i=0; i < 3; i++)
1459  {
1460  txyz[i] = q[i];
1461  rxyz[i] = q[i+3];
1462  }
1463 
1464  vpRotationMatrix fRc(rxyz);
1465  vpHomogeneousMatrix fMc_(txyz, fRc);
1466 
1467  do
1468  {
1469  articularCoordinates = get_artCoord();
1470  qdes = articularCoordinates;
1471  nbSol = getInverseKinematics(fMc_, qdes, true, verbose_);
1472  setVelocityCalled = true;
1473  if (nbSol > 0)
1474  {
1475  error = qdes - articularCoordinates;
1476  errsqr = error.sumSquare();
1477  //findHighestPositioningSpeed(error);
1478  set_artVel(error);
1479  if (errsqr < 1e-4)
1480  {
1481  set_artCoord (qdes);
1482  error = 0;
1483  set_artVel(error);
1484  set_velocity(error);
1485  break;
1486  }
1487  }
1488  else
1489  vpERROR_TRACE ("Positionning error. Position unreachable");
1490  }while (errsqr > 1e-8 && nbSol > 0);
1491  break ;
1492  }
1493  case vpRobot::MIXT_FRAME:
1494  {
1495  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1497  "Positionning error: "
1498  "Mixt frame not implemented.");
1499  }
1500  }
1501 }
1502 
1567  const double pos1,
1568  const double pos2,
1569  const double pos3,
1570  const double pos4,
1571  const double pos5,
1572  const double pos6)
1573 {
1574  try{
1575  vpColVector position(6) ;
1576  position[0] = pos1 ;
1577  position[1] = pos2 ;
1578  position[2] = pos3 ;
1579  position[3] = pos4 ;
1580  position[4] = pos5 ;
1581  position[5] = pos6 ;
1582 
1583  setPosition(frame, position) ;
1584  }
1585  catch(...)
1586  {
1587  vpERROR_TRACE("Error caught");
1588  throw ;
1589  }
1590 }
1591 
1627 void vpSimulatorAfma6::setPosition(const char *filename)
1628 {
1629  vpColVector q;
1630  bool ret;
1631 
1632  ret = this->readPosFile(filename, q);
1633 
1634  if (ret == false) {
1635  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1637  "Bad position in filename.");
1638  }
1641 }
1642 
1702 void
1704 {
1705  q.resize(6);
1706 
1707  switch(frame)
1708  {
1709  case vpRobot::CAMERA_FRAME :
1710  {
1711  q = 0;
1712  break ;
1713  }
1714 
1716  {
1717  q = get_artCoord();
1718  break ;
1719  }
1720 
1722  {
1723  vpHomogeneousMatrix fMc_;
1724  vpAfma6::get_fMc (get_artCoord(), fMc_);
1725 
1726  vpRotationMatrix fRc;
1727  fMc_.extract(fRc);
1728  vpRxyzVector rxyz(fRc);
1729 
1730  vpTranslationVector txyz;
1731  fMc_.extract(txyz);
1732 
1733  for (unsigned int i=0; i <3; i++)
1734  {
1735  q[i] = txyz[i];
1736  q[i+3] = rxyz[i];
1737  }
1738  break ;
1739  }
1740 
1741  case vpRobot::MIXT_FRAME:
1742  {
1743  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1745  "Positionning error: "
1746  "Mixt frame not implemented.");
1747  }
1748  }
1749 }
1750 
1777 void
1779 {
1780  timestamp = vpTime::measureTimeSecond();
1781  getPosition(frame, q);
1782 }
1783 
1784 
1795 void
1797 {
1798  vpColVector posRxyz;
1799  //recupere position en Rxyz
1800  this->getPosition(frame,posRxyz);
1801 
1802  //recupere le vecteur thetaU correspondant
1803  vpThetaUVector RtuVect(vpRxyzVector(posRxyz[3],posRxyz[4],posRxyz[5]));
1804 
1805  //remplit le vpPoseVector avec translation et rotation ThetaU
1806  for(unsigned int j=0;j<3;j++)
1807  {
1808  position[j]=posRxyz[j];
1809  position[j+3]=RtuVect[j];
1810  }
1811 }
1812 
1823 void
1825  vpPoseVector &position, double &timestamp)
1826 {
1827  timestamp = vpTime::measureTimeSecond();
1828  getPosition(frame, position);
1829 }
1830 
1837 void
1839 {
1840  if (limitMin.getRows() != 6 || limitMax.getRows() != 6)
1841  {
1842  vpTRACE("Joint limit vector has not a size of 6 !");
1843  return;
1844  }
1845 
1846  _joint_min[0] = limitMin[0];
1847  _joint_min[1] = limitMin[1];
1848  _joint_min[2] = limitMin[2];
1849  _joint_min[3] = limitMin[3];
1850  _joint_min[4] = limitMin[4];
1851  _joint_min[5] = limitMin[5];
1852 
1853  _joint_max[0] = limitMax[0];
1854  _joint_max[1] = limitMax[1];
1855  _joint_max[2] = limitMax[2];
1856  _joint_max[3] = limitMax[3];
1857  _joint_max[4] = limitMax[4];
1858  _joint_max[5] = limitMax[5];
1859 
1860 }
1861 
1867 bool
1869 {
1870  double q5 = q[4];
1871 
1872  bool cond = fabs(q5-M_PI/2) < 1e-1;
1873 
1874  if(cond)
1875  {
1876  J[0][3] = 0;
1877  J[0][4] = 0;
1878  J[1][3] = 0;
1879  J[1][4] = 0;
1880  J[3][3] = 0;
1881  J[3][4] = 0;
1882  J[5][3] = 0;
1883  J[5][4] = 0;
1884  return true;
1885  }
1886 
1887  return false;
1888 }
1889 
1893 int
1895 {
1896  int artNumb = 0;
1897  double diff = 0;
1898  double difft = 0;
1899 
1900  vpColVector articularCoordinates = get_artCoord();
1901 
1902  for (unsigned int i = 0; i < 6; i++)
1903  {
1904  if (articularCoordinates[i] <= _joint_min[i])
1905  {
1906  difft = _joint_min[i] - articularCoordinates[i];
1907  if (difft > diff)
1908  {
1909  diff = difft;
1910  artNumb = -(int)i-1;
1911  }
1912  }
1913  }
1914 
1915  for (unsigned int i = 0; i < 6; i++)
1916  {
1917  if (articularCoordinates[i] >= _joint_max[i])
1918  {
1919  difft = articularCoordinates[i] - _joint_max[i];
1920  if (difft > diff)
1921  {
1922  diff = difft;
1923  artNumb = (int)(i+1);
1924  }
1925  }
1926  }
1927 
1928  if (artNumb != 0)
1929  std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" <<std::endl;
1930 
1931  return artNumb;
1932 }
1933 
1945 void
1946 vpSimulatorAfma6::getCameraDisplacement(vpColVector &displacement)
1947 {
1948  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
1949 }
1950 
1960 void
1961 vpSimulatorAfma6::getArticularDisplacement(vpColVector &displacement)
1962 {
1964 }
1965 
1984 void
1986  vpColVector &displacement)
1987 {
1988  displacement.resize (6);
1989  displacement = 0;
1990  vpColVector q_cur(6);
1991 
1992  q_cur = get_artCoord();
1993 
1994  if ( ! first_time_getdis )
1995  {
1996  switch (frame)
1997  {
1998  case vpRobot::CAMERA_FRAME:
1999  {
2000  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2001  return;
2002  }
2003 
2005  {
2006  displacement = q_cur - q_prev_getdis;
2007  break ;
2008  }
2009 
2011  {
2012  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2013  return;
2014  }
2015 
2016  case vpRobot::MIXT_FRAME:
2017  {
2018  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2019  return;
2020  }
2021  }
2022  }
2023  else
2024  {
2025  first_time_getdis = false;
2026  }
2027 
2028  // Memorize the joint position for the next call
2029  q_prev_getdis = q_cur;
2030 }
2031 
2078 bool
2079 vpSimulatorAfma6::readPosFile(const std::string &filename, vpColVector &q)
2080 {
2081  std::ifstream fd(filename.c_str(), std::ios::in);
2082 
2083  if(! fd.is_open()) {
2084  return false;
2085  }
2086 
2087  std::string line;
2088  std::string key("R:");
2089  std::string id("#AFMA6 - Position");
2090  bool pos_found = false;
2091  int lineNum = 0;
2092 
2093  q.resize(njoint);
2094 
2095  while(std::getline(fd, line)) {
2096  lineNum ++;
2097  if (lineNum == 1) {
2098  if(! (line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
2099  std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
2100  return false;
2101  }
2102  }
2103  if((line.compare(0, 1, "#") == 0)) { // skip comment
2104  continue;
2105  }
2106  if((line.compare(0, key.size(), key) == 0)) { // decode position
2107  // check if there are at least njoint values in the line
2108  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2109  if (chain.size() < njoint+1) // try to split with tab separator
2110  chain = vpIoTools::splitChain(line, std::string("\t"));
2111  if(chain.size() < njoint+1)
2112  continue;
2113 
2114  std::istringstream ss(line);
2115  std::string key_;
2116  ss >> key_;
2117  for (unsigned int i=0; i< njoint; i++)
2118  ss >> q[i];
2119  pos_found = true;
2120  break;
2121  }
2122  }
2123 
2124  // converts rotations from degrees into radians
2125  q[3] = vpMath::rad(q[3]);
2126  q[4] = vpMath::rad(q[4]);
2127  q[5] = vpMath::rad(q[5]);
2128 
2129  fd.close();
2130 
2131  if (!pos_found) {
2132  std::cout << "Error: unable to find a position for Afma6 robot in " << filename << std::endl;
2133  return false;
2134  }
2135 
2136  return true;
2137 }
2138 
2161 bool
2162 vpSimulatorAfma6::savePosFile(const std::string &filename, const vpColVector &q)
2163 {
2164  FILE * fd ;
2165  fd = fopen(filename.c_str(), "w") ;
2166  if (fd == NULL)
2167  return false;
2168 
2169  fprintf(fd, "\
2170 #AFMA6 - Position - Version 2.01\n\
2171 #\n\
2172 # R: X Y Z A B C\n\
2173 # Joint position: X, Y, Z: translations in meters\n\
2174 # A, B, C: rotations in degrees\n\
2175 #\n\
2176 #\n\n");
2177 
2178  // Save positions in mm and deg
2179  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2180  q[0],
2181  q[1],
2182  q[2],
2183  vpMath::deg(q[3]),
2184  vpMath::deg(q[4]),
2185  vpMath::deg(q[5]));
2186 
2187  fclose(fd) ;
2188  return (true);
2189 }
2190 
2198 void
2199 vpSimulatorAfma6::move(const char *filename)
2200 {
2201  vpColVector q;
2202 
2203  try
2204  {
2205  this->readPosFile(filename, q);
2208  }
2209  catch(...)
2210  {
2211  throw;
2212  }
2213 }
2214 
2224 void
2226 {
2227  vpAfma6::get_cMe(cMe) ;
2228 }
2229 
2237 void
2239 {
2240  vpHomogeneousMatrix cMe ;
2241  vpAfma6::get_cMe(cMe) ;
2242 
2243  cVe.buildFrom(cMe) ;
2244 }
2245 
2255 void
2257 {
2258  try
2259  {
2260  vpAfma6::get_eJe(get_artCoord(), eJe_) ;
2261  }
2262  catch(...)
2263  {
2264  vpERROR_TRACE("catch exception ") ;
2265  throw ;
2266  }
2267 }
2268 
2279 void
2281 {
2282  try
2283  {
2284  vpColVector articularCoordinates = get_artCoord();
2285  vpAfma6::get_fJe(articularCoordinates, fJe_) ;
2286  }
2287  catch(...)
2288  {
2289  vpERROR_TRACE("Error caught");
2290  throw ;
2291  }
2292 }
2293 
2297 void
2299 {
2301  return;
2302 
2303  vpColVector stop(6);
2304  stop = 0;
2305  set_artVel(stop);
2306  set_velocity(stop);
2308 }
2309 
2310 
2311 
2312 /**********************************************************************************/
2313 /**********************************************************************************/
2314 /**********************************************************************************/
2315 /**********************************************************************************/
2316 
2325 void
2327 {
2328  // set scene_dir from #define VISP_SCENE_DIR if it exists
2329  // VISP_SCENES_DIR may contain multiple locations separated by ";"
2330  std::string scene_dir_;
2331  std::vector<std::string> scene_dirs = vpIoTools::splitChain(std::string(VISP_SCENES_DIR), std::string(";"));
2332  bool sceneDirExists = false;
2333  for(size_t i=0; i < scene_dirs.size(); i++)
2334  if (vpIoTools::checkDirectory(scene_dirs[i]) == true) { // directory exists
2335  scene_dir_ = scene_dirs[i];
2336  sceneDirExists = true;
2337  break;
2338  }
2339  if (! sceneDirExists) {
2340  try {
2341  scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR");
2342  std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2343  }
2344  catch (...) {
2345  std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2346  }
2347  }
2348 
2349 
2350  unsigned int name_length = 30; // the size of this kind of string "/afma6_arm2.bnd"
2351  if (scene_dir_.size() > FILENAME_MAX)
2352  throw vpException (vpException::dimensionError, "Cannot initialize Afma6 simulator");
2353  unsigned int full_length = (unsigned int)scene_dir_.size() + name_length;
2354  if (full_length > FILENAME_MAX)
2355  throw vpException (vpException::dimensionError, "Cannot initialize Afma6 simulator");
2356 
2357  char *name_cam = new char [full_length];
2358 
2359  strcpy(name_cam, scene_dir_.c_str());
2360  strcat(name_cam,"/camera.bnd");
2361  set_scene(name_cam,&camera,cameraFactor);
2362 
2363  if (arm_dir.size() > FILENAME_MAX)
2364  throw vpException (vpException::dimensionError, "Cannot initialize Afma6 simulator");
2365  full_length = (unsigned int)arm_dir.size() + name_length;
2366  if (full_length > FILENAME_MAX)
2367  throw vpException (vpException::dimensionError, "Cannot initialize Afma6 simulator");
2368 
2369  char *name_arm = new char [full_length];
2370  strcpy(name_arm, arm_dir.c_str());
2371  strcat(name_arm,"/afma6_gate.bnd");
2372  std::cout <<"name arm: " << name_arm << std::endl;
2373  set_scene(name_arm, robotArms, 1.0);
2374  strcpy(name_arm, arm_dir.c_str());
2375  strcat(name_arm,"/afma6_arm1.bnd");
2376  set_scene(name_arm, robotArms+1, 1.0);
2377  strcpy(name_arm, arm_dir.c_str());
2378  strcat(name_arm,"/afma6_arm2.bnd");
2379  set_scene(name_arm, robotArms+2, 1.0);
2380  strcpy(name_arm, arm_dir.c_str());
2381  strcat(name_arm,"/afma6_arm3.bnd");
2382  set_scene(name_arm, robotArms+3, 1.0);
2383  strcpy(name_arm, arm_dir.c_str());
2384  strcat(name_arm,"/afma6_arm4.bnd");
2385  set_scene(name_arm, robotArms+4, 1.0);
2386 
2388  tool = getToolType();
2389  strcpy(name_arm, arm_dir.c_str());
2390  switch (tool) {
2391  case vpAfma6::TOOL_CCMOP: {
2392  strcat(name_arm,"/afma6_tool_ccmop.bnd");
2393  break;
2394  }
2395  case vpAfma6::TOOL_GRIPPER: {
2396  strcat(name_arm,"/afma6_tool_gripper.bnd");
2397  break;
2398  }
2399  case vpAfma6::TOOL_VACUUM: {
2400  strcat(name_arm,"/afma6_tool_vacuum.bnd");
2401  break;
2402  }
2403  case vpAfma6::TOOL_CUSTOM: {
2404  std::cout << "The custom tool is not handled in vpSimulatorAfma6.cpp" << std::endl;
2405  break;
2406  }
2408  std::cout << "The generic camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
2409  break;
2410  }
2411  }
2412  set_scene(name_arm, robotArms+5, 1.0);
2413 
2414  add_rfstack(IS_BACK);
2415 
2416  add_vwstack ("start","depth", 0.0, 100.0);
2417  add_vwstack ("start","window", -0.1,0.1,-0.1,0.1);
2418  add_vwstack ("start","type", PERSPECTIVE);
2419 //
2420 // sceneInitialized = true;
2421 // displayObject = true;
2422  displayCamera = true;
2423 
2424  delete [] name_cam;
2425  delete [] name_arm;
2426 }
2427 
2428 
2429 void
2431 {
2432  bool changed = false;
2433  vpHomogeneousMatrix displacement = navigation(I_,changed);
2434 
2435  //if (displacement[2][3] != 0)
2436  if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2437  camMf2 = camMf2*displacement;
2438 
2439  f2Mf = camMf2.inverse()*camMf;
2440 
2441  camMf = camMf2* displacement * f2Mf;
2442 
2443  double u;
2444  double v;
2445  //if(px_ext != 1 && py_ext != 1)
2446  // we assume px_ext and py_ext > 0
2447  if( (std::fabs(px_ext-1.) > vpMath::maximum(px_ext,1.)*std::numeric_limits<double>::epsilon())
2448  && (std::fabs(py_ext-1) > vpMath::maximum(py_ext,1.)*std::numeric_limits<double>::epsilon()))
2449  {
2450  u = (double)I_.getWidth()/(2*px_ext);
2451  v = (double)I_.getHeight()/(2*py_ext);
2452  }
2453  else
2454  {
2455  u = (double)I_.getWidth()/(vpMath::minimum(I_.getWidth(),I_.getHeight()));
2456  v = (double)I_.getHeight()/(vpMath::minimum(I_.getWidth(),I_.getHeight()));
2457  }
2458 
2459  float w44o[4][4],w44cext[4][4],x,y,z;
2460 
2461  vp2jlc_matrix(camMf.inverse(),w44cext);
2462 
2463  add_vwstack ("start","cop", w44cext[3][0],w44cext[3][1],w44cext[3][2]);
2464  x = w44cext[2][0] + w44cext[3][0];
2465  y = w44cext[2][1] + w44cext[3][1];
2466  z = w44cext[2][2] + w44cext[3][2];
2467  add_vwstack ("start","vrp", x,y,z);
2468  add_vwstack ("start","vpn", w44cext[2][0],w44cext[2][1],w44cext[2][2]);
2469  add_vwstack ("start","vup", w44cext[1][0],w44cext[1][1],w44cext[1][2]);
2470  add_vwstack ("start","window", -u, u, -v, v);
2471 
2472  vpHomogeneousMatrix fMit[8];
2473  get_fMi(fMit);
2474 
2475  vp2jlc_matrix(vpHomogeneousMatrix(0,0,0,0,0,0),w44o);
2476  display_scene(w44o,robotArms[0],I_, curColor);
2477 
2478  vp2jlc_matrix(fMit[0],w44o);
2479  display_scene(w44o,robotArms[1],I_, curColor);
2480 
2481  vp2jlc_matrix(fMit[2],w44o);
2482  display_scene(w44o,robotArms[2],I_, curColor);
2483 
2484  vp2jlc_matrix(fMit[3],w44o);
2485  display_scene(w44o,robotArms[3],I_, curColor);
2486 
2487  vp2jlc_matrix(fMit[4],w44o);
2488  display_scene(w44o,robotArms[4],I_, curColor);
2489 
2490  vp2jlc_matrix(fMit[5],w44o);
2491  display_scene(w44o,robotArms[5],I_, curColor);
2492 
2493  if (displayCamera)
2494  {
2495  vpHomogeneousMatrix cMe;
2496  get_cMe(cMe);
2497  cMe = cMe.inverse();
2498  cMe = fMit[6] * cMe;
2499  vp2jlc_matrix(cMe,w44o);
2500  display_scene(w44o,camera, I_, camColor);
2501  }
2502 
2503  if (displayObject)
2504  {
2505  vp2jlc_matrix(fMo,w44o);
2506  display_scene(w44o,scene,I_, curColor);
2507  }
2508 }
2509 
2526 bool
2528 {
2529  vpColVector stop(6);
2530  bool status = true;
2531  stop = 0;
2532  set_artVel(stop);
2533  set_velocity(stop);
2534  vpHomogeneousMatrix fMc_;
2535  fMc_ = fMo * cMo_.inverse();
2536 
2537  vpColVector articularCoordinates = get_artCoord();
2538  int nbSol = getInverseKinematics(fMc_, articularCoordinates, true, verbose_);
2539 
2540  if (nbSol == 0) {
2541  status = false;
2542  vpERROR_TRACE ("Positionning error. Position unreachable");
2543  }
2544 
2545  if (verbose_)
2546  std::cout << "Used joint coordinates (rad): " << articularCoordinates.t() << std::endl;
2547 
2548  set_artCoord(articularCoordinates);
2549 
2550  compute_fMi();
2551 
2552  return status;
2553 }
2554 
2567 void
2569 {
2570  vpColVector stop(6);
2571  stop = 0;
2572  set_artVel(stop);
2573  set_velocity(stop);
2574  vpHomogeneousMatrix fMit[8];
2575  get_fMi(fMit);
2576  fMo = fMit[7] * cMo_;
2577 }
2578 
2589 bool
2591 {
2592  // get rid of max velocity
2593  double vMax = getMaxTranslationVelocity();
2594  double wMax = getMaxRotationVelocity();
2595  setMaxTranslationVelocity(10.*vMax);
2596  setMaxRotationVelocity(10.*wMax);
2597 
2598  vpColVector v(3),w(3),vel(6);
2599  vpHomogeneousMatrix cdMc;
2601  vpColVector err(6);err=1.;
2602  const double lambda = 5.;
2603 
2605 
2606  unsigned int i,iter=0;
2607  while((iter++<300) & (err.euclideanNorm()>errMax))
2608  {
2609  double t = vpTime::measureTimeMs();
2610 
2611  // update image
2612  if(Iint != NULL)
2613  {
2614  vpDisplay::display(*Iint);
2615  getInternalView(*Iint);
2616  vpDisplay::flush(*Iint);
2617  }
2618 
2619  // update pose error
2620  cdMc = cdMo_*get_cMo().inverse();
2621  cdMc.extract(cdRc);
2622  cdMc.extract(cdTc);
2623  cdTUc.buildFrom(cdRc);
2624 
2625  // compute v,w and velocity
2626  v = -lambda*cdRc.t()*cdTc;
2627  w = -lambda*cdTUc;
2628  for(i=0;i<3;++i)
2629  {
2630  vel[i] = v[i];
2631  vel[i+3] = w[i];
2632  err[i] = cdTc[i];
2633  err[i+3] = cdTUc[i];
2634  }
2635 
2636  // update feat
2638 
2639  // wait for it
2640  vpTime::wait(t,10);
2641  }
2642  vel=0.;
2643  set_velocity(vel);
2644  set_artVel(vel);
2646  setMaxRotationVelocity(wMax);
2647 
2648  //std::cout << "setPosition: final error " << err.t() << std::endl;
2649  return(err.euclideanNorm()<= errMax);
2650 }
2651 
2652 #elif !defined(VISP_BUILD_SHARED_LIBS)
2653 // Work arround to avoid warning: libvisp_robot.a(vpSimulatorAfma6.cpp.o) has no symbols
2654 void dummy_vpSimulatorAfma6() {};
2655 #endif
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:76
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
vpRxyzVector _erc
Definition: vpAfma6.h:206
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:157
vpTranslationVector _etc
Definition: vpAfma6.h:205
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:191
Error that can be emited by the vpRobot class and its derivates.
static bool checkDirectory(const char *dirname)
Definition: vpIoTools.cpp:358
unsigned int getWidth() const
Definition: vpImage.h:226
void setMaxTranslationVelocity(const double maxVt)
Definition: vpRobot.cpp:238
void get_eJe(vpMatrix &eJe)
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition: vpAfma6.cpp:542
double getSamplingTime() const
vpAfma6ToolType getToolType() const
Get the current tool type.
Definition: vpAfma6.h:158
Implementation of an homogeneous matrix and operations on such kind of matrices.
void get_cVe(vpVelocityTwistMatrix &cVe)
double euclideanNorm() const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:723
void move(const char *filename)
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
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
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:892
error that can be emited by ViSP classes.
Definition: vpException.h:73
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:115
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void track(const vpHomogeneousMatrix &cMo)
static const double defaultPositioningVelocity
vpRotationMatrix t() const
vpControlFrameType
Definition: vpRobot.h:76
double get_py() const
static bool savePosFile(const std::string &filename, const vpColVector &q)
void getExternalImage(vpImage< vpRGBa > &I)
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpAfma6.h:214
double get_y() const
Get the point y coordinate in the image plane.
Definition: vpPoint.cpp:458
static const vpColor green
Definition: vpColor.h:166
vpHomogeneousMatrix fMo
static void flush(const vpImage< unsigned char > &I)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
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 setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:189
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition: vpAfma6.h:102
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.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement)
bool singularityTest(const vpColVector q, vpMatrix &J)
Initialize the velocity controller.
Definition: vpRobot.h:68
static bool readPosFile(const std::string &filename, vpColVector &q)
vpRobotStateType
Definition: vpRobot.h:64
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
void setExternalCameraPosition(const vpHomogeneousMatrix camMf_)
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)
static void display(const vpImage< unsigned char > &I)
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:839
vpRowVector t() const
void getInternalView(vpImage< vpRGBa > &I)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
Generic class defining intrinsic camera parameters.
vpHomogeneousMatrix getExternalCameraPosition() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
void extract(vpRotationMatrix &R) const
double get_x() const
Get the point x coordinate in the image plane.
Definition: vpPoint.cpp:456
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
void setCameraParameters(const vpCameraParameters &cam)
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
void set_velocity(const vpColVector &vel)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
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
This class aims to be a basis used to create all the simulators of robots.
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:262
double sumSquare() const
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)
double getPositioningVelocity(void)
double _long_56
Definition: vpAfma6.h:201
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 get_fJe(vpMatrix &fJe)
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
vpHomogeneousMatrix inverse() const
vpHomogeneousMatrix _eMc
Definition: vpAfma6.h:208
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
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
void get_cMe(vpHomogeneousMatrix &cMe)
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
Definition: vpMatrix.cpp:1741
double _joint_max[6]
Definition: vpAfma6.h:202
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)
VISP_EXPORT double getMinTimeForUsleepCall()
Definition: vpTime.cpp:82
void set_artVel(const vpColVector &vel)
void get_fMi(vpHomogeneousMatrix *fMit)
static const char *const CONST_CCMOP_CAMERA_NAME
Definition: vpAfma6.h:97
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:961
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
vpHomogeneousMatrix camMf2
double _joint_min[6]
Definition: vpAfma6.h:203
void findHighestPositioningSpeed(vpColVector &q)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:225