ViSP  2.6.2
vpSimulatorViper850.cpp
1 /****************************************************************************
2  *
3  * $Id: vpSimulatorViper850.cpp 3608 2012-03-07 15:03:06Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 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 
57 
62 {
63  init();
64  initDisplay();
65 
67 
68  #if defined(WIN32)
69  mutex_fMi = CreateMutex(NULL,FALSE,NULL);
70  mutex_artVel = CreateMutex(NULL,FALSE,NULL);
71  mutex_artCoord = CreateMutex(NULL,FALSE,NULL);
72  mutex_velocity = CreateMutex(NULL,FALSE,NULL);
73  mutex_display = CreateMutex(NULL,FALSE,NULL);
74 
75 
76  DWORD dwThreadIdArray;
77  hThread = CreateThread(
78  NULL, // default security attributes
79  0, // use default stack size
80  launcher, // thread function name
81  this, // argument to thread function
82  0, // use default creation flags
83  &dwThreadIdArray); // returns the thread identifier
84  #elif defined (VISP_HAVE_PTHREAD)
85  pthread_mutex_init(&mutex_fMi, NULL);
86  pthread_mutex_init(&mutex_artVel, NULL);
87  pthread_mutex_init(&mutex_artCoord, NULL);
88  pthread_mutex_init(&mutex_velocity, NULL);
89  pthread_mutex_init(&mutex_display, NULL);
90 
91  pthread_attr_init(&attr);
92  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
93 
94  pthread_create(&thread, NULL, launcher, (void *)this);
95  #endif
96 
97  compute_fMi();
98 }
99 
104 {
105  init();
106  initDisplay();
107 
109 
110  #if defined(WIN32)
111  mutex_fMi = CreateMutex(NULL,FALSE,NULL);
112  mutex_artVel = CreateMutex(NULL,FALSE,NULL);
113  mutex_artCoord = CreateMutex(NULL,FALSE,NULL);
114  mutex_velocity = CreateMutex(NULL,FALSE,NULL);
115  mutex_display = CreateMutex(NULL,FALSE,NULL);
116 
117 
118  DWORD dwThreadIdArray;
119  hThread = CreateThread(
120  NULL, // default security attributes
121  0, // use default stack size
122  launcher, // thread function name
123  this, // argument to thread function
124  0, // use default creation flags
125  &dwThreadIdArray); // returns the thread identifier
126  #elif defined(VISP_HAVE_PTHREAD)
127  pthread_mutex_init(&mutex_fMi, NULL);
128  pthread_mutex_init(&mutex_artVel, NULL);
129  pthread_mutex_init(&mutex_artCoord, NULL);
130  pthread_mutex_init(&mutex_velocity, NULL);
131  pthread_mutex_init(&mutex_display, NULL);
132 
133  pthread_attr_init(&attr);
134  pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
135 
136  pthread_create(&thread, NULL, launcher, (void *)this);
137  #endif
138 
139  compute_fMi();
140 }
141 
146 {
147  robotStop = true;
148 
149  #if defined(WIN32)
150  WaitForSingleObject(hThread,INFINITE);
151  CloseHandle(hThread);
152  CloseHandle(mutex_fMi);
153  CloseHandle(mutex_artVel);
154  CloseHandle(mutex_artCoord);
155  CloseHandle(mutex_velocity);
156  CloseHandle(mutex_display);
157  #elif defined(VISP_HAVE_PTHREAD)
158  pthread_attr_destroy(&attr);
159  pthread_join(thread, NULL);
160  pthread_mutex_destroy(&mutex_fMi);
161  pthread_mutex_destroy(&mutex_artVel);
162  pthread_mutex_destroy(&mutex_artCoord);
163  pthread_mutex_destroy(&mutex_velocity);
164  pthread_mutex_destroy(&mutex_display);
165  #endif
166 
167  if (robotArms != NULL)
168  {
169  // free_Bound_scene (&(camera));
170  for(int i = 0; i < 6; i++)
171  free_Bound_scene (&(robotArms[i]));
172  }
173 
174  delete[] robotArms;
175  delete[] fMi;
176 }
177 
186 void
188 {
189  // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
190  if (vpIoTools::checkDirectory(VISP_ROBOT_ARMS_DIR) == true) // directory exists
191  arm_dir = VISP_ROBOT_ARMS_DIR;
192  else {
193  try {
194  arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
195  std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
196  }
197  catch (...) {
198  std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
199  }
200  }
201 
203  toolCustom = false;
204 
205  size_fMi = 8;
206  fMi = new vpHomogeneousMatrix[8];
209 
210  zeroPos.resize(njoint);
211  zeroPos = 0;
212  zeroPos[1] = -M_PI/2; zeroPos[2] = M_PI;
213  reposPos.resize(njoint);
214  reposPos = 0;
215  reposPos[1] = -M_PI/2; reposPos[2] = M_PI; reposPos[4] = M_PI/2;
216 
217  artCoord = reposPos;
218  artVel = 0;
219 
220  q_prev_getdis.resize(njoint);
221  q_prev_getdis = 0;
222  first_time_getdis = true;
223 
224  positioningVelocity = defaultPositioningVelocity ;
225 
228 
229  // Software joint limits in radians
230  //joint_min.resize(njoint);
231  joint_min[0] = vpMath::rad(-50);
232  joint_min[1] = vpMath::rad(-135);
233  joint_min[2] = vpMath::rad(-40);
234  joint_min[3] = vpMath::rad(-190);
235  joint_min[4] = vpMath::rad(-110);
236  joint_min[5] = vpMath::rad(-184);
237  //joint_max.resize(njoint);
238  joint_max[0] = vpMath::rad(50);
239  joint_max[1] = vpMath::rad(-40);
240  joint_max[2] = vpMath::rad(215);
241  joint_max[3] = vpMath::rad(190);
242  joint_max[4] = vpMath::rad(110);
243  joint_max[5] = vpMath::rad(184);
244 }
245 
249 void
251 {
252  robotArms = NULL;
253  robotArms = new Bound_scene[6];
254  initArms();
256  cameraParam.initPersProjWithoutDistortion (558.5309599, 556.055053, 320, 240);
258  vpCameraParameters tmp;
259  getCameraParameters(tmp,640,480);
260  px_int = tmp.get_px();
261  py_int = tmp.get_py();
262  sceneInitialized = true;
263 }
264 
265 
281 void
284 {
285  this->projModel = projModel;
286 
287  // Use here default values of the robot constant parameters.
288  switch (tool) {
290  erc[0] = vpMath::rad(0.07); // rx
291  erc[1] = vpMath::rad(2.76); // ry
292  erc[2] = vpMath::rad(-91.50); // rz
293  etc[0] = -0.0453; // tx
294  etc[1] = 0.0005; // ty
295  etc[2] = 0.0728; // tz
296 
297  setCameraParameters(vpCameraParameters(1232.0, 1233.0, 320, 240));
298  break;
299  }
301  erc[0] = vpMath::rad(0.1527764261); // rx
302  erc[1] = vpMath::rad(1.285092455); // ry
303  erc[2] = vpMath::rad(-90.75777848); // rz
304  etc[0] = -0.04558630174; // tx
305  etc[1] = -0.00134326752; // ty
306  etc[2] = 0.001000828017; // tz
307 
308  setCameraParameters(vpCameraParameters(868.0, 869.0, 320, 240));
309  break;
310  }
313  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
314  break;
315  }
316  }
317 
318  vpRotationMatrix eRc(erc);
319  this->eMc.buildFrom(etc, eRc);
320 
321  setToolType(tool);
322  return ;
323 }
324 
335 void
337  const unsigned int &image_width,
338  const unsigned int &image_height)
339 {
340  if (toolCustom)
341  {
342  vpCameraParameters(px_int,py_int,image_width/2,image_height/2);
343  }
344  // Set default parameters
345  switch (getToolType()) {
347  // Set default intrinsic camera parameters for 640x480 images
348  if (image_width == 640 && image_height == 480)
349  {
350  std::cout << "Get default camera parameters for camera \""
351  << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl;
352  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240);
353  }
354  else {
355  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
356  }
357  break;
358  }
360  // Set default intrinsic camera parameters for 640x480 images
361  if (image_width == 640 && image_height == 480) {
362  std::cout << "Get default camera parameters for camera \""
363  << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl;
364  cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240);
365  }
366  else {
367  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
368  }
369  break;
370  }
373  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
374  break;
375  }
376  }
377  return;
378 }
379 
388 void
390  const vpImage<unsigned char> &I)
391 {
393 }
394 
403 void
405  const vpImage<vpRGBa> &I)
406 {
408 }
409 
410 
416 void
418 {
419  px_int = cam.get_px();
420  py_int = cam.get_py();
421  toolCustom = true;
422 }
423 
424 
428 void
430 {
431  double tcur_1 = tcur;// temporary variable used to store the last time since the last command
432 
433  while (!robotStop)
434  {
435  //Get current time
436  tprev = tcur_1;
438 
439 
441  setVelocityCalled = false;
443 
444  double ellapsedTime = tcur - tprev;
445  if(constantSamplingTimeMode){//if we want a constant velocity, we force the ellapsed time to the given samplingTime
446  ellapsedTime = samplingTime;
447  }
448 
449  vpColVector articularCoordinates = get_artCoord();
450  articularCoordinates = get_artCoord();
451  vpColVector articularVelocities = get_artVel();
452 
453  if (jointLimit)
454  {
455  double art = articularCoordinates[jointLimitArt-1] + ellapsedTime*articularVelocities[jointLimitArt-1]*1e-3;
456  if (art <= joint_min[jointLimitArt-1] || art >= joint_max[jointLimitArt-1])
457  articularVelocities = 0.0;
458  else
459  jointLimit = false;
460  }
461 
462  articularCoordinates[0] = articularCoordinates[0] + ellapsedTime*articularVelocities[0]*1e-3;
463  articularCoordinates[1] = articularCoordinates[1] + ellapsedTime*articularVelocities[1]*1e-3;
464  articularCoordinates[2] = articularCoordinates[2] + ellapsedTime*articularVelocities[2]*1e-3;
465  articularCoordinates[3] = articularCoordinates[3] + ellapsedTime*articularVelocities[3]*1e-3;
466  articularCoordinates[4] = articularCoordinates[4] + ellapsedTime*articularVelocities[4]*1e-3;
467  articularCoordinates[5] = articularCoordinates[5] + ellapsedTime*articularVelocities[5]*1e-3;
468 
469  int jl = isInJointLimit();
470 
471  if (jl != 0 && jointLimit == false)
472  {
473  if (jl < 0)
474  ellapsedTime = (joint_min[(unsigned int)(-jl-1)] - articularCoordinates[(unsigned int)(-jl-1)])/(articularVelocities[(unsigned int)(-jl-1)]*1e-3);
475  else
476  ellapsedTime = (joint_max[(unsigned int)(jl-1)] - articularCoordinates[(unsigned int)(jl-1)])/(articularVelocities[(unsigned int)(jl-1)]*1e-3);
477 
478  for (unsigned int i = 0; i < 6; i++)
479  articularCoordinates[i] = articularCoordinates[i] + ellapsedTime*articularVelocities[i]*1e-3;
480 
481  jointLimit = true;
482  jointLimitArt = (unsigned int)fabs((double)jl);
483  }
484 
485  set_artCoord(articularCoordinates);
486  set_artVel(articularVelocities);
487 
488  compute_fMi();
489 
490  if (displayAllowed)
491  {
495  }
496 
498  {
499  while (get_displayBusy()) vpTime::wait(2);
501  set_displayBusy(false);
502  }
503 
504 
506  {
507  vpHomogeneousMatrix fMit[8];
508  get_fMi(fMit);
509 
510  //vpDisplay::displayFrame(I,getExternalCameraPosition ()*fMi[6],cameraParam,0.2,vpColor::none);
511 
512  vpImagePoint iP, iP_1;
513  vpPoint pt;
514  pt.setWorldCoordinates (0,0,0);
515 
518  pt.track(getExternalCameraPosition ()*fMit[0]);
521  for (int k = 1; k < 7; k++)
522  {
523  pt.track(getExternalCameraPosition ()*fMit[k-1]);
525 
526  pt.track(getExternalCameraPosition ()*fMit[k]);
528 
530  }
532  }
533 
535 
536 
538  tcur_1 = tcur;
539  }else{
540  vpTime::wait(tcur, 4);
541  }
542  }
543 }
544 
552 void
554 {
555  //vpColVector q = get_artCoord();
556  vpColVector q(6);//; = get_artCoord();
557  q = get_artCoord();
558 
559  vpHomogeneousMatrix fMit[8];
560 
561  double q1 = q[0];
562  double q2 = q[1];
563  double q3 = q[2];
564  double q4 = q[3];
565  double q5 = q[4];
566  double q6 = q[5];
567 
568  double c1 = cos(q1);
569  double s1 = sin(q1);
570  double c2 = cos(q2);
571  double s2 = sin(q2);
572  double c23 = cos(q2+q3);
573  double s23 = sin(q2+q3);
574  double c4 = cos(q4);
575  double s4 = sin(q4);
576  double c5 = cos(q5);
577  double s5 = sin(q5);
578  double c6 = cos(q6);
579  double s6 = sin(q6);
580 
581  fMit[0][0][0] = c1;
582  fMit[0][1][0] = s1;
583  fMit[0][2][0] = 0;
584  fMit[0][0][1] = 0;
585  fMit[0][1][1] = 0;
586  fMit[0][2][1] = -1;
587  fMit[0][0][2] = -s1;
588  fMit[0][1][2] = c1;
589  fMit[0][2][2] = 0;
590  fMit[0][0][3] = a1*c1;
591  fMit[0][1][3] = a1*s1;
592  fMit[0][2][3] = d1;
593 
594  fMit[1][0][0] = c1*c2;
595  fMit[1][1][0] = s1*c2;
596  fMit[1][2][0] = -s2;
597  fMit[1][0][1] = -c1*s2;
598  fMit[1][1][1] = -s1*s2;
599  fMit[1][2][1] = -c2;
600  fMit[1][0][2] = -s1;
601  fMit[1][1][2] = c1;
602  fMit[1][2][2] = 0;
603  fMit[1][0][3] = c1*(a2*c2+a1);
604  fMit[1][1][3] = s1*(a2*c2+a1);
605  fMit[1][2][3] = d1-a2*s2;
606 
607  double quickcomp1 = a3*c23-a2*c2-a1;
608 
609  fMit[2][0][0] = -c1*c23;
610  fMit[2][1][0] = -s1*c23;
611  fMit[2][2][0] = s23;
612  fMit[2][0][1] = s1;
613  fMit[2][1][1] = -c1;
614  fMit[2][2][1] = 0;
615  fMit[2][0][2] = c1*s23;
616  fMit[2][1][2] = s1*s23;
617  fMit[2][2][2] = c23;
618  fMit[2][0][3] = -c1*quickcomp1;
619  fMit[2][1][3] = -s1*quickcomp1;
620  fMit[2][2][3] = a3*s23-a2*s2+d1;
621 
622  double quickcomp2 = c1*(s23*d4 - quickcomp1);
623  double quickcomp3 = s1*(s23*d4 - quickcomp1);
624 
625  fMit[3][0][0] = -c1*c23*c4+s1*s4;
626  fMit[3][1][0] = -s1*c23*c4-c1*s4;
627  fMit[3][2][0] = s23*c4;
628  fMit[3][0][1] = c1*s23;
629  fMit[3][1][1] = s1*s23;
630  fMit[3][2][1] = c23;
631  fMit[3][0][2] = -c1*c23*s4-s1*c4;
632  fMit[3][1][2] = -s1*c23*s4+c1*c4;
633  fMit[3][2][2] = s23*s4;
634  fMit[3][0][3] = quickcomp2;
635  fMit[3][1][3] = quickcomp3;
636  fMit[3][2][3] = c23*d4+a3*s23-a2*s2+d1;
637 
638  fMit[4][0][0] = c1*(s23*s5-c5*c23*c4)+s1*c5*s4;
639  fMit[4][1][0] = s1*(s23*s5-c5*c23*c4)-c1*c5*s4;
640  fMit[4][2][0] = s23*c4*c5+c23*s5;
641  fMit[4][0][1] = c1*c23*s4+s1*c4;
642  fMit[4][1][1] = s1*c23*s4-c1*c4;
643  fMit[4][2][1] = -s23*s4;
644  fMit[4][0][2] = c1*(s23*c5+s5*c23*c4)-s1*s5*s4;
645  fMit[4][1][2] = s1*(s23*c5+s5*c23*c4)+c1*s5*s4;
646  fMit[4][2][2] = -s23*c4*s5+c23*c5;
647  fMit[4][0][3] = quickcomp2;
648  fMit[4][1][3] = quickcomp3;
649  fMit[4][2][3] = c23*d4+a3*s23-a2*s2+d1;
650 
651  fMit[5][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
652  fMit[5][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
653  fMit[5][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
654  fMit[5][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
655  fMit[5][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
656  fMit[5][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
657  fMit[5][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
658  fMit[5][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
659  fMit[5][2][2] = -s23*c4*s5+c23*c5;
660  fMit[5][0][3] = quickcomp2;
661  fMit[5][1][3] = quickcomp3;
662  fMit[5][2][3] = s23*a3+c23*d4-a2*s2+d1;
663 
664  fMit[6][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
665  fMit[6][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
666  fMit[6][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
667  fMit[6][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
668  fMit[6][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
669  fMit[6][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
670  fMit[6][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
671  fMit[6][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
672  fMit[6][2][2] = -s23*c4*s5+c23*c5;
673  fMit[6][0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
674  fMit[6][1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
675  fMit[6][2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
676 
678  get_cMe(cMe);
679  cMe = cMe.inverse();
680 // fMit[7] = fMit[6] * cMe;
681  get_fMc(q,fMit[7]);
682 
683  #if defined(WIN32)
684  WaitForSingleObject(mutex_fMi,INFINITE);
685  for (int i = 0; i < 8; i++)
686  fMi[i] = fMit[i];
687  ReleaseMutex(mutex_fMi);
688  #elif defined(VISP_HAVE_PTHREAD)
689  pthread_mutex_lock (&mutex_fMi);
690  for (int i = 0; i < 8; i++)
691  fMi[i] = fMit[i];
692  pthread_mutex_unlock (&mutex_fMi);
693  #endif
694 }
695 
696 
704 {
705  switch (newState) {
706  case vpRobot::STATE_STOP: {
707  // Start primitive STOP only if the current state is Velocity
709  stopMotion();
710  }
711  break;
712  }
715  std::cout << "Change the control mode from velocity to position control.\n";
716  stopMotion();
717  }
718  else {
719  //std::cout << "Change the control mode from stop to position control.\n";
720  }
721  break;
722  }
725  std::cout << "Change the control mode from stop to velocity control.\n";
726  }
727  break;
728  }
730  default:
731  break ;
732  }
733 
734  return vpRobot::setRobotState (newState);
735 }
736 
806 void
808 {
810  vpERROR_TRACE ("Cannot send a velocity to the robot "
811  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
813  "Cannot send a velocity to the robot "
814  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
815  }
816 
817  vpColVector vel_sat(6);
818 
819  double scale_trans_sat = 1;
820  double scale_rot_sat = 1;
821  double scale_sat = 1;
822  double vel_trans_max = getMaxTranslationVelocity();
823  double vel_rot_max = getMaxRotationVelocity();
824 
825  double vel_abs; // Absolute value
826 
827  // Velocity saturation
828  switch(frame)
829  {
830  // saturation in cartesian space
831  case vpRobot::CAMERA_FRAME :
833  {
834  if (vel.getRows() != 6)
835  {
836  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
837  throw;
838  }
839 
840  for (unsigned int i = 0 ; i < 3; ++ i)
841  {
842  vel_abs = fabs (vel[i]);
843  if (vel_abs > vel_trans_max && !jointLimit)
844  {
845  vel_trans_max = vel_abs;
846  vpERROR_TRACE ("Excess velocity %g m/s in TRANSLATION "
847  "(axis nr. %d).", vel[i], i+1);
848  }
849 
850  vel_abs = fabs (vel[i+3]);
851  if (vel_abs > vel_rot_max && !jointLimit) {
852  vel_rot_max = vel_abs;
853  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
854  "(axis nr. %d).", vel[i+3], i+4);
855  }
856  }
857 
858  if (vel_trans_max > getMaxTranslationVelocity())
859  scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
860 
861  if (vel_rot_max > getMaxRotationVelocity())
862  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
863 
864  if ( (scale_trans_sat < 1) || (scale_rot_sat < 1) )
865  {
866  if (scale_trans_sat < scale_rot_sat)
867  scale_sat = scale_trans_sat;
868  else
869  scale_sat = scale_rot_sat;
870  }
871  break;
872  }
873 
874  // saturation in joint space
876  {
877  if (vel.getRows() != 6)
878  {
879  vpERROR_TRACE ("The velocity vector must have a size of 6 !!!!");
880  throw;
881  }
882  for (unsigned int i = 0 ; i < 6; ++ i)
883  {
884  vel_abs = fabs (vel[i]);
885  if (vel_abs > vel_rot_max && !jointLimit)
886  {
887  vel_rot_max = vel_abs;
888  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
889  "(axis nr. %d).", vel[i], i+1);
890  }
891  }
892  if (vel_rot_max > getMaxRotationVelocity())
893  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
894  if ( scale_rot_sat < 1 )
895  scale_sat = scale_rot_sat;
896  break;
897  }
898  case vpRobot::MIXT_FRAME :
899  {
900  break;
901  }
902  }
903 
904  set_velocity (vel * scale_sat);
905  setRobotFrame (frame);
906  setVelocityCalled = true;
907 }
908 
909 
913 void
915 {
917 
918  double scale_rot_sat = 1;
919  double scale_sat = 1;
920  double vel_rot_max = getMaxRotationVelocity();
921  double vel_abs;
922 
923  vpColVector articularCoordinates = get_artCoord();
924  vpColVector velocityframe = get_velocity();
925  vpColVector articularVelocity;
926 
927  switch(frame)
928  {
929  case vpRobot::CAMERA_FRAME :
930  {
931  vpMatrix eJe;
933  vpViper850::get_eJe(articularCoordinates,eJe);
934  eJe = eJe.pseudoInverse();
936  singularityTest(articularCoordinates,eJe);
937  articularVelocity = eJe*eVc*velocityframe;
938  set_artVel (articularVelocity);
939  break;
940  }
942  {
943  vpMatrix fJe;
944  vpViper850::get_fJe(articularCoordinates,fJe);
945  fJe = fJe.pseudoInverse();
947  singularityTest(articularCoordinates,fJe);
948  articularVelocity = fJe*velocityframe;
949  set_artVel (articularVelocity);
950  break;
951  }
953  {
954  articularVelocity = velocityframe;
955  set_artVel (articularVelocity);
956  break;
957  }
958  case vpRobot::MIXT_FRAME :
959  {
960  break;
961  }
962  }
963 
964 
965 
966  switch(frame)
967  {
968  case vpRobot::CAMERA_FRAME :
970  {
971  for (unsigned int i = 0 ; i < 6; ++ i)
972  {
973  vel_abs = fabs (articularVelocity[i]);
974  if (vel_abs > vel_rot_max && !jointLimit)
975  {
976  vel_rot_max = vel_abs;
977  vpERROR_TRACE ("Excess velocity %g rad/s in ROTATION "
978  "(axis nr. %d).", articularVelocity[i], i+1);
979  }
980  }
981  if (vel_rot_max > getMaxRotationVelocity())
982  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
983  if ( scale_rot_sat < 1 )
984  scale_sat = scale_rot_sat;
985 
986  set_artVel(articularVelocity * scale_sat);
987  break;
988  }
990  case vpRobot::MIXT_FRAME :
991  {
992  break;
993  }
994  }
995 }
996 
997 
1044 void
1046 {
1047  vel.resize(6);
1048 
1049  vpColVector articularCoordinates = get_artCoord();
1050  vpColVector articularVelocity = get_artVel();
1051 
1052  switch(frame)
1053  {
1054  case vpRobot::CAMERA_FRAME :
1055  {
1056  vpMatrix eJe;
1058  vpViper850::get_eJe(articularCoordinates,eJe);
1059  vel = cVe*eJe*articularVelocity;
1060  break ;
1061  }
1062  case vpRobot::ARTICULAR_FRAME :
1063  {
1064  vel = articularVelocity;
1065  break ;
1066  }
1067  case vpRobot::REFERENCE_FRAME :
1068  {
1069  vpMatrix fJe;
1070  vpViper850::get_fJe(articularCoordinates,fJe);
1071  vel = fJe*articularVelocity;
1072  break ;
1073  }
1074  case vpRobot::MIXT_FRAME :
1075  {
1076  break ;
1077  }
1078  default:
1079  {
1080  vpERROR_TRACE ("Error in spec of vpRobot. "
1081  "Case not taken in account.");
1082  return;
1083  }
1084  }
1085 }
1086 
1131 {
1132  vpColVector velocity(6);
1133  getVelocity (frame, velocity);
1134 
1135  return velocity;
1136 }
1137 
1138 
1139 void
1141 {
1142  double vel_rot_max = getMaxRotationVelocity();
1143  double velmax = fabs(q[0]);
1144  for (unsigned int i = 1; i < 6; i++)
1145  {
1146  if (velmax < fabs(q[i]))
1147  velmax = fabs(q[i]);
1148  }
1149 
1150  double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax*100);
1151  q = q * alpha;
1152 }
1153 
1228 void
1230 {
1232  {
1233  vpERROR_TRACE ("Robot was not in position-based control\n"
1234  "Modification of the robot state");
1235  // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1236  }
1237 
1238  vpColVector articularCoordinates = get_artCoord();
1239 
1240  vpColVector error(6);
1241  double errsqr = 0;
1242  switch(frame)
1243  {
1244  case vpRobot::CAMERA_FRAME :
1245  {
1246  unsigned int nbSol;
1247  vpColVector qdes(6);
1248 
1249  vpTranslationVector txyz;
1250  vpRxyzVector rxyz;
1251  for (unsigned int i=0; i < 3; i++)
1252  {
1253  txyz[i] = q[i];
1254  rxyz[i] = q[i+3];
1255  }
1256 
1257  vpRotationMatrix cRc2(rxyz);
1258  vpHomogeneousMatrix cMc2(txyz, cRc2);
1259 
1261  vpViper850::get_fMc(articularCoordinates, fMc);
1262 
1263  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1264 
1265  do
1266  {
1267  articularCoordinates = get_artCoord();
1268  qdes = articularCoordinates;
1269  nbSol = getInverseKinematics(fMc2, qdes);
1270  setVelocityCalled = true;
1271  if (nbSol > 0)
1272  {
1273  error = qdes - articularCoordinates;
1274  errsqr = error.sumSquare();
1275  //findHighestPositioningSpeed(error);
1276  set_artVel(error);
1277  if (errsqr < 1e-4)
1278  {
1279  set_artCoord (qdes);
1280  error = 0;
1281  set_artVel(error);
1282  set_velocity(error);
1283  break;
1284  }
1285  }
1286  else
1287  {
1288  vpERROR_TRACE ("Positionning error.");
1290  "Position out of range.");
1291  }
1292  }while (errsqr > 1e-8 && nbSol > 0);
1293 
1294  break ;
1295  }
1296 
1298  {
1299  do
1300  {
1301  articularCoordinates = get_artCoord();
1302  error = q - articularCoordinates;
1303  errsqr = error.sumSquare();
1304  //findHighestPositioningSpeed(error);
1305  set_artVel(error);
1306  setVelocityCalled = true;
1307  if (errsqr < 1e-4)
1308  {
1309  set_artCoord (q);
1310  error = 0;
1311  set_artVel(error);
1312  set_velocity(error);
1313  break;
1314  }
1315  }while (errsqr > 1e-8);
1316  break ;
1317  }
1318 
1320  {
1321  unsigned int nbSol;
1322  vpColVector qdes(6);
1323 
1324  vpTranslationVector txyz;
1325  vpRxyzVector rxyz;
1326  for (unsigned int i=0; i < 3; i++)
1327  {
1328  txyz[i] = q[i];
1329  rxyz[i] = q[i+3];
1330  }
1331 
1332  vpRotationMatrix fRc(rxyz);
1333  vpHomogeneousMatrix fMc(txyz, fRc);
1334 
1335  do
1336  {
1337  articularCoordinates = get_artCoord();
1338  qdes = articularCoordinates;
1339  nbSol = getInverseKinematics(fMc, qdes);
1340  if (nbSol > 0)
1341  {
1342  error = qdes - articularCoordinates;
1343  errsqr = error.sumSquare();
1344  //findHighestPositioningSpeed(error);
1345  set_artVel(error);
1346  setVelocityCalled = true;
1347  if (errsqr < 1e-4)
1348  {
1349  set_artCoord (qdes);
1350  error = 0;
1351  set_artVel(error);
1352  set_velocity(error);
1353  break;
1354  }
1355  }
1356  else
1357  vpERROR_TRACE ("Positionning error. Position unreachable");
1358  }while (errsqr > 1e-8 && nbSol > 0);
1359  break ;
1360  }
1361  case vpRobot::MIXT_FRAME:
1362  {
1363  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1365  "Positionning error: "
1366  "Mixt frame not implemented.");
1367  break ;
1368  }
1369  }
1370 }
1371 
1436  const double pos1,
1437  const double pos2,
1438  const double pos3,
1439  const double pos4,
1440  const double pos5,
1441  const double pos6)
1442 {
1443  try{
1444  vpColVector position(6) ;
1445  position[0] = pos1 ;
1446  position[1] = pos2 ;
1447  position[2] = pos3 ;
1448  position[3] = pos4 ;
1449  position[4] = pos5 ;
1450  position[5] = pos6 ;
1451 
1452  setPosition(frame, position) ;
1453  }
1454  catch(...)
1455  {
1456  vpERROR_TRACE("Error caught");
1457  throw ;
1458  }
1459 }
1460 
1496 void vpSimulatorViper850::setPosition(const char *filename)
1497 {
1498  vpColVector q;
1499  bool ret;
1500 
1501  ret = this->readPosFile(filename, q);
1502 
1503  if (ret == false) {
1504  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1506  "Bad position in filename.");
1507  }
1510 }
1511 
1571 void
1573 {
1574  q.resize(6);
1575 
1576  switch(frame)
1577  {
1578  case vpRobot::CAMERA_FRAME :
1579  {
1580  q = 0;
1581  break ;
1582  }
1583 
1585  {
1586  q = get_artCoord();
1587  break ;
1588  }
1589 
1591  {
1593  get_fMc (get_artCoord(), fMc);
1594 
1595  vpRotationMatrix fRc;
1596  fMc.extract(fRc);
1597  vpRxyzVector rxyz(fRc);
1598 
1599  vpTranslationVector txyz;
1600  fMc.extract(txyz);
1601 
1602  for (unsigned int i=0; i <3; i++)
1603  {
1604  q[i] = txyz[i];
1605  q[i+3] = rxyz[i];
1606  }
1607  break ;
1608  }
1609 
1610  case vpRobot::MIXT_FRAME:
1611  {
1612  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1614  "Positionning error: "
1615  "Mixt frame not implemented.");
1616  break ;
1617  }
1618  }
1619 }
1620 
1621 
1632 void
1634  vpPoseVector &position)
1635 {
1636  vpColVector posRxyz;
1637  //recupere position en Rxyz
1638  this->getPosition(frame,posRxyz);
1639 
1640  //recupere le vecteur thetaU correspondant
1641  vpThetaUVector RtuVect(posRxyz[3],posRxyz[4],posRxyz[5]);
1642 
1643  //remplit le vpPoseVector avec translation et rotation ThetaU
1644  for(unsigned int j=0;j<3;j++)
1645  {
1646  position[j]=posRxyz[j];
1647  position[j+3]=RtuVect[j];
1648  }
1649 }
1650 
1657 void
1659 {
1660  if (limitMin.getRows() != 6 || limitMax.getRows() != 6)
1661  {
1662  vpTRACE("Joint limit vector has not a size of 6 !");
1663  return;
1664  }
1665 
1666  joint_min[0] = limitMin[0];
1667  joint_min[1] = limitMin[1];
1668  joint_min[2] = limitMin[2];
1669  joint_min[3] = limitMin[3];
1670  joint_min[4] = limitMin[4];
1671  joint_min[5] = limitMin[5];
1672 
1673  joint_max[0] = limitMax[0];
1674  joint_max[1] = limitMax[1];
1675  joint_max[2] = limitMax[2];
1676  joint_max[3] = limitMax[3];
1677  joint_max[4] = limitMax[4];
1678  joint_max[5] = limitMax[5];
1679 
1680 }
1681 
1687 bool
1689 {
1690  double q2 = q[1];
1691  double q3 = q[2];
1692  double q5 = q[4];
1693 
1694  double c2 = cos(q2);
1695  double c3 = cos(q3);
1696  double s3 = sin(q3);
1697  double c23 = cos(q2+q3);
1698  double s23 = sin(q2+q3);
1699  double s5 = sin(q5);
1700 
1701  bool cond1 = fabs(s5) < 1e-1;
1702  bool cond2 = fabs(a3*s3+c3*d4) < 1e-1;
1703  bool cond3 = fabs(a2*c2-a3*c23+s23*d4+a1) < 1e-1;
1704 
1705  if(cond1)
1706  {
1707  J[3][0] = 0;
1708  J[5][0] = 0;
1709  J[3][1] = 0;
1710  J[5][1] = 0;
1711  J[3][2] = 0;
1712  J[5][2] = 0;
1713  J[3][3] = 0;
1714  J[5][3] = 0;
1715  J[3][4] = 0;
1716  J[5][4] = 0;
1717  J[3][5] = 0;
1718  J[5][5] = 0;
1719  return true;
1720  }
1721 
1722  if(cond2)
1723  {
1724  J[1][0] = 0; J[2][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1725  J[1][1] = 0; J[2][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1726  J[1][2] = 0; J[2][2] = 0; J[3][2] = 0; J[4][2] = 0; J[5][2] = 0;
1727  return true;
1728  }
1729 
1730  if(cond3)
1731  {
1732  J[0][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1733  J[0][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1734  }
1735 
1736  return false;
1737 }
1738 
1742 int
1744 {
1745  int artNumb = 0;
1746  double diff = 0;
1747  double difft = 0;
1748 
1749  vpColVector articularCoordinates = get_artCoord();
1750 
1751  for (unsigned int i = 0; i < 6; i++)
1752  {
1753  if (articularCoordinates[i] <= joint_min[i])
1754  {
1755  difft = joint_min[i] - articularCoordinates[i];
1756  if (difft > diff)
1757  {
1758  diff = difft;
1759  artNumb = -(int)i-1;
1760  }
1761  }
1762  }
1763 
1764  for (unsigned int i = 0; i < 6; i++)
1765  {
1766  if (articularCoordinates[i] >= joint_max[i])
1767  {
1768  difft = articularCoordinates[i] - joint_max[i];
1769  if (difft > diff)
1770  {
1771  diff = difft;
1772  artNumb = (int)(i+1);
1773  }
1774  }
1775  }
1776 
1777  if (artNumb != 0)
1778  std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" <<std::endl;
1779 
1780  return artNumb;
1781 }
1782 
1794 void
1796 {
1797  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
1798 }
1799 
1809 void
1811 {
1813 }
1814 
1833 void
1835  vpColVector &displacement)
1836 {
1837  displacement.resize (6);
1838  displacement = 0;
1839  vpColVector q_cur(6);
1840 
1841  q_cur = get_artCoord();
1842 
1843  if ( ! first_time_getdis )
1844  {
1845  switch (frame)
1846  {
1847  case vpRobot::CAMERA_FRAME:
1848  {
1849  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
1850  return;
1851  break ;
1852  }
1853 
1855  {
1856  displacement = q_cur - q_prev_getdis;
1857  break ;
1858  }
1859 
1861  {
1862  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
1863  return;
1864  break ;
1865  }
1866 
1867  case vpRobot::MIXT_FRAME:
1868  {
1869  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
1870  return;
1871  break ;
1872  }
1873  }
1874  }
1875  else
1876  {
1877  first_time_getdis = false;
1878  }
1879 
1880  // Memorize the joint position for the next call
1881  q_prev_getdis = q_cur;
1882 }
1883 
1945 bool
1947 {
1948 
1949  FILE * fd ;
1950  fd = fopen(filename, "r") ;
1951  if (fd == NULL)
1952  return false;
1953 
1954  char line[FILENAME_MAX];
1955  char dummy[FILENAME_MAX];
1956  char head[] = "R:";
1957  bool sortie = false;
1958 
1959  do {
1960  // Saut des lignes commencant par #
1961  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1962  if ( strncmp (line, "#", 1) != 0) {
1963  // La ligne n'est pas un commentaire
1964  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1965  sortie = true; // Position robot trouvee.
1966  }
1967 // else
1968 // return (false); // fin fichier sans position robot.
1969  }
1970  }
1971  else {
1972  return (false); /* fin fichier */
1973  }
1974 
1975  }
1976  while ( sortie != true );
1977 
1978  // Lecture des positions
1979  q.resize(njoint);
1980  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1981  dummy,
1982  &q[0], &q[1], &q[2],
1983  &q[3], &q[4], &q[5]);
1984 
1985  // converts rotations from degrees into radians
1986  q.deg2rad();
1987 
1988  fclose(fd) ;
1989  return (true);
1990 }
1991 
2013 bool
2014 vpSimulatorViper850::savePosFile(const char *filename, const vpColVector &q)
2015 {
2016 
2017  FILE * fd ;
2018  fd = fopen(filename, "w") ;
2019  if (fd == NULL)
2020  return false;
2021 
2022  fprintf(fd, "\
2023 #Viper - Position - Version 1.0\n\
2024 #\n\
2025 # R: A B C D E F\n\
2026 # Joint position in degrees\n\
2027 #\n\
2028 #\n\n");
2029 
2030  // Save positions in mm and deg
2031  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2032  vpMath::deg(q[0]),
2033  vpMath::deg(q[1]),
2034  vpMath::deg(q[2]),
2035  vpMath::deg(q[3]),
2036  vpMath::deg(q[4]),
2037  vpMath::deg(q[5]));
2038 
2039  fclose(fd) ;
2040  return (true);
2041 }
2042 
2050 void
2051 vpSimulatorViper850::move(const char *filename)
2052 {
2053  vpColVector q;
2054 
2055  try
2056  {
2057  this->readPosFile(filename, q);
2060  }
2061  catch(...)
2062  {
2063  throw;
2064  }
2065 }
2066 
2076 void
2078 {
2079  vpViper850::get_cMe(cMe) ;
2080 }
2081 
2089 void
2091 {
2092  vpHomogeneousMatrix cMe ;
2093  vpViper850::get_cMe(cMe) ;
2094 
2095  cVe.buildFrom(cMe) ;
2096 }
2097 
2107 void
2109 {
2110  try
2111  {
2113  }
2114  catch(...)
2115  {
2116  vpERROR_TRACE("catch exception ") ;
2117  throw ;
2118  }
2119 }
2120 
2131 void
2133 {
2134  try
2135  {
2136  vpColVector articularCoordinates = get_artCoord();
2137  vpViper850::get_fJe(articularCoordinates, fJe) ;
2138  }
2139  catch(...)
2140  {
2141  vpERROR_TRACE("Error caught");
2142  throw ;
2143  }
2144 }
2145 
2149 void
2151 {
2153  return;
2154 
2155  vpColVector stop(6);
2156  stop = 0;
2157  set_artVel(stop);
2158  set_velocity(stop);
2160 }
2161 
2162 
2163 
2164 /**********************************************************************************/
2165 /**********************************************************************************/
2166 /**********************************************************************************/
2167 /**********************************************************************************/
2168 
2177 void
2179 {
2180  // set scene_dir from #define VISP_SCENE_DIR if it exists
2181  std::string scene_dir;
2182  if (vpIoTools::checkDirectory(VISP_SCENES_DIR) == true) // directory exists
2183  scene_dir = VISP_SCENES_DIR;
2184  else {
2185  try {
2186  scene_dir = vpIoTools::getenv("VISP_SCENES_DIR");
2187  std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir << std::endl;
2188  }
2189  catch (...) {
2190  std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2191  }
2192  }
2193 
2194  char name_cam[FILENAME_MAX];
2195 
2196  strcpy(name_cam, scene_dir.c_str());
2197  strcat(name_cam,"/camera.bnd");
2198  set_scene(name_cam,&camera,cameraFactor);
2199 
2200  char name_arm[FILENAME_MAX];
2201  strcpy(name_arm, arm_dir.c_str());
2202  strcat(name_arm,"/viper850_arm1.bnd");
2203  set_scene(name_arm, robotArms, 1.0);
2204  strcpy(name_arm, arm_dir.c_str());
2205  strcat(name_arm,"/viper850_arm2.bnd");
2206  set_scene(name_arm, robotArms+1, 1.0);
2207  strcpy(name_arm, arm_dir.c_str());
2208  strcat(name_arm,"/viper850_arm3.bnd");
2209  set_scene(name_arm, robotArms+2, 1.0);
2210  strcpy(name_arm, arm_dir.c_str());
2211  strcat(name_arm,"/viper850_arm4.bnd");
2212  set_scene(name_arm, robotArms+3, 1.0);
2213  strcpy(name_arm, arm_dir.c_str());
2214  strcat(name_arm,"/viper850_arm5.bnd");
2215  set_scene(name_arm, robotArms+4, 1.0);
2216  strcpy(name_arm, arm_dir.c_str());
2217  strcat(name_arm,"/viper850_arm6.bnd");
2218  set_scene(name_arm, robotArms+5, 1.0);
2219 
2220 // set_scene("./arm2.bnd", robotArms+1, 1.0);
2221 // set_scene("./arm3.bnd", robotArms+2, 1.0);
2222 // set_scene("./arm4.bnd", robotArms+3, 1.0);
2223 // set_scene("./arm5.bnd", robotArms+4, 1.0);
2224 // set_scene("./arm6.bnd", robotArms+5, 1.0);
2225 
2226  add_rfstack(IS_BACK);
2227 
2228  add_vwstack ("start","depth", 0.0, 100.0);
2229  add_vwstack ("start","window", -0.1,0.1,-0.1,0.1);
2230  add_vwstack ("start","type", PERSPECTIVE);
2231 //
2232 // sceneInitialized = true;
2233 // displayObject = true;
2234  displayCamera = true;
2235 }
2236 
2237 
2238 void
2240 {
2241  bool changed = false;
2242  vpHomogeneousMatrix displacement = navigation(I,changed);
2243 
2244  //if (displacement[2][3] != 0)
2245  if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2246  camMf2 = camMf2*displacement;
2247 
2248  f2Mf = camMf2.inverse()*camMf;
2249 
2250  camMf = camMf2* displacement * f2Mf;
2251 
2252  double u;
2253  double v;
2254  //if(px_ext != 1 && py_ext != 1)
2255  // we assume px_ext and py_ext > 0
2256  if( (std::fabs(px_ext-1.) > vpMath::maximum(px_ext,1.)*std::numeric_limits<double>::epsilon())
2257  && (std::fabs(py_ext-1) > vpMath::maximum(py_ext,1.)*std::numeric_limits<double>::epsilon()))
2258  {
2259  u = (double)I.getWidth()/(2*px_ext);
2260  v = (double)I.getHeight()/(2*py_ext);
2261  }
2262  else
2263  {
2264  u = (double)I.getWidth()/(vpMath::minimum(I.getWidth(),I.getHeight()));
2265  v = (double)I.getHeight()/(vpMath::minimum(I.getWidth(),I.getHeight()));
2266  }
2267 
2268  float w44o[4][4],w44cext[4][4],x,y,z;
2269 
2270  vp2jlc_matrix(camMf.inverse(),w44cext);
2271 
2272  add_vwstack ("start","cop", w44cext[3][0],w44cext[3][1],w44cext[3][2]);
2273  x = w44cext[2][0] + w44cext[3][0];
2274  y = w44cext[2][1] + w44cext[3][1];
2275  z = w44cext[2][2] + w44cext[3][2];
2276  add_vwstack ("start","vrp", x,y,z);
2277  add_vwstack ("start","vpn", w44cext[2][0],w44cext[2][1],w44cext[2][2]);
2278  add_vwstack ("start","vup", w44cext[1][0],w44cext[1][1],w44cext[1][2]);
2279  add_vwstack ("start","window", -u, u, -v, v);
2280 
2281  vpHomogeneousMatrix fMit[8];
2282  get_fMi(fMit);
2283 
2284  vp2jlc_matrix(vpHomogeneousMatrix(0,0,0,0,0,0),w44o);
2285  display_scene(w44o,robotArms[0],I, curColor);
2286 
2287  vp2jlc_matrix(fMit[0],w44o);
2288  display_scene(w44o,robotArms[1],I, curColor);
2289 
2290  vp2jlc_matrix(fMit[1],w44o);
2291  display_scene(w44o,robotArms[2],I, curColor);
2292 
2293  vp2jlc_matrix(fMit[2],w44o);
2294  display_scene(w44o,robotArms[3],I, curColor);
2295 
2296  vp2jlc_matrix(fMit[3],w44o);
2297  display_scene(w44o,robotArms[4],I, curColor);
2298 
2299  vp2jlc_matrix(fMit[6],w44o);
2300  display_scene(w44o,robotArms[5],I, curColor);
2301 
2302  if (displayCamera)
2303  {
2304  vpHomogeneousMatrix cMe;
2305  get_cMe(cMe);
2306  cMe = cMe.inverse();
2307  cMe = fMit[6] * cMe;
2308  vp2jlc_matrix(cMe,w44o);
2309  display_scene(w44o,camera, I, camColor);
2310  }
2311 
2312  if (displayObject)
2313  {
2314  vp2jlc_matrix(fMo,w44o);
2315  display_scene(w44o,scene,I, curColor);
2316  }
2317 }
2318 
2326 void
2328 {
2329  vpColVector stop(6);
2330  stop = 0;
2331  set_artVel(stop);
2332  set_velocity(stop);
2334  fMc = fMo * cMo.inverse();
2335 
2336  vpColVector articularCoordinates = get_artCoord();
2337  unsigned int nbSol = getInverseKinematics(fMc, articularCoordinates);
2338 
2339  if (nbSol == 0)
2340  vpERROR_TRACE ("Positionning error. Position unreachable");
2341 
2342  set_artCoord(articularCoordinates);
2343 
2344  compute_fMi();
2345 }
2346 
2354 void
2356 {
2357  vpColVector stop(6);
2358  stop = 0;
2359  set_artVel(stop);
2360  set_velocity(stop);
2361  vpHomogeneousMatrix fMit[8];
2362  get_fMi(fMit);
2363  fMo = fMit[7] * cMo;
2364 }
2365 
2366 #endif
unsigned int jointLimitArt
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)
vpHomogeneousMatrix * fMi
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:289
void get_fMi(vpHomogeneousMatrix *fMit)
vpColVector get_velocity()
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:154
void get_cMe(vpHomogeneousMatrix &cMe)
void setJointLimit(vpColVector limitMin, vpColVector limitMax)
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:968
#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 ...
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color)
Definition: vpDisplay.cpp:482
virtual vpRobotStateType getRobotState(void)
Definition: vpRobot.h:148
void getExternalImage(vpImage< vpRGBa > &I)
vpHomogeneousMatrix navigation(vpImage< vpRGBa > &I, bool &changed)
void set_artVel(const vpColVector &vel)
static std::string getenv(const char *env)
Definition: vpIoTools.cpp:204
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:208
static const vpColor none
Definition: vpColor.h:177
Initialize the position controller.
Definition: vpRobot.h:71
void getCameraDisplacement(vpColVector &displacement)
void track(const vpHomogeneousMatrix &cMo)
vpHomogeneousMatrix getExternalCameraPosition() const
void get_fJe(vpMatrix &fJe)
vpControlFrameType
Definition: vpRobot.h:83
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:145
void getArticularDisplacement(vpColVector &displacement)
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:758
static const vpColor green
Definition: vpColor.h:168
vpHomogeneousMatrix fMo
double a2
for joint 2
Definition: vpViper.h:154
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:1964
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:233
void set_artCoord(const vpColVector &coord)
static DWORD WINAPI launcher(LPVOID lpParam)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:152
Class that defines what is a point.
Definition: vpPoint.h:65
void deg2rad()
Definition: vpColVector.h:186
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q)
Definition: vpViper.cpp:559
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:137
The vpRotationMatrix considers the particular case of a rotation matrix.
vpColVector get_artCoord()
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:147
void move(const char *filename)
This class aims to be a basis used to create all the simulators of robots.
Initialize the velocity controller.
Definition: vpRobot.h:70
vpRobotStateType
Definition: vpRobot.h:66
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)
bool constantSamplingTimeMode
Flag used to force the sampling time in the thread computing the robot's displacement to a constant v...
vpHomogeneousMatrix f2Mf
void setCameraParameters(const vpCameraParameters cam)
unsigned int size_fMi
static void display(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:186
Bound_scene * robotArms
void set_velocity(const vpColVector &vel)
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.
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement)
void setExternalCameraPosition(const vpHomogeneousMatrix camMf)
vpImage< vpRGBa > I
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:143
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...
vpColVector velocity
vpColVector artCoord
bool setVelocityCalled
Flag used to specify to the thread managing the robot displacements that the setVelocity() method has...
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:346
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
vpColVector get_artVel()
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpViper.cpp:1160
void display_scene(Matrix mat, Bound_scene &sc, vpImage< vpRGBa > &I, vpColor color)
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
void initialiseObjectRelativeToCamera(vpHomogeneousMatrix cMo)
vpHomogeneousMatrix camMf
vpCameraParameters cameraParam
vpHomogeneousMatrix fMc
static double deg(double rad)
Definition: vpMath.h:93
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition: vpRobot.h:113
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
void initialiseCameraRelativeToObject(vpHomogeneousMatrix cMo)
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpViper.cpp:914
unsigned int getHeight() const
Definition: vpImage.h:145
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:159
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:1810
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
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
vpDisplayRobotType displayType
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)
void setExternalCameraParameters(const vpCameraParameters cam)
static const double defaultPositioningVelocity
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:117
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 const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:597
void set_displayBusy(const bool &status)
vpHomogeneousMatrix camMf2
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