ViSP  2.8.0
vpSimulatorViper850.cpp
1 /****************************************************************************
2  *
3  * $Id: vpSimulatorViper850.cpp 4317 2013-07-17 09:40:17Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2013 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Class which provides a simulator for the robot Viper850.
36  *
37  * Authors:
38  * Nicolas Melchior
39  *
40  *****************************************************************************/
41 
42 
43 
44 #include <visp/vpSimulatorViper850.h>
45 #include <visp/vpTime.h>
46 #include <visp/vpImagePoint.h>
47 #include <visp/vpPoint.h>
48 #include <visp/vpMeterPixelConversion.h>
49 #include <visp/vpIoTools.h>
50 #include <cmath> // std::fabs
51 #include <limits> // numeric_limits
52 #include <string>
53 #if defined(WIN32) || defined(VISP_HAVE_PTHREAD)
54 
56 
61 {
62  init();
63  initDisplay();
64 
66 
67  #if defined(WIN32)
68  mutex_fMi = CreateMutex(NULL,FALSE,NULL);
69  mutex_artVel = CreateMutex(NULL,FALSE,NULL);
70  mutex_artCoord = CreateMutex(NULL,FALSE,NULL);
71  mutex_velocity = CreateMutex(NULL,FALSE,NULL);
72  mutex_display = CreateMutex(NULL,FALSE,NULL);
73 
74 
75  DWORD dwThreadIdArray;
76  hThread = CreateThread(
77  NULL, // default security attributes
78  0, // use default stack size
79  launcher, // thread function name
80  this, // argument to thread function
81  0, // use default creation flags
82  &dwThreadIdArray); // returns the thread identifier
83  #elif defined (VISP_HAVE_PTHREAD)
84  pthread_mutex_init(&mutex_fMi, NULL);
85  pthread_mutex_init(&mutex_artVel, NULL);
86  pthread_mutex_init(&mutex_artCoord, NULL);
87  pthread_mutex_init(&mutex_velocity, NULL);
88  pthread_mutex_init(&mutex_display, NULL);
89 
90  pthread_attr_init(&attr);
91  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
92 
93  pthread_create(&thread, NULL, launcher, (void *)this);
94  #endif
95 
96  compute_fMi();
97 }
98 
106 {
107  init();
108  initDisplay();
109 
111 
112  #if defined(WIN32)
113  mutex_fMi = CreateMutex(NULL,FALSE,NULL);
114  mutex_artVel = CreateMutex(NULL,FALSE,NULL);
115  mutex_artCoord = CreateMutex(NULL,FALSE,NULL);
116  mutex_velocity = CreateMutex(NULL,FALSE,NULL);
117  mutex_display = CreateMutex(NULL,FALSE,NULL);
118 
119 
120  DWORD dwThreadIdArray;
121  hThread = CreateThread(
122  NULL, // default security attributes
123  0, // use default stack size
124  launcher, // thread function name
125  this, // argument to thread function
126  0, // use default creation flags
127  &dwThreadIdArray); // returns the thread identifier
128  #elif defined(VISP_HAVE_PTHREAD)
129  pthread_mutex_init(&mutex_fMi, NULL);
130  pthread_mutex_init(&mutex_artVel, NULL);
131  pthread_mutex_init(&mutex_artCoord, NULL);
132  pthread_mutex_init(&mutex_velocity, NULL);
133  pthread_mutex_init(&mutex_display, NULL);
134 
135  pthread_attr_init(&attr);
136  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
137 
138  pthread_create(&thread, NULL, launcher, (void *)this);
139  #endif
140 
141  compute_fMi();
142 }
143 
148 {
149  robotStop = true;
150 
151  #if defined(WIN32)
152  WaitForSingleObject(hThread,INFINITE);
153  CloseHandle(hThread);
154  CloseHandle(mutex_fMi);
155  CloseHandle(mutex_artVel);
156  CloseHandle(mutex_artCoord);
157  CloseHandle(mutex_velocity);
158  CloseHandle(mutex_display);
159  #elif defined(VISP_HAVE_PTHREAD)
160  pthread_attr_destroy(&attr);
161  pthread_join(thread, NULL);
162  pthread_mutex_destroy(&mutex_fMi);
163  pthread_mutex_destroy(&mutex_artVel);
164  pthread_mutex_destroy(&mutex_artCoord);
165  pthread_mutex_destroy(&mutex_velocity);
166  pthread_mutex_destroy(&mutex_display);
167  #endif
168 
169  if (robotArms != NULL)
170  {
171  // free_Bound_scene (&(camera));
172  for(int i = 0; i < 6; i++)
173  free_Bound_scene (&(robotArms[i]));
174  }
175 
176  delete[] robotArms;
177  delete[] fMi;
178 }
179 
188 void
190 {
191  // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
192  if (vpIoTools::checkDirectory(VISP_ROBOT_ARMS_DIR) == true) // directory exists
193  arm_dir = VISP_ROBOT_ARMS_DIR;
194  else {
195  try {
196  arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
197  std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
198  }
199  catch (...) {
200  std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
201  }
202  }
203 
205  toolCustom = false;
206 
207  size_fMi = 8;
208  fMi = new vpHomogeneousMatrix[8];
211 
212  zeroPos.resize(njoint);
213  zeroPos = 0;
214  zeroPos[1] = -M_PI/2; zeroPos[2] = M_PI;
215  reposPos.resize(njoint);
216  reposPos = 0;
217  reposPos[1] = -M_PI/2; reposPos[2] = M_PI; reposPos[4] = M_PI/2;
218 
219  artCoord = reposPos;
220  artVel = 0;
221 
222  q_prev_getdis.resize(njoint);
223  q_prev_getdis = 0;
224  first_time_getdis = true;
225 
226  positioningVelocity = defaultPositioningVelocity ;
227 
230 
231  // Software joint limits in radians
232  //joint_min.resize(njoint);
233  joint_min[0] = vpMath::rad(-50);
234  joint_min[1] = vpMath::rad(-135);
235  joint_min[2] = vpMath::rad(-40);
236  joint_min[3] = vpMath::rad(-190);
237  joint_min[4] = vpMath::rad(-110);
238  joint_min[5] = vpMath::rad(-184);
239  //joint_max.resize(njoint);
240  joint_max[0] = vpMath::rad(50);
241  joint_max[1] = vpMath::rad(-40);
242  joint_max[2] = vpMath::rad(215);
243  joint_max[3] = vpMath::rad(190);
244  joint_max[4] = vpMath::rad(110);
245  joint_max[5] = vpMath::rad(184);
246 }
247 
251 void
253 {
254  robotArms = NULL;
255  robotArms = new Bound_scene[6];
256  initArms();
258  cameraParam.initPersProjWithoutDistortion (558.5309599, 556.055053, 320, 240);
260  vpCameraParameters tmp;
261  getCameraParameters(tmp,640,480);
262  px_int = tmp.get_px();
263  py_int = tmp.get_py();
264  sceneInitialized = true;
265 }
266 
267 
283 void
286 {
287  this->projModel = projModel;
288 
289  // Use here default values of the robot constant parameters.
290  switch (tool) {
292  erc[0] = vpMath::rad(0.07); // rx
293  erc[1] = vpMath::rad(2.76); // ry
294  erc[2] = vpMath::rad(-91.50); // rz
295  etc[0] = -0.0453; // tx
296  etc[1] = 0.0005; // ty
297  etc[2] = 0.0728; // tz
298 
299  setCameraParameters(vpCameraParameters(1232.0, 1233.0, 320, 240));
300  break;
301  }
303  erc[0] = vpMath::rad(0.1527764261); // rx
304  erc[1] = vpMath::rad(1.285092455); // ry
305  erc[2] = vpMath::rad(-90.75777848); // rz
306  etc[0] = -0.04558630174; // tx
307  etc[1] = -0.00134326752; // ty
308  etc[2] = 0.001000828017; // tz
309 
310  setCameraParameters(vpCameraParameters(868.0, 869.0, 320, 240));
311  break;
312  }
315  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
316  break;
317  }
318  }
319 
320  vpRotationMatrix eRc(erc);
321  this->eMc.buildFrom(etc, eRc);
322 
323  setToolType(tool);
324  return ;
325 }
326 
337 void
339  const unsigned int &image_width,
340  const unsigned int &image_height)
341 {
342  if (toolCustom)
343  {
344  vpCameraParameters(px_int,py_int,image_width/2,image_height/2);
345  }
346  // Set default parameters
347  switch (getToolType()) {
349  // Set default intrinsic camera parameters for 640x480 images
350  if (image_width == 640 && image_height == 480)
351  {
352  std::cout << "Get default camera parameters for camera \""
353  << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl;
354  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240);
355  }
356  else {
357  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
358  }
359  break;
360  }
362  // Set default intrinsic camera parameters for 640x480 images
363  if (image_width == 640 && image_height == 480) {
364  std::cout << "Get default camera parameters for camera \""
365  << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl;
366  cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240);
367  }
368  else {
369  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
370  }
371  break;
372  }
375  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
376  break;
377  }
378  }
379  return;
380 }
381 
390 void
392  const vpImage<unsigned char> &I)
393 {
395 }
396 
405 void
407  const vpImage<vpRGBa> &I)
408 {
410 }
411 
412 
418 void
420 {
421  px_int = cam.get_px();
422  py_int = cam.get_py();
423  toolCustom = true;
424 }
425 
426 
430 void
432 {
433  double tcur_1 = tcur;// temporary variable used to store the last time since the last command
434 
435  while (!robotStop)
436  {
437  //Get current time
438  tprev = tcur_1;
440 
441 
443  setVelocityCalled = false;
445 
446  double ellapsedTime = (tcur - tprev) * 1e-3;
447  if(constantSamplingTimeMode){//if we want a constant velocity, we force the ellapsed time to the given samplingTime
448  ellapsedTime = getSamplingTime(); // in second
449  }
450 
451  vpColVector articularCoordinates = get_artCoord();
452  articularCoordinates = get_artCoord();
453  vpColVector articularVelocities = get_artVel();
454 
455  if (jointLimit)
456  {
457  double art = articularCoordinates[jointLimitArt-1] + ellapsedTime*articularVelocities[jointLimitArt-1];
458  if (art <= joint_min[jointLimitArt-1] || art >= joint_max[jointLimitArt-1]) {
459  if (verbose_) {
460  std::cout << "Joint " << jointLimitArt-1
461  << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt-1]) << " < " << vpMath::deg(art) << " < " << vpMath::deg(joint_max[jointLimitArt-1]) << std::endl;
462  }
463  articularVelocities = 0.0;
464  }
465  else
466  jointLimit = false;
467  }
468 
469  articularCoordinates[0] = articularCoordinates[0] + ellapsedTime*articularVelocities[0];
470  articularCoordinates[1] = articularCoordinates[1] + ellapsedTime*articularVelocities[1];
471  articularCoordinates[2] = articularCoordinates[2] + ellapsedTime*articularVelocities[2];
472  articularCoordinates[3] = articularCoordinates[3] + ellapsedTime*articularVelocities[3];
473  articularCoordinates[4] = articularCoordinates[4] + ellapsedTime*articularVelocities[4];
474  articularCoordinates[5] = articularCoordinates[5] + ellapsedTime*articularVelocities[5];
475 
476  int jl = isInJointLimit();
477 
478  if (jl != 0 && jointLimit == false)
479  {
480  if (jl < 0)
481  ellapsedTime = (joint_min[(unsigned int)(-jl-1)] - articularCoordinates[(unsigned int)(-jl-1)])/(articularVelocities[(unsigned int)(-jl-1)]);
482  else
483  ellapsedTime = (joint_max[(unsigned int)(jl-1)] - articularCoordinates[(unsigned int)(jl-1)])/(articularVelocities[(unsigned int)(jl-1)]);
484 
485  for (unsigned int i = 0; i < 6; i++)
486  articularCoordinates[i] = articularCoordinates[i] + ellapsedTime*articularVelocities[i];
487 
488  jointLimit = true;
489  jointLimitArt = (unsigned int)fabs((double)jl);
490  }
491 
492  set_artCoord(articularCoordinates);
493  set_artVel(articularVelocities);
494 
495  compute_fMi();
496 
497  if (displayAllowed)
498  {
502  }
503 
505  {
506  while (get_displayBusy()) vpTime::wait(2);
508  set_displayBusy(false);
509  }
510 
511 
513  {
514  vpHomogeneousMatrix fMit[8];
515  get_fMi(fMit);
516 
517  //vpDisplay::displayFrame(I,getExternalCameraPosition ()*fMi[6],cameraParam,0.2,vpColor::none);
518 
519  vpImagePoint iP, iP_1;
520  vpPoint pt;
521  pt.setWorldCoordinates (0,0,0);
522 
525  pt.track(getExternalCameraPosition ()*fMit[0]);
528  for (int k = 1; k < 7; k++)
529  {
530  pt.track(getExternalCameraPosition ()*fMit[k-1]);
532 
533  pt.track(getExternalCameraPosition ()*fMit[k]);
535 
537  }
539  }
540 
542 
543  vpTime::wait( tcur, 1000 * getSamplingTime() );
544  tcur_1 = tcur;
545  }else{
547  }
548  }
549 }
550 
561 void
563 {
564  //vpColVector q = get_artCoord();
565  vpColVector q(6);//; = get_artCoord();
566  q = get_artCoord();
567 
568  vpHomogeneousMatrix fMit[8];
569 
570  double q1 = q[0];
571  double q2 = q[1];
572  double q3 = q[2];
573  double q4 = q[3];
574  double q5 = q[4];
575  double q6 = q[5];
576 
577  double c1 = cos(q1);
578  double s1 = sin(q1);
579  double c2 = cos(q2);
580  double s2 = sin(q2);
581  double c23 = cos(q2+q3);
582  double s23 = sin(q2+q3);
583  double c4 = cos(q4);
584  double s4 = sin(q4);
585  double c5 = cos(q5);
586  double s5 = sin(q5);
587  double c6 = cos(q6);
588  double s6 = sin(q6);
589 
590  fMit[0][0][0] = c1;
591  fMit[0][1][0] = s1;
592  fMit[0][2][0] = 0;
593  fMit[0][0][1] = 0;
594  fMit[0][1][1] = 0;
595  fMit[0][2][1] = -1;
596  fMit[0][0][2] = -s1;
597  fMit[0][1][2] = c1;
598  fMit[0][2][2] = 0;
599  fMit[0][0][3] = a1*c1;
600  fMit[0][1][3] = a1*s1;
601  fMit[0][2][3] = d1;
602 
603  fMit[1][0][0] = c1*c2;
604  fMit[1][1][0] = s1*c2;
605  fMit[1][2][0] = -s2;
606  fMit[1][0][1] = -c1*s2;
607  fMit[1][1][1] = -s1*s2;
608  fMit[1][2][1] = -c2;
609  fMit[1][0][2] = -s1;
610  fMit[1][1][2] = c1;
611  fMit[1][2][2] = 0;
612  fMit[1][0][3] = c1*(a2*c2+a1);
613  fMit[1][1][3] = s1*(a2*c2+a1);
614  fMit[1][2][3] = d1-a2*s2;
615 
616  double quickcomp1 = a3*c23-a2*c2-a1;
617 
618  fMit[2][0][0] = -c1*c23;
619  fMit[2][1][0] = -s1*c23;
620  fMit[2][2][0] = s23;
621  fMit[2][0][1] = s1;
622  fMit[2][1][1] = -c1;
623  fMit[2][2][1] = 0;
624  fMit[2][0][2] = c1*s23;
625  fMit[2][1][2] = s1*s23;
626  fMit[2][2][2] = c23;
627  fMit[2][0][3] = -c1*quickcomp1;
628  fMit[2][1][3] = -s1*quickcomp1;
629  fMit[2][2][3] = a3*s23-a2*s2+d1;
630 
631  double quickcomp2 = c1*(s23*d4 - quickcomp1);
632  double quickcomp3 = s1*(s23*d4 - quickcomp1);
633 
634  fMit[3][0][0] = -c1*c23*c4+s1*s4;
635  fMit[3][1][0] = -s1*c23*c4-c1*s4;
636  fMit[3][2][0] = s23*c4;
637  fMit[3][0][1] = c1*s23;
638  fMit[3][1][1] = s1*s23;
639  fMit[3][2][1] = c23;
640  fMit[3][0][2] = -c1*c23*s4-s1*c4;
641  fMit[3][1][2] = -s1*c23*s4+c1*c4;
642  fMit[3][2][2] = s23*s4;
643  fMit[3][0][3] = quickcomp2;
644  fMit[3][1][3] = quickcomp3;
645  fMit[3][2][3] = c23*d4+a3*s23-a2*s2+d1;
646 
647  fMit[4][0][0] = c1*(s23*s5-c5*c23*c4)+s1*c5*s4;
648  fMit[4][1][0] = s1*(s23*s5-c5*c23*c4)-c1*c5*s4;
649  fMit[4][2][0] = s23*c4*c5+c23*s5;
650  fMit[4][0][1] = c1*c23*s4+s1*c4;
651  fMit[4][1][1] = s1*c23*s4-c1*c4;
652  fMit[4][2][1] = -s23*s4;
653  fMit[4][0][2] = c1*(s23*c5+s5*c23*c4)-s1*s5*s4;
654  fMit[4][1][2] = s1*(s23*c5+s5*c23*c4)+c1*s5*s4;
655  fMit[4][2][2] = -s23*c4*s5+c23*c5;
656  fMit[4][0][3] = quickcomp2;
657  fMit[4][1][3] = quickcomp3;
658  fMit[4][2][3] = c23*d4+a3*s23-a2*s2+d1;
659 
660  fMit[5][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
661  fMit[5][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
662  fMit[5][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
663  fMit[5][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
664  fMit[5][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
665  fMit[5][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
666  fMit[5][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
667  fMit[5][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
668  fMit[5][2][2] = -s23*c4*s5+c23*c5;
669  fMit[5][0][3] = quickcomp2;
670  fMit[5][1][3] = quickcomp3;
671  fMit[5][2][3] = s23*a3+c23*d4-a2*s2+d1;
672 
673  fMit[6][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
674  fMit[6][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
675  fMit[6][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
676  fMit[6][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
677  fMit[6][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
678  fMit[6][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
679  fMit[6][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
680  fMit[6][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
681  fMit[6][2][2] = -s23*c4*s5+c23*c5;
682  fMit[6][0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
683  fMit[6][1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
684  fMit[6][2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
685 
687  get_cMe(cMe);
688  cMe = cMe.inverse();
689 // fMit[7] = fMit[6] * cMe;
690  vpViper::get_fMc(q,fMit[7]);
691 
692  #if defined(WIN32)
693  WaitForSingleObject(mutex_fMi,INFINITE);
694  for (int i = 0; i < 8; i++)
695  fMi[i] = fMit[i];
696  ReleaseMutex(mutex_fMi);
697  #elif defined(VISP_HAVE_PTHREAD)
698  pthread_mutex_lock (&mutex_fMi);
699  for (int i = 0; i < 8; i++)
700  fMi[i] = fMit[i];
701  pthread_mutex_unlock (&mutex_fMi);
702  #endif
703 }
704 
705 
713 {
714  switch (newState) {
715  case vpRobot::STATE_STOP: {
716  // Start primitive STOP only if the current state is Velocity
718  stopMotion();
719  }
720  break;
721  }
724  std::cout << "Change the control mode from velocity to position control.\n";
725  stopMotion();
726  }
727  else {
728  //std::cout << "Change the control mode from stop to position control.\n";
729  }
730  break;
731  }
734  std::cout << "Change the control mode from stop to velocity control.\n";
735  }
736  break;
737  }
739  default:
740  break ;
741  }
742 
743  return vpRobot::setRobotState (newState);
744 }
745 
815 void
817 {
819  vpERROR_TRACE ("Cannot send a velocity to the robot "
820  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
822  "Cannot send a velocity to the robot "
823  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
824  }
825 
826  vpColVector vel_sat(6);
827 
828  double scale_trans_sat = 1;
829  double scale_rot_sat = 1;
830  double scale_sat = 1;
831  double vel_trans_max = getMaxTranslationVelocity();
832  double vel_rot_max = getMaxRotationVelocity();
833 
834  double vel_abs; // Absolute value
835 
836  // Velocity saturation
837  switch(frame)
838  {
839  // saturation in cartesian space
840  case vpRobot::CAMERA_FRAME :
842  {
843  if (vel.getRows() != 6)
844  {
845  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
846  throw;
847  }
848 
849  for (unsigned int i = 0 ; i < 3; ++ i)
850  {
851  vel_abs = fabs (vel[i]);
852  if (vel_abs > vel_trans_max && !jointLimit)
853  {
854  vel_trans_max = vel_abs;
855  vpERROR_TRACE ("Excess velocity %g m/s in TRANSLATION "
856  "(axis nr. %d).", vel[i], i+1);
857  }
858 
859  vel_abs = fabs (vel[i+3]);
860  if (vel_abs > vel_rot_max && !jointLimit) {
861  vel_rot_max = vel_abs;
862  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
863  "(axis nr. %d).", vel[i+3], i+4);
864  }
865  }
866 
867  if (vel_trans_max > getMaxTranslationVelocity())
868  scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
869 
870  if (vel_rot_max > getMaxRotationVelocity())
871  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
872 
873  if ( (scale_trans_sat < 1) || (scale_rot_sat < 1) )
874  {
875  if (scale_trans_sat < scale_rot_sat)
876  scale_sat = scale_trans_sat;
877  else
878  scale_sat = scale_rot_sat;
879  }
880  break;
881  }
882 
883  // saturation in joint space
885  {
886  if (vel.getRows() != 6)
887  {
888  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
889  throw;
890  }
891  for (unsigned int i = 0 ; i < 6; ++ i)
892  {
893  vel_abs = fabs (vel[i]);
894  if (vel_abs > vel_rot_max && !jointLimit)
895  {
896  vel_rot_max = vel_abs;
897  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
898  "(axis nr. %d).", vel[i], i+1);
899  }
900  }
901  if (vel_rot_max > getMaxRotationVelocity())
902  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
903  if ( scale_rot_sat < 1 )
904  scale_sat = scale_rot_sat;
905  break;
906  }
907  case vpRobot::MIXT_FRAME :
908  {
909  break;
910  }
911  }
912 
913  set_velocity (vel * scale_sat);
914  setRobotFrame (frame);
915  setVelocityCalled = true;
916 }
917 
918 
922 void
924 {
926 
927  double scale_rot_sat = 1;
928  double scale_sat = 1;
929  double vel_rot_max = getMaxRotationVelocity();
930  double vel_abs;
931 
932  vpColVector articularCoordinates = get_artCoord();
933  vpColVector velocityframe = get_velocity();
934  vpColVector articularVelocity;
935 
936  switch(frame)
937  {
938  case vpRobot::CAMERA_FRAME :
939  {
940  vpMatrix eJe;
942  vpViper850::get_eJe(articularCoordinates,eJe);
943  eJe = eJe.pseudoInverse();
945  singularityTest(articularCoordinates,eJe);
946  articularVelocity = eJe*eVc*velocityframe;
947  set_artVel (articularVelocity);
948  break;
949  }
951  {
952  vpMatrix fJe;
953  vpViper850::get_fJe(articularCoordinates,fJe);
954  fJe = fJe.pseudoInverse();
956  singularityTest(articularCoordinates,fJe);
957  articularVelocity = fJe*velocityframe;
958  set_artVel (articularVelocity);
959  break;
960  }
962  {
963  articularVelocity = velocityframe;
964  set_artVel (articularVelocity);
965  break;
966  }
967  case vpRobot::MIXT_FRAME :
968  {
969  break;
970  }
971  }
972 
973 
974 
975  switch(frame)
976  {
977  case vpRobot::CAMERA_FRAME :
979  {
980  for (unsigned int i = 0 ; i < 6; ++ i)
981  {
982  vel_abs = fabs (articularVelocity[i]);
983  if (vel_abs > vel_rot_max && !jointLimit)
984  {
985  vel_rot_max = vel_abs;
986  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
987  "(axis nr. %d).", articularVelocity[i], i+1);
988  }
989  }
990  if (vel_rot_max > getMaxRotationVelocity())
991  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
992  if ( scale_rot_sat < 1 )
993  scale_sat = scale_rot_sat;
994 
995  set_artVel(articularVelocity * scale_sat);
996  break;
997  }
999  case vpRobot::MIXT_FRAME :
1000  {
1001  break;
1002  }
1003  }
1004 }
1005 
1006 
1053 void
1055 {
1056  vel.resize(6);
1057 
1058  vpColVector articularCoordinates = get_artCoord();
1059  vpColVector articularVelocity = get_artVel();
1060 
1061  switch(frame)
1062  {
1063  case vpRobot::CAMERA_FRAME :
1064  {
1065  vpMatrix eJe;
1067  vpViper850::get_eJe(articularCoordinates,eJe);
1068  vel = cVe*eJe*articularVelocity;
1069  break ;
1070  }
1071  case vpRobot::ARTICULAR_FRAME :
1072  {
1073  vel = articularVelocity;
1074  break ;
1075  }
1076  case vpRobot::REFERENCE_FRAME :
1077  {
1078  vpMatrix fJe;
1079  vpViper850::get_fJe(articularCoordinates,fJe);
1080  vel = fJe*articularVelocity;
1081  break ;
1082  }
1083  case vpRobot::MIXT_FRAME :
1084  {
1085  break ;
1086  }
1087  default:
1088  {
1089  vpERROR_TRACE ("Error in spec of vpRobot. "
1090  "Case not taken in account.");
1091  return;
1092  }
1093  }
1094 }
1095 
1140 {
1141  vpColVector velocity(6);
1142  getVelocity (frame, velocity);
1143 
1144  return velocity;
1145 }
1146 
1147 
1148 void
1150 {
1151  double vel_rot_max = getMaxRotationVelocity();
1152  double velmax = fabs(q[0]);
1153  for (unsigned int i = 1; i < 6; i++)
1154  {
1155  if (velmax < fabs(q[i]))
1156  velmax = fabs(q[i]);
1157  }
1158 
1159  double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax*100);
1160  q = q * alpha;
1161 }
1162 
1237 void
1239 {
1241  {
1242  vpERROR_TRACE ("Robot was not in position-based control\n"
1243  "Modification of the robot state");
1244  // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1245  }
1246 
1247  vpColVector articularCoordinates = get_artCoord();
1248 
1249  vpColVector error(6);
1250  double errsqr = 0;
1251  switch(frame)
1252  {
1253  case vpRobot::CAMERA_FRAME :
1254  {
1255  unsigned int nbSol;
1256  vpColVector qdes(6);
1257 
1258  vpTranslationVector txyz;
1259  vpRxyzVector rxyz;
1260  for (unsigned int i=0; i < 3; i++)
1261  {
1262  txyz[i] = q[i];
1263  rxyz[i] = q[i+3];
1264  }
1265 
1266  vpRotationMatrix cRc2(rxyz);
1267  vpHomogeneousMatrix cMc2(txyz, cRc2);
1268 
1270  vpViper850::get_fMc(articularCoordinates, fMc);
1271 
1272  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1273 
1274  do
1275  {
1276  articularCoordinates = get_artCoord();
1277  qdes = articularCoordinates;
1278  nbSol = getInverseKinematics(fMc2, qdes, verbose_);
1279  setVelocityCalled = true;
1280  if (nbSol > 0)
1281  {
1282  error = qdes - articularCoordinates;
1283  errsqr = error.sumSquare();
1284  //findHighestPositioningSpeed(error);
1285  set_artVel(error);
1286  if (errsqr < 1e-4)
1287  {
1288  set_artCoord (qdes);
1289  error = 0;
1290  set_artVel(error);
1291  set_velocity(error);
1292  break;
1293  }
1294  }
1295  else
1296  {
1297  vpERROR_TRACE ("Positionning error.");
1299  "Position out of range.");
1300  }
1301  }while (errsqr > 1e-8 && nbSol > 0);
1302 
1303  break ;
1304  }
1305 
1307  {
1308  do
1309  {
1310  articularCoordinates = get_artCoord();
1311  error = q - articularCoordinates;
1312  errsqr = error.sumSquare();
1313  //findHighestPositioningSpeed(error);
1314  set_artVel(error);
1315  setVelocityCalled = true;
1316  if (errsqr < 1e-4)
1317  {
1318  set_artCoord (q);
1319  error = 0;
1320  set_artVel(error);
1321  set_velocity(error);
1322  break;
1323  }
1324  }while (errsqr > 1e-8);
1325  break ;
1326  }
1327 
1329  {
1330  unsigned int nbSol;
1331  vpColVector qdes(6);
1332 
1333  vpTranslationVector txyz;
1334  vpRxyzVector rxyz;
1335  for (unsigned int i=0; i < 3; i++)
1336  {
1337  txyz[i] = q[i];
1338  rxyz[i] = q[i+3];
1339  }
1340 
1341  vpRotationMatrix fRc(rxyz);
1342  vpHomogeneousMatrix fMc(txyz, fRc);
1343 
1344  do
1345  {
1346  articularCoordinates = get_artCoord();
1347  qdes = articularCoordinates;
1348  nbSol = getInverseKinematics(fMc, qdes, verbose_);
1349  if (nbSol > 0)
1350  {
1351  error = qdes - articularCoordinates;
1352  errsqr = error.sumSquare();
1353  //findHighestPositioningSpeed(error);
1354  set_artVel(error);
1355  setVelocityCalled = true;
1356  if (errsqr < 1e-4)
1357  {
1358  set_artCoord (qdes);
1359  error = 0;
1360  set_artVel(error);
1361  set_velocity(error);
1362  break;
1363  }
1364  }
1365  else
1366  vpERROR_TRACE ("Positionning error. Position unreachable");
1367  }while (errsqr > 1e-8 && nbSol > 0);
1368  break ;
1369  }
1370  case vpRobot::MIXT_FRAME:
1371  {
1372  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1374  "Positionning error: "
1375  "Mixt frame not implemented.");
1376  break ;
1377  }
1378  }
1379 }
1380 
1445  const double pos1,
1446  const double pos2,
1447  const double pos3,
1448  const double pos4,
1449  const double pos5,
1450  const double pos6)
1451 {
1452  try{
1453  vpColVector position(6) ;
1454  position[0] = pos1 ;
1455  position[1] = pos2 ;
1456  position[2] = pos3 ;
1457  position[3] = pos4 ;
1458  position[4] = pos5 ;
1459  position[5] = pos6 ;
1460 
1461  setPosition(frame, position) ;
1462  }
1463  catch(...)
1464  {
1465  vpERROR_TRACE("Error caught");
1466  throw ;
1467  }
1468 }
1469 
1505 void vpSimulatorViper850::setPosition(const char *filename)
1506 {
1507  vpColVector q;
1508  bool ret;
1509 
1510  ret = this->readPosFile(filename, q);
1511 
1512  if (ret == false) {
1513  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1515  "Bad position in filename.");
1516  }
1519 }
1520 
1580 void
1582 {
1583  q.resize(6);
1584 
1585  switch(frame)
1586  {
1587  case vpRobot::CAMERA_FRAME :
1588  {
1589  q = 0;
1590  break ;
1591  }
1592 
1594  {
1595  q = get_artCoord();
1596  break ;
1597  }
1598 
1600  {
1602  vpViper::get_fMc (get_artCoord(), fMc);
1603 
1604  vpRotationMatrix fRc;
1605  fMc.extract(fRc);
1606  vpRxyzVector rxyz(fRc);
1607 
1608  vpTranslationVector txyz;
1609  fMc.extract(txyz);
1610 
1611  for (unsigned int i=0; i <3; i++)
1612  {
1613  q[i] = txyz[i];
1614  q[i+3] = rxyz[i];
1615  }
1616  break ;
1617  }
1618 
1619  case vpRobot::MIXT_FRAME:
1620  {
1621  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1623  "Positionning error: "
1624  "Mixt frame not implemented.");
1625  break ;
1626  }
1627  }
1628 }
1629 
1630 
1641 void
1643  vpPoseVector &position)
1644 {
1645  vpColVector posRxyz;
1646  //recupere position en Rxyz
1647  this->getPosition(frame,posRxyz);
1648 
1649  //recupere le vecteur thetaU correspondant
1650  vpThetaUVector RtuVect(posRxyz[3],posRxyz[4],posRxyz[5]);
1651 
1652  //remplit le vpPoseVector avec translation et rotation ThetaU
1653  for(unsigned int j=0;j<3;j++)
1654  {
1655  position[j]=posRxyz[j];
1656  position[j+3]=RtuVect[j];
1657  }
1658 }
1659 
1666 void
1668 {
1669  if (limitMin.getRows() != 6 || limitMax.getRows() != 6)
1670  {
1671  vpTRACE("Joint limit vector has not a size of 6 !");
1672  return;
1673  }
1674 
1675  joint_min[0] = limitMin[0];
1676  joint_min[1] = limitMin[1];
1677  joint_min[2] = limitMin[2];
1678  joint_min[3] = limitMin[3];
1679  joint_min[4] = limitMin[4];
1680  joint_min[5] = limitMin[5];
1681 
1682  joint_max[0] = limitMax[0];
1683  joint_max[1] = limitMax[1];
1684  joint_max[2] = limitMax[2];
1685  joint_max[3] = limitMax[3];
1686  joint_max[4] = limitMax[4];
1687  joint_max[5] = limitMax[5];
1688 
1689 }
1690 
1696 bool
1698 {
1699  double q2 = q[1];
1700  double q3 = q[2];
1701  double q5 = q[4];
1702 
1703  double c2 = cos(q2);
1704  double c3 = cos(q3);
1705  double s3 = sin(q3);
1706  double c23 = cos(q2+q3);
1707  double s23 = sin(q2+q3);
1708  double s5 = sin(q5);
1709 
1710  bool cond1 = fabs(s5) < 1e-1;
1711  bool cond2 = fabs(a3*s3+c3*d4) < 1e-1;
1712  bool cond3 = fabs(a2*c2-a3*c23+s23*d4+a1) < 1e-1;
1713 
1714  if(cond1)
1715  {
1716  J[3][0] = 0;
1717  J[5][0] = 0;
1718  J[3][1] = 0;
1719  J[5][1] = 0;
1720  J[3][2] = 0;
1721  J[5][2] = 0;
1722  J[3][3] = 0;
1723  J[5][3] = 0;
1724  J[3][4] = 0;
1725  J[5][4] = 0;
1726  J[3][5] = 0;
1727  J[5][5] = 0;
1728  return true;
1729  }
1730 
1731  if(cond2)
1732  {
1733  J[1][0] = 0; J[2][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1734  J[1][1] = 0; J[2][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1735  J[1][2] = 0; J[2][2] = 0; J[3][2] = 0; J[4][2] = 0; J[5][2] = 0;
1736  return true;
1737  }
1738 
1739  if(cond3)
1740  {
1741  J[0][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1742  J[0][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1743  }
1744 
1745  return false;
1746 }
1747 
1751 int
1753 {
1754  int artNumb = 0;
1755  double diff = 0;
1756  double difft = 0;
1757 
1758  vpColVector articularCoordinates = get_artCoord();
1759 
1760  for (unsigned int i = 0; i < 6; i++)
1761  {
1762  if (articularCoordinates[i] <= joint_min[i])
1763  {
1764  difft = joint_min[i] - articularCoordinates[i];
1765  if (difft > diff)
1766  {
1767  diff = difft;
1768  artNumb = -(int)i-1;
1769  }
1770  }
1771  }
1772 
1773  for (unsigned int i = 0; i < 6; i++)
1774  {
1775  if (articularCoordinates[i] >= joint_max[i])
1776  {
1777  difft = articularCoordinates[i] - joint_max[i];
1778  if (difft > diff)
1779  {
1780  diff = difft;
1781  artNumb = (int)(i+1);
1782  }
1783  }
1784  }
1785 
1786  if (artNumb != 0)
1787  std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" <<std::endl;
1788 
1789  return artNumb;
1790 }
1791 
1803 void
1804 vpSimulatorViper850::getCameraDisplacement(vpColVector &displacement)
1805 {
1806  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
1807 }
1808 
1818 void
1819 vpSimulatorViper850::getArticularDisplacement(vpColVector &displacement)
1820 {
1822 }
1823 
1842 void
1844  vpColVector &displacement)
1845 {
1846  displacement.resize (6);
1847  displacement = 0;
1848  vpColVector q_cur(6);
1849 
1850  q_cur = get_artCoord();
1851 
1852  if ( ! first_time_getdis )
1853  {
1854  switch (frame)
1855  {
1856  case vpRobot::CAMERA_FRAME:
1857  {
1858  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
1859  return;
1860  break ;
1861  }
1862 
1864  {
1865  displacement = q_cur - q_prev_getdis;
1866  break ;
1867  }
1868 
1870  {
1871  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
1872  return;
1873  break ;
1874  }
1875 
1876  case vpRobot::MIXT_FRAME:
1877  {
1878  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
1879  return;
1880  break ;
1881  }
1882  }
1883  }
1884  else
1885  {
1886  first_time_getdis = false;
1887  }
1888 
1889  // Memorize the joint position for the next call
1890  q_prev_getdis = q_cur;
1891 }
1892 
1954 bool
1956 {
1957 
1958  FILE * fd ;
1959  fd = fopen(filename, "r") ;
1960  if (fd == NULL)
1961  return false;
1962 
1963  char line[FILENAME_MAX];
1964  char dummy[FILENAME_MAX];
1965  char head[] = "R:";
1966  bool sortie = false;
1967 
1968  do {
1969  // Saut des lignes commencant par #
1970  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1971  if ( strncmp (line, "#", 1) != 0) {
1972  // La ligne n'est pas un commentaire
1973  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1974  sortie = true; // Position robot trouvee.
1975  }
1976 // else
1977 // return (false); // fin fichier sans position robot.
1978  }
1979  }
1980  else {
1981  return (false); /* fin fichier */
1982  }
1983 
1984  }
1985  while ( sortie != true );
1986 
1987  // Lecture des positions
1988  q.resize(njoint);
1989  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1990  dummy,
1991  &q[0], &q[1], &q[2],
1992  &q[3], &q[4], &q[5]);
1993 
1994  // converts rotations from degrees into radians
1995  q.deg2rad();
1996 
1997  fclose(fd) ;
1998  return (true);
1999 }
2000 
2022 bool
2023 vpSimulatorViper850::savePosFile(const char *filename, const vpColVector &q)
2024 {
2025 
2026  FILE * fd ;
2027  fd = fopen(filename, "w") ;
2028  if (fd == NULL)
2029  return false;
2030 
2031  fprintf(fd, "\
2032 #Viper - Position - Version 1.0\n\
2033 #\n\
2034 # R: A B C D E F\n\
2035 # Joint position in degrees\n\
2036 #\n\
2037 #\n\n");
2038 
2039  // Save positions in mm and deg
2040  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2041  vpMath::deg(q[0]),
2042  vpMath::deg(q[1]),
2043  vpMath::deg(q[2]),
2044  vpMath::deg(q[3]),
2045  vpMath::deg(q[4]),
2046  vpMath::deg(q[5]));
2047 
2048  fclose(fd) ;
2049  return (true);
2050 }
2051 
2059 void
2060 vpSimulatorViper850::move(const char *filename)
2061 {
2062  vpColVector q;
2063 
2064  try
2065  {
2066  this->readPosFile(filename, q);
2069  }
2070  catch(...)
2071  {
2072  throw;
2073  }
2074 }
2075 
2085 void
2087 {
2088  vpViper850::get_cMe(cMe) ;
2089 }
2090 
2098 void
2100 {
2101  vpHomogeneousMatrix cMe ;
2102  vpViper850::get_cMe(cMe) ;
2103 
2104  cVe.buildFrom(cMe) ;
2105 }
2106 
2116 void
2118 {
2119  try
2120  {
2122  }
2123  catch(...)
2124  {
2125  vpERROR_TRACE("catch exception ") ;
2126  throw ;
2127  }
2128 }
2129 
2140 void
2142 {
2143  try
2144  {
2145  vpColVector articularCoordinates = get_artCoord();
2146  vpViper850::get_fJe(articularCoordinates, fJe) ;
2147  }
2148  catch(...)
2149  {
2150  vpERROR_TRACE("Error caught");
2151  throw ;
2152  }
2153 }
2154 
2158 void
2160 {
2162  return;
2163 
2164  vpColVector stop(6);
2165  stop = 0;
2166  set_artVel(stop);
2167  set_velocity(stop);
2169 }
2170 
2171 
2172 
2173 /**********************************************************************************/
2174 /**********************************************************************************/
2175 /**********************************************************************************/
2176 /**********************************************************************************/
2177 
2186 void
2188 {
2189  // set scene_dir from #define VISP_SCENE_DIR if it exists
2190  std::string scene_dir;
2191  if (vpIoTools::checkDirectory(VISP_SCENES_DIR) == true) // directory exists
2192  scene_dir = VISP_SCENES_DIR;
2193  else {
2194  try {
2195  scene_dir = vpIoTools::getenv("VISP_SCENES_DIR");
2196  std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir << std::endl;
2197  }
2198  catch (...) {
2199  std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2200  }
2201  }
2202 
2203  char name_cam[FILENAME_MAX];
2204 
2205  strcpy(name_cam, scene_dir.c_str());
2206  strcat(name_cam,"/camera.bnd");
2207  set_scene(name_cam,&camera,cameraFactor);
2208 
2209  char name_arm[FILENAME_MAX];
2210  strcpy(name_arm, arm_dir.c_str());
2211  strcat(name_arm,"/viper850_arm1.bnd");
2212  set_scene(name_arm, robotArms, 1.0);
2213  strcpy(name_arm, arm_dir.c_str());
2214  strcat(name_arm,"/viper850_arm2.bnd");
2215  set_scene(name_arm, robotArms+1, 1.0);
2216  strcpy(name_arm, arm_dir.c_str());
2217  strcat(name_arm,"/viper850_arm3.bnd");
2218  set_scene(name_arm, robotArms+2, 1.0);
2219  strcpy(name_arm, arm_dir.c_str());
2220  strcat(name_arm,"/viper850_arm4.bnd");
2221  set_scene(name_arm, robotArms+3, 1.0);
2222  strcpy(name_arm, arm_dir.c_str());
2223  strcat(name_arm,"/viper850_arm5.bnd");
2224  set_scene(name_arm, robotArms+4, 1.0);
2225  strcpy(name_arm, arm_dir.c_str());
2226  strcat(name_arm,"/viper850_arm6.bnd");
2227  set_scene(name_arm, robotArms+5, 1.0);
2228 
2229 // set_scene("./arm2.bnd", robotArms+1, 1.0);
2230 // set_scene("./arm3.bnd", robotArms+2, 1.0);
2231 // set_scene("./arm4.bnd", robotArms+3, 1.0);
2232 // set_scene("./arm5.bnd", robotArms+4, 1.0);
2233 // set_scene("./arm6.bnd", robotArms+5, 1.0);
2234 
2235  add_rfstack(IS_BACK);
2236 
2237  add_vwstack ("start","depth", 0.0, 100.0);
2238  add_vwstack ("start","window", -0.1,0.1,-0.1,0.1);
2239  add_vwstack ("start","type", PERSPECTIVE);
2240 //
2241 // sceneInitialized = true;
2242 // displayObject = true;
2243  displayCamera = true;
2244 }
2245 
2246 
2247 void
2249 {
2250  bool changed = false;
2251  vpHomogeneousMatrix displacement = navigation(I,changed);
2252 
2253  //if (displacement[2][3] != 0)
2254  if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2255  camMf2 = camMf2*displacement;
2256 
2257  f2Mf = camMf2.inverse()*camMf;
2258 
2259  camMf = camMf2* displacement * f2Mf;
2260 
2261  double u;
2262  double v;
2263  //if(px_ext != 1 && py_ext != 1)
2264  // we assume px_ext and py_ext > 0
2265  if( (std::fabs(px_ext-1.) > vpMath::maximum(px_ext,1.)*std::numeric_limits<double>::epsilon())
2266  && (std::fabs(py_ext-1) > vpMath::maximum(py_ext,1.)*std::numeric_limits<double>::epsilon()))
2267  {
2268  u = (double)I.getWidth()/(2*px_ext);
2269  v = (double)I.getHeight()/(2*py_ext);
2270  }
2271  else
2272  {
2273  u = (double)I.getWidth()/(vpMath::minimum(I.getWidth(),I.getHeight()));
2274  v = (double)I.getHeight()/(vpMath::minimum(I.getWidth(),I.getHeight()));
2275  }
2276 
2277  float w44o[4][4],w44cext[4][4],x,y,z;
2278 
2279  vp2jlc_matrix(camMf.inverse(),w44cext);
2280 
2281  add_vwstack ("start","cop", w44cext[3][0],w44cext[3][1],w44cext[3][2]);
2282  x = w44cext[2][0] + w44cext[3][0];
2283  y = w44cext[2][1] + w44cext[3][1];
2284  z = w44cext[2][2] + w44cext[3][2];
2285  add_vwstack ("start","vrp", x,y,z);
2286  add_vwstack ("start","vpn", w44cext[2][0],w44cext[2][1],w44cext[2][2]);
2287  add_vwstack ("start","vup", w44cext[1][0],w44cext[1][1],w44cext[1][2]);
2288  add_vwstack ("start","window", -u, u, -v, v);
2289 
2290  vpHomogeneousMatrix fMit[8];
2291  get_fMi(fMit);
2292 
2293  vp2jlc_matrix(vpHomogeneousMatrix(0,0,0,0,0,0),w44o);
2294  display_scene(w44o,robotArms[0],I, curColor);
2295 
2296  vp2jlc_matrix(fMit[0],w44o);
2297  display_scene(w44o,robotArms[1],I, curColor);
2298 
2299  vp2jlc_matrix(fMit[1],w44o);
2300  display_scene(w44o,robotArms[2],I, curColor);
2301 
2302  vp2jlc_matrix(fMit[2],w44o);
2303  display_scene(w44o,robotArms[3],I, curColor);
2304 
2305  vp2jlc_matrix(fMit[3],w44o);
2306  display_scene(w44o,robotArms[4],I, curColor);
2307 
2308  vp2jlc_matrix(fMit[6],w44o);
2309  display_scene(w44o,robotArms[5],I, curColor);
2310 
2311  if (displayCamera)
2312  {
2313  vpHomogeneousMatrix cMe;
2314  get_cMe(cMe);
2315  cMe = cMe.inverse();
2316  cMe = fMit[6] * cMe;
2317  vp2jlc_matrix(cMe,w44o);
2318  display_scene(w44o,camera, I, camColor);
2319  }
2320 
2321  if (displayObject)
2322  {
2323  vp2jlc_matrix(fMo,w44o);
2324  display_scene(w44o,scene,I, curColor);
2325  }
2326 }
2327 
2343 bool
2345 {
2346  vpColVector stop(6);
2347  bool status = true;
2348  stop = 0;
2349  set_artVel(stop);
2350  set_velocity(stop);
2352  fMc = fMo * cMo.inverse();
2353 
2354  vpColVector articularCoordinates = get_artCoord();
2355  unsigned int nbSol = getInverseKinematics(fMc, articularCoordinates, verbose_);
2356 
2357  if (nbSol == 0) {
2358  status = false;
2359  vpERROR_TRACE ("Positionning error. Position unreachable");
2360  }
2361 
2362  if (verbose_)
2363  std::cout << "Used joint coordinates (rad): " << articularCoordinates.t() << std::endl;
2364 
2365  set_artCoord(articularCoordinates);
2366 
2367  compute_fMi();
2368 
2369  return status;
2370 }
2371 
2384 void
2386 {
2387  vpColVector stop(6);
2388  stop = 0;
2389  set_artVel(stop);
2390  set_velocity(stop);
2391  vpHomogeneousMatrix fMit[8];
2392  get_fMi(fMit);
2393  fMo = fMit[7] * cMo;
2394 }
2395 
2396 #endif
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
Definition: vpDisplay.cpp:506
vpToolType getToolType()
Get the current tool type.
Definition: vpViper850.h:126
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
bool singularityTest(const vpColVector q, vpMatrix &J)
double a3
for joint 3
Definition: vpViper.h:155
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:147
Error that can be emited by the vpRobot class and its derivates.
static bool checkDirectory(const char *dirname)
Definition: vpIoTools.cpp:335
void get_fMi(vpHomogeneousMatrix *fMit)
static bool readPosFile(const char *filename, vpColVector &q)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:99
unsigned int getWidth() const
Definition: vpImage.h:159
void get_cMe(vpHomogeneousMatrix &cMe)
double getSamplingTime() const
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h:379
void get_eJe(const vpColVector &q, vpMatrix &eJe)
Definition: vpViper.cpp:985
#define vpTRACE
Definition: vpDebug.h:401
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 ...
virtual vpRobotStateType getRobotState(void)
Definition: vpRobot.h:139
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:208
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:203
static const vpColor none
Definition: vpColor.h:179
Initialize the position controller.
Definition: vpRobot.h:71
void track(const vpHomogeneousMatrix &cMo)
void get_fJe(vpMatrix &fJe)
vpControlFrameType
Definition: vpRobot.h:78
vpRxyzVector erc
Definition: vpViper.h:150
double get_py() const
static double measureTimeMs()
Definition: vpTime.cpp:86
double get_y() const
Get the point y coordinate in the image plane.
Definition: vpPoint.h:138
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition: vpViper850.h:85
static int wait(double t0, double t)
Definition: vpTime.cpp:149
double sumSquare() const
return sum of the Aij^2 (for all i, for all j)
Definition: vpMatrix.cpp:760
static const vpColor green
Definition: vpColor.h:170
vpHomogeneousMatrix fMo
double a2
for joint 2
Definition: vpViper.h:154
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:1991
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:228
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:154
Class that defines what is a point.
Definition: vpPoint.h:65
void deg2rad()
Definition: vpColVector.h:187
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:137
The vpRotationMatrix considers the particular case of a rotation matrix.
double d1
for joint 1
Definition: vpViper.h:153
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
double a1
Definition: vpViper.h:153
vpControlFrameType getRobotFrame(void)
Definition: vpRobot.h:159
void move(const char *filename)
Initialize the velocity controller.
Definition: vpRobot.h:70
vpRobotStateType
Definition: vpRobot.h:66
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition: vpViper850.h:136
vpTranslationVector etc
Definition: vpViper.h:149
Initialize the acceleration controller.
Definition: vpRobot.h:72
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix f2Mf
void set_displayBusy(const bool &status)
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
static void display(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:203
vpRowVector t() const
transpose of Vector
vpColVector joint_max
Definition: vpViper.h:161
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:91
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:66
vpHomogeneousMatrix cMo
void extract(vpRotationMatrix &R) const
double get_x() const
Get the point x coordinate in the image plane.
Definition: vpPoint.h:136
static Type minimum(const Type &a, const Type &b)
Definition: vpMath.h:148
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
void set_velocity(const vpColVector &vel)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness=1)
Definition: vpDisplay.cpp:368
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Construction from translation vector and rotation matrix.
double get_px() const
static double rad(double deg)
Definition: vpMath.h:100
void setExternalCameraParameters(const vpCameraParameters &cam)
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpViper.cpp:1177
This class aims to be a basis used to create all the simulators of robots.
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
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)
void setExternalCameraPosition(const vpHomogeneousMatrix camMf)
vpHomogeneousMatrix camMf
vpHomogeneousMatrix navigation(const vpImage< vpRGBa > &I, bool &changed)
vpHomogeneousMatrix fMc
static double deg(double rad)
Definition: vpMath.h:93
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition: vpRobot.h:103
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
void setCameraParameters(const vpCameraParameters &cam)
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpViper.cpp:931
unsigned int getHeight() const
Definition: vpImage.h:150
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Definition: vpRxyzVector.h:152
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:161
double d4
for joint 4
Definition: vpViper.h:156
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
Definition: vpMatrix.cpp:1812
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:92
void set_artCoord(const vpColVector &coord)
virtual void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1)=0
void get_cVe(vpVelocityTwistMatrix &cVe)
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper850.h:144
void set_artVel(const vpColVector &vel)
static DWORD WINAPI launcher(LPVOID lpParam)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
unsigned int getRows() const
Return the number of rows of the matrix.
Definition: vpMatrix.h:157
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
static const double defaultPositioningVelocity
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:107
static bool savePosFile(const char *filename, const vpColVector &q)
Class that consider the case of a translation vector.
Class that consider the case of the parameterization for the rotation.
double getPositioningVelocity(void)
static double minTimeForUsleepCall
Definition: vpTime.h:81
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false)
Definition: vpViper.cpp:576
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:614
vpHomogeneousMatrix camMf2
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition: vpViper850.h:86
void setWorldCoordinates(const double ox, const double oy, const double oz)
Set the point world coordinates. We mean here the coordinates of the point in the object frame...
Definition: vpPoint.cpp:74
void get_eJe(vpMatrix &eJe)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:94
double d6
for joint 6
Definition: vpViper.h:157
vpColVector joint_min
Definition: vpViper.h:162