Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpSimulatorViper850.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Class which provides a simulator for the robot Viper850.
33  *
34 *****************************************************************************/
35 
36 #include <visp3/robot/vpSimulatorViper850.h>
37 
38 #if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS)
39 
40 #include <cmath> // std::fabs
41 #include <limits> // numeric_limits
42 #include <string>
43 #include <visp3/core/vpDebug.h>
44 #include <visp3/core/vpImagePoint.h>
45 #include <visp3/core/vpIoTools.h>
46 #include <visp3/core/vpMeterPixelConversion.h>
47 #include <visp3/core/vpPoint.h>
48 #include <visp3/core/vpTime.h>
49 
50 #include "../wireframe-simulator/vpBound.h"
51 #include "../wireframe-simulator/vpRfstack.h"
52 #include "../wireframe-simulator/vpScene.h"
53 #include "../wireframe-simulator/vpVwstack.h"
54 
57 
62  : vpRobotWireFrameSimulator(), vpViper850(), q_prev_getdis(), first_time_getdis(true),
63  positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir()
64 {
65  init();
66  initDisplay();
67 
69 
70  m_thread = new std::thread(&launcher, std::ref(*this));
71 
72  compute_fMi();
73 }
74 
82  : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true),
83  positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir()
84 {
85  init();
86  initDisplay();
87 
89 
90  m_thread = new std::thread(&launcher, std::ref(*this));
91 
92  compute_fMi();
93 }
94 
99 {
100  m_mutex_robotStop.lock();
101  robotStop = true;
102  m_mutex_robotStop.unlock();
103 
104  m_thread->join();
105 
106  if (robotArms != nullptr) {
107  // free_Bound_scene (&(camera));
108  for (int i = 0; i < 6; i++)
109  free_Bound_scene(&(robotArms[i]));
110  }
111 
112  delete[] robotArms;
113  delete[] fMi;
114  delete m_thread;
115 }
116 
126 {
127  // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
128  // VISP_ROBOT_ARMS_DIR may contain multiple locations separated by ";"
129  std::vector<std::string> arm_dirs = vpIoTools::splitChain(std::string(VISP_ROBOT_ARMS_DIR), std::string(";"));
130  bool armDirExists = false;
131  for (size_t i = 0; i < arm_dirs.size(); i++)
132  if (vpIoTools::checkDirectory(arm_dirs[i]) == true) { // directory exists
133  arm_dir = arm_dirs[i];
134  armDirExists = true;
135  break;
136  }
137  if (!armDirExists) {
138  try {
139  arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
140  std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
141  }
142  catch (...) {
143  std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
144  }
145  }
146 
148  toolCustom = false;
149 
150  size_fMi = 8;
151  fMi = new vpHomogeneousMatrix[8];
154 
155  zeroPos.resize(njoint);
156  zeroPos = 0;
157  zeroPos[1] = -M_PI / 2;
158  zeroPos[2] = M_PI;
159  reposPos.resize(njoint);
160  reposPos = 0;
161  reposPos[1] = -M_PI / 2;
162  reposPos[2] = M_PI;
163  reposPos[4] = M_PI / 2;
164 
165  artCoord = reposPos;
166  artVel = 0;
167 
168  q_prev_getdis.resize(njoint);
169  q_prev_getdis = 0;
170  first_time_getdis = true;
171 
172  positioningVelocity = defaultPositioningVelocity;
173 
176 
177  // Software joint limits in radians
178  // joint_min.resize(njoint);
179  joint_min[0] = vpMath::rad(-50);
180  joint_min[1] = vpMath::rad(-135);
181  joint_min[2] = vpMath::rad(-40);
182  joint_min[3] = vpMath::rad(-190);
183  joint_min[4] = vpMath::rad(-110);
184  joint_min[5] = vpMath::rad(-184);
185  // joint_max.resize(njoint);
186  joint_max[0] = vpMath::rad(50);
187  joint_max[1] = vpMath::rad(-40);
188  joint_max[2] = vpMath::rad(215);
189  joint_max[3] = vpMath::rad(190);
190  joint_max[4] = vpMath::rad(110);
191  joint_max[5] = vpMath::rad(184);
192 }
193 
198 {
199  robotArms = nullptr;
200  robotArms = new Bound_scene[6];
201  initArms();
202  setExternalCameraPosition(vpHomogeneousMatrix(0.0, 0.5, 1.5, vpMath::rad(90), 0, 0));
203  cameraParam.initPersProjWithoutDistortion(558.5309599, 556.055053, 320, 240);
205  vpCameraParameters tmp;
206  getCameraParameters(tmp, 640, 480);
207  px_int = tmp.get_px();
208  py_int = tmp.get_py();
209  sceneInitialized = true;
210 }
211 
228 {
229  this->projModel = proj_model;
230 
231  // Use here default values of the robot constant parameters.
232  switch (tool) {
234  erc[0] = vpMath::rad(0.07); // rx
235  erc[1] = vpMath::rad(2.76); // ry
236  erc[2] = vpMath::rad(-91.50); // rz
237  etc[0] = -0.0453; // tx
238  etc[1] = 0.0005; // ty
239  etc[2] = 0.0728; // tz
240 
241  setCameraParameters(vpCameraParameters(1232.0, 1233.0, 320, 240));
242  break;
243  }
245  erc[0] = vpMath::rad(0.1527764261); // rx
246  erc[1] = vpMath::rad(1.285092455); // ry
247  erc[2] = vpMath::rad(-90.75777848); // rz
248  etc[0] = -0.04558630174; // tx
249  etc[1] = -0.00134326752; // ty
250  etc[2] = 0.001000828017; // tz
251 
252  setCameraParameters(vpCameraParameters(868.0, 869.0, 320, 240));
253  break;
254  }
258  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
259  break;
260  }
261  }
262 
263  vpRotationMatrix eRc(erc);
264 
265  m_mutex_eMc.lock();
266  this->eMc.build(etc, eRc);
267  m_mutex_eMc.unlock();
268 
269  setToolType(tool);
270  return;
271 }
272 
283 void vpSimulatorViper850::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
284  const unsigned int &image_height)
285 {
286  if (toolCustom) {
287  cam.initPersProjWithoutDistortion(px_int, py_int, image_width / 2, image_height / 2);
288  }
289  // Set default parameters
290  switch (getToolType()) {
292  // Set default intrinsic camera parameters for 640x480 images
293  if (image_width == 640 && image_height == 480) {
294  std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\""
295  << std::endl;
296  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240);
297  }
298  else {
299  vpTRACE("Cannot get default intrinsic camera parameters for this image "
300  "resolution");
301  }
302  break;
303  }
305  // Set default intrinsic camera parameters for 640x480 images
306  if (image_width == 640 && image_height == 480) {
307  std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\""
308  << std::endl;
309  cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240);
310  }
311  else {
312  vpTRACE("Cannot get default intrinsic camera parameters for this image "
313  "resolution");
314  }
315  break;
316  }
320  std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
321  break;
322  }
323  }
324  return;
325 }
326 
336 {
337  getCameraParameters(cam, I_.getWidth(), I_.getHeight());
338 }
339 
349 {
350  getCameraParameters(cam, I_.getWidth(), I_.getHeight());
351 }
352 
359 {
360  px_int = cam.get_px();
361  py_int = cam.get_py();
362  toolCustom = true;
363 }
364 
370 {
371  double tcur_1 = tcur; // temporary variable used to store the last time
372  // since the last command
373 
374  bool stop = false;
375  bool setVelocityCalled_ = false;
376  while (!stop) {
377  // Get current time
378  tprev = tcur_1;
380 
382  setVelocityCalled_ = setVelocityCalled;
383  m_mutex_setVelocityCalled.unlock();
384 
385  if (setVelocityCalled_ || !constantSamplingTimeMode) {
387  setVelocityCalled = false;
388  m_mutex_setVelocityCalled.unlock();
390 
391  double ellapsedTime = (tcur - tprev) * 1e-3;
392  if (constantSamplingTimeMode) { // if we want a constant velocity, we
393  // force the ellapsed time to the given
394  // samplingTime
395  ellapsedTime = getSamplingTime(); // in second
396  }
397 
398  vpColVector articularCoordinates = get_artCoord();
399  vpColVector articularVelocities = get_artVel();
400 
401  if (jointLimit) {
402  double art = articularCoordinates[jointLimitArt - 1] + ellapsedTime * articularVelocities[jointLimitArt - 1];
403  if (art <= joint_min[jointLimitArt - 1] || art >= joint_max[jointLimitArt - 1]) {
404  if (verbose_) {
405  std::cout << "Joint " << jointLimitArt - 1
406  << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art)
407  << " < " << vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl;
408  }
409  articularVelocities = 0.0;
410  }
411  else
412  jointLimit = false;
413  }
414 
415  articularCoordinates[0] = articularCoordinates[0] + ellapsedTime * articularVelocities[0];
416  articularCoordinates[1] = articularCoordinates[1] + ellapsedTime * articularVelocities[1];
417  articularCoordinates[2] = articularCoordinates[2] + ellapsedTime * articularVelocities[2];
418  articularCoordinates[3] = articularCoordinates[3] + ellapsedTime * articularVelocities[3];
419  articularCoordinates[4] = articularCoordinates[4] + ellapsedTime * articularVelocities[4];
420  articularCoordinates[5] = articularCoordinates[5] + ellapsedTime * articularVelocities[5];
421 
422  int jl = isInJointLimit();
423 
424  if (jl != 0 && jointLimit == false) {
425  if (jl < 0)
426  ellapsedTime = (joint_min[(unsigned int)(-jl - 1)] - articularCoordinates[(unsigned int)(-jl - 1)]) /
427  (articularVelocities[(unsigned int)(-jl - 1)]);
428  else
429  ellapsedTime = (joint_max[(unsigned int)(jl - 1)] - articularCoordinates[(unsigned int)(jl - 1)]) /
430  (articularVelocities[(unsigned int)(jl - 1)]);
431 
432  for (unsigned int i = 0; i < 6; i++)
433  articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i];
434 
435  jointLimit = true;
436  jointLimitArt = (unsigned int)fabs((double)jl);
437  }
438 
439  set_artCoord(articularCoordinates);
440  set_artVel(articularVelocities);
441 
442  compute_fMi();
443 
444  if (displayAllowed) {
448  }
449 
450  if (displayType == MODEL_3D && displayAllowed) {
451  while (get_displayBusy()) {
452  vpTime::wait(2);
453  }
455  set_displayBusy(false);
456  }
457 
458  if (displayType == MODEL_DH && displayAllowed) {
459  vpHomogeneousMatrix fMit[8];
460  get_fMi(fMit);
461 
462  // vpDisplay::displayFrame(I,getExternalCameraPosition
463  // ()*fMi[6],cameraParam,0.2,vpColor::none);
464 
465  vpImagePoint iP, iP_1;
466  vpPoint pt(0, 0, 0);
467 
470  pt.track(getExternalCameraPosition() * fMit[0]);
473  for (int k = 1; k < 7; k++) {
474  pt.track(getExternalCameraPosition() * fMit[k - 1]);
476 
477  pt.track(getExternalCameraPosition() * fMit[k]);
479 
481  }
483  thickness_);
484  }
485 
487 
488  vpTime::wait(tcur, 1000 * getSamplingTime());
489  tcur_1 = tcur;
490  }
491  else {
493  }
494  m_mutex_robotStop.lock();
495  stop = robotStop;
496  m_mutex_robotStop.unlock();
497  }
498 }
499 
513 {
514  // vpColVector q = get_artCoord();
515  vpColVector q(6); //; = get_artCoord();
516  q = get_artCoord();
517 
518  vpHomogeneousMatrix fMit[8];
519 
520  double q1 = q[0];
521  double q2 = q[1];
522  double q3 = q[2];
523  double q4 = q[3];
524  double q5 = q[4];
525  double q6 = q[5];
526 
527  double c1 = cos(q1);
528  double s1 = sin(q1);
529  double c2 = cos(q2);
530  double s2 = sin(q2);
531  double c23 = cos(q2 + q3);
532  double s23 = sin(q2 + q3);
533  double c4 = cos(q4);
534  double s4 = sin(q4);
535  double c5 = cos(q5);
536  double s5 = sin(q5);
537  double c6 = cos(q6);
538  double s6 = sin(q6);
539 
540  fMit[0][0][0] = c1;
541  fMit[0][1][0] = s1;
542  fMit[0][2][0] = 0;
543  fMit[0][0][1] = 0;
544  fMit[0][1][1] = 0;
545  fMit[0][2][1] = -1;
546  fMit[0][0][2] = -s1;
547  fMit[0][1][2] = c1;
548  fMit[0][2][2] = 0;
549  fMit[0][0][3] = a1 * c1;
550  fMit[0][1][3] = a1 * s1;
551  fMit[0][2][3] = d1;
552 
553  fMit[1][0][0] = c1 * c2;
554  fMit[1][1][0] = s1 * c2;
555  fMit[1][2][0] = -s2;
556  fMit[1][0][1] = -c1 * s2;
557  fMit[1][1][1] = -s1 * s2;
558  fMit[1][2][1] = -c2;
559  fMit[1][0][2] = -s1;
560  fMit[1][1][2] = c1;
561  fMit[1][2][2] = 0;
562  fMit[1][0][3] = c1 * (a2 * c2 + a1);
563  fMit[1][1][3] = s1 * (a2 * c2 + a1);
564  fMit[1][2][3] = d1 - a2 * s2;
565 
566  double quickcomp1 = a3 * c23 - a2 * c2 - a1;
567 
568  fMit[2][0][0] = -c1 * c23;
569  fMit[2][1][0] = -s1 * c23;
570  fMit[2][2][0] = s23;
571  fMit[2][0][1] = s1;
572  fMit[2][1][1] = -c1;
573  fMit[2][2][1] = 0;
574  fMit[2][0][2] = c1 * s23;
575  fMit[2][1][2] = s1 * s23;
576  fMit[2][2][2] = c23;
577  fMit[2][0][3] = -c1 * quickcomp1;
578  fMit[2][1][3] = -s1 * quickcomp1;
579  fMit[2][2][3] = a3 * s23 - a2 * s2 + d1;
580 
581  double quickcomp2 = c1 * (s23 * d4 - quickcomp1);
582  double quickcomp3 = s1 * (s23 * d4 - quickcomp1);
583 
584  fMit[3][0][0] = -c1 * c23 * c4 + s1 * s4;
585  fMit[3][1][0] = -s1 * c23 * c4 - c1 * s4;
586  fMit[3][2][0] = s23 * c4;
587  fMit[3][0][1] = c1 * s23;
588  fMit[3][1][1] = s1 * s23;
589  fMit[3][2][1] = c23;
590  fMit[3][0][2] = -c1 * c23 * s4 - s1 * c4;
591  fMit[3][1][2] = -s1 * c23 * s4 + c1 * c4;
592  fMit[3][2][2] = s23 * s4;
593  fMit[3][0][3] = quickcomp2;
594  fMit[3][1][3] = quickcomp3;
595  fMit[3][2][3] = c23 * d4 + a3 * s23 - a2 * s2 + d1;
596 
597  fMit[4][0][0] = c1 * (s23 * s5 - c5 * c23 * c4) + s1 * c5 * s4;
598  fMit[4][1][0] = s1 * (s23 * s5 - c5 * c23 * c4) - c1 * c5 * s4;
599  fMit[4][2][0] = s23 * c4 * c5 + c23 * s5;
600  fMit[4][0][1] = c1 * c23 * s4 + s1 * c4;
601  fMit[4][1][1] = s1 * c23 * s4 - c1 * c4;
602  fMit[4][2][1] = -s23 * s4;
603  fMit[4][0][2] = c1 * (s23 * c5 + s5 * c23 * c4) - s1 * s5 * s4;
604  fMit[4][1][2] = s1 * (s23 * c5 + s5 * c23 * c4) + c1 * s5 * s4;
605  fMit[4][2][2] = -s23 * c4 * s5 + c23 * c5;
606  fMit[4][0][3] = quickcomp2;
607  fMit[4][1][3] = quickcomp3;
608  fMit[4][2][3] = c23 * d4 + a3 * s23 - a2 * s2 + d1;
609 
610  fMit[5][0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
611  fMit[5][1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
612  fMit[5][2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
613  fMit[5][0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
614  fMit[5][1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
615  fMit[5][2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
616  fMit[5][0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
617  fMit[5][1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
618  fMit[5][2][2] = -s23 * c4 * s5 + c23 * c5;
619  fMit[5][0][3] = quickcomp2;
620  fMit[5][1][3] = quickcomp3;
621  fMit[5][2][3] = s23 * a3 + c23 * d4 - a2 * s2 + d1;
622 
623  fMit[6][0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
624  fMit[6][1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
625  fMit[6][2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
626  fMit[6][0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
627  fMit[6][1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
628  fMit[6][2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
629  fMit[6][0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
630  fMit[6][1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
631  fMit[6][2][2] = -s23 * c4 * s5 + c23 * c5;
632  fMit[6][0][3] = c1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) - s1 * s4 * s5 * d6;
633  fMit[6][1][3] = s1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) + c1 * s4 * s5 * d6;
634  fMit[6][2][3] = s23 * (a3 - c4 * s5 * d6) + c23 * (c5 * d6 + d4) - a2 * s2 + d1;
635 
636  // vpHomogeneousMatrix cMe;
637  // get_cMe(cMe);
638  // cMe = cMe.inverse();
639  // fMit[7] = fMit[6] * cMe;
640  m_mutex_eMc.lock();
641  vpViper::get_fMc(q, fMit[7]);
642  m_mutex_eMc.unlock();
643 
644  m_mutex_fMi.lock();
645  for (int i = 0; i < 8; i++) {
646  fMi[i] = fMit[i];
647  }
648  m_mutex_fMi.unlock();
649 }
650 
657 {
658  switch (newState) {
659  case vpRobot::STATE_STOP: {
660  // Start primitive STOP only if the current state is Velocity
662  stopMotion();
663  }
664  break;
665  }
668  std::cout << "Change the control mode from velocity to position control.\n";
669  stopMotion();
670  }
671  else {
672  // std::cout << "Change the control mode from stop to position
673  // control.\n";
674  }
675  break;
676  }
679  std::cout << "Change the control mode from stop to velocity control.\n";
680  }
681  break;
682  }
684  default:
685  break;
686  }
687 
688  return vpRobot::setRobotState(newState);
689 }
690 
768 {
770  vpERROR_TRACE("Cannot send a velocity to the robot "
771  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
773  "Cannot send a velocity to the robot "
774  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
775  }
776 
777  vpColVector vel_sat(6);
778 
779  double scale_sat = 1;
780  double vel_trans_max = getMaxTranslationVelocity();
781  double vel_rot_max = getMaxRotationVelocity();
782 
783  double vel_abs; // Absolute value
784 
785  // Velocity saturation
786  switch (frame) {
787  // saturation in cartesian space
790  if (vel.getRows() != 6) {
791  vpERROR_TRACE("The velocity vector must have a size of 6 !!!!");
792  throw;
793  }
794 
795  for (unsigned int i = 0; i < 3; ++i) {
796  vel_abs = fabs(vel[i]);
797  if (vel_abs > vel_trans_max && !jointLimit) {
798  vel_trans_max = vel_abs;
799  vpERROR_TRACE("Excess velocity %g m/s in TRANSLATION "
800  "(axis nr. %d).",
801  vel[i], i + 1);
802  }
803 
804  vel_abs = fabs(vel[i + 3]);
805  if (vel_abs > vel_rot_max && !jointLimit) {
806  vel_rot_max = vel_abs;
807  vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
808  "(axis nr. %d).",
809  vel[i + 3], i + 4);
810  }
811  }
812 
813  double scale_trans_sat = 1;
814  double scale_rot_sat = 1;
815  if (vel_trans_max > getMaxTranslationVelocity())
816  scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
817 
818  if (vel_rot_max > getMaxRotationVelocity())
819  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
820 
821  if ((scale_trans_sat < 1) || (scale_rot_sat < 1)) {
822  if (scale_trans_sat < scale_rot_sat)
823  scale_sat = scale_trans_sat;
824  else
825  scale_sat = scale_rot_sat;
826  }
827  break;
828  }
829 
830  // saturation in joint space
832  if (vel.getRows() != 6) {
833  vpERROR_TRACE("The velocity vector must have a size of 6 !!!!");
834  throw;
835  }
836  for (unsigned int i = 0; i < 6; ++i) {
837  vel_abs = fabs(vel[i]);
838  if (vel_abs > vel_rot_max && !jointLimit) {
839  vel_rot_max = vel_abs;
840  vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
841  "(axis nr. %d).",
842  vel[i], i + 1);
843  }
844  }
845  double scale_rot_sat = 1;
846  if (vel_rot_max > getMaxRotationVelocity())
847  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
848  if (scale_rot_sat < 1)
849  scale_sat = scale_rot_sat;
850  break;
851  }
853  case vpRobot::MIXT_FRAME: {
854  break;
855  }
856  }
857 
858  set_velocity(vel * scale_sat);
859 
860  m_mutex_frame.lock();
861  setRobotFrame(frame);
862  m_mutex_frame.unlock();
863 
865  setVelocityCalled = true;
866  m_mutex_setVelocityCalled.unlock();
867 }
868 
873 {
875 
876  m_mutex_frame.lock();
877  frame = getRobotFrame();
878  m_mutex_frame.unlock();
879 
880  double vel_rot_max = getMaxRotationVelocity();
881 
882  vpColVector articularCoordinates = get_artCoord();
883  vpColVector velocityframe = get_velocity();
884  vpColVector articularVelocity;
885 
886  switch (frame) {
887  case vpRobot::CAMERA_FRAME: {
888  vpMatrix eJe_;
890  vpViper850::get_eJe(articularCoordinates, eJe_);
891  eJe_ = eJe_.pseudoInverse();
893  singularityTest(articularCoordinates, eJe_);
894  articularVelocity = eJe_ * eVc * velocityframe;
895  set_artVel(articularVelocity);
896  break;
897  }
899  vpMatrix fJe_;
900  vpViper850::get_fJe(articularCoordinates, fJe_);
901  fJe_ = fJe_.pseudoInverse();
903  singularityTest(articularCoordinates, fJe_);
904  articularVelocity = fJe_ * velocityframe;
905  set_artVel(articularVelocity);
906  break;
907  }
909  articularVelocity = velocityframe;
910  set_artVel(articularVelocity);
911  break;
912  }
914  case vpRobot::MIXT_FRAME: {
915  break;
916  }
917  }
918 
919  switch (frame) {
922  for (unsigned int i = 0; i < 6; ++i) {
923  double vel_abs = fabs(articularVelocity[i]);
924  if (vel_abs > vel_rot_max && !jointLimit) {
925  vel_rot_max = vel_abs;
926  vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
927  "(axis nr. %d).",
928  articularVelocity[i], i + 1);
929  }
930  }
931  double scale_rot_sat = 1;
932  double scale_sat = 1;
933 
934  if (vel_rot_max > getMaxRotationVelocity())
935  scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
936  if (scale_rot_sat < 1)
937  scale_sat = scale_rot_sat;
938 
939  set_artVel(articularVelocity * scale_sat);
940  break;
941  }
944  case vpRobot::MIXT_FRAME: {
945  break;
946  }
947  }
948 }
949 
1000 {
1001  vel.resize(6);
1002 
1003  vpColVector articularCoordinates = get_artCoord();
1004  vpColVector articularVelocity = get_artVel();
1005 
1006  switch (frame) {
1007  case vpRobot::CAMERA_FRAME: {
1008  vpMatrix eJe_;
1010  vpViper850::get_eJe(articularCoordinates, eJe_);
1011  vel = cVe * eJe_ * articularVelocity;
1012  break;
1013  }
1014  case vpRobot::ARTICULAR_FRAME: {
1015  vel = articularVelocity;
1016  break;
1017  }
1018  case vpRobot::REFERENCE_FRAME: {
1019  vpMatrix fJe_;
1020  vpViper850::get_fJe(articularCoordinates, fJe_);
1021  vel = fJe_ * articularVelocity;
1022  break;
1023  }
1025  case vpRobot::MIXT_FRAME: {
1026  break;
1027  }
1028  default: {
1029  vpERROR_TRACE("Error in spec of vpRobot. "
1030  "Case not taken in account.");
1031  return;
1032  }
1033  }
1034 }
1035 
1053 {
1054  timestamp = vpTime::measureTimeSecond();
1055  getVelocity(frame, vel);
1056 }
1057 
1104 {
1105  vpColVector vel(6);
1106  getVelocity(frame, vel);
1107 
1108  return vel;
1109 }
1110 
1124 {
1125  timestamp = vpTime::measureTimeSecond();
1126  vpColVector vel(6);
1127  getVelocity(frame, vel);
1128 
1129  return vel;
1130 }
1131 
1133 {
1134  double vel_rot_max = getMaxRotationVelocity();
1135  double velmax = fabs(q[0]);
1136  for (unsigned int i = 1; i < 6; i++) {
1137  if (velmax < fabs(q[i]))
1138  velmax = fabs(q[i]);
1139  }
1140 
1141  double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax * 100);
1142  q = q * alpha;
1143 }
1144 
1224 {
1226  vpERROR_TRACE("Robot was not in position-based control\n"
1227  "Modification of the robot state");
1228  // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1229  }
1230 
1231  vpColVector articularCoordinates = get_artCoord();
1232 
1233  vpColVector error(6);
1234  double errsqr = 0;
1235  switch (frame) {
1236  case vpRobot::CAMERA_FRAME: {
1237  unsigned int nbSol;
1238  vpColVector qdes(6);
1239 
1240  vpTranslationVector txyz;
1241  vpRxyzVector rxyz;
1242  for (unsigned int i = 0; i < 3; i++) {
1243  txyz[i] = q[i];
1244  rxyz[i] = q[i + 3];
1245  }
1246 
1247  vpRotationMatrix cRc2(rxyz);
1248  vpHomogeneousMatrix cMc2(txyz, cRc2);
1249 
1250  vpHomogeneousMatrix fMc_;
1251  vpViper850::get_fMc(articularCoordinates, fMc_);
1252 
1253  vpHomogeneousMatrix fMc2 = fMc_ * cMc2;
1254 
1255  do {
1256  articularCoordinates = get_artCoord();
1257  qdes = articularCoordinates;
1258  nbSol = getInverseKinematics(fMc2, qdes, verbose_);
1260  setVelocityCalled = true;
1261  m_mutex_setVelocityCalled.unlock();
1262  if (nbSol > 0) {
1263  error = qdes - articularCoordinates;
1264  errsqr = error.sumSquare();
1265  // findHighestPositioningSpeed(error);
1266  set_artVel(error);
1267  if (errsqr < 1e-4) {
1268  set_artCoord(qdes);
1269  error = 0;
1270  set_artVel(error);
1271  set_velocity(error);
1272  break;
1273  }
1274  }
1275  else {
1276  vpERROR_TRACE("Positioning error.");
1277  throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1278  }
1279  } while (errsqr > 1e-8 && nbSol > 0);
1280 
1281  break;
1282  }
1283 
1284  case vpRobot::ARTICULAR_FRAME: {
1285  do {
1286  articularCoordinates = get_artCoord();
1287  error = q - articularCoordinates;
1288  errsqr = error.sumSquare();
1289  // findHighestPositioningSpeed(error);
1290  set_artVel(error);
1292  setVelocityCalled = true;
1293  m_mutex_setVelocityCalled.unlock();
1294  if (errsqr < 1e-4) {
1295  set_artCoord(q);
1296  error = 0;
1297  set_artVel(error);
1298  set_velocity(error);
1299  break;
1300  }
1301  } while (errsqr > 1e-8);
1302  break;
1303  }
1304 
1305  case vpRobot::REFERENCE_FRAME: {
1306  unsigned int nbSol;
1307  vpColVector qdes(6);
1308 
1309  vpTranslationVector txyz;
1310  vpRxyzVector rxyz;
1311  for (unsigned int i = 0; i < 3; i++) {
1312  txyz[i] = q[i];
1313  rxyz[i] = q[i + 3];
1314  }
1315 
1316  vpRotationMatrix fRc(rxyz);
1317  vpHomogeneousMatrix fMc_(txyz, fRc);
1318 
1319  do {
1320  articularCoordinates = get_artCoord();
1321  qdes = articularCoordinates;
1322  nbSol = getInverseKinematics(fMc_, qdes, verbose_);
1323  if (nbSol > 0) {
1324  error = qdes - articularCoordinates;
1325  errsqr = error.sumSquare();
1326  // findHighestPositioningSpeed(error);
1327  set_artVel(error);
1329  setVelocityCalled = true;
1330  m_mutex_setVelocityCalled.unlock();
1331  if (errsqr < 1e-4) {
1332  set_artCoord(qdes);
1333  error = 0;
1334  set_artVel(error);
1335  set_velocity(error);
1336  break;
1337  }
1338  }
1339  else
1340  vpERROR_TRACE("Positioning error. Position unreachable");
1341  } while (errsqr > 1e-8 && nbSol > 0);
1342  break;
1343  }
1344  case vpRobot::MIXT_FRAME: {
1345  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1346  "Mixt frame not implemented.");
1347  }
1349  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1350  "End-effector frame not implemented.");
1351  }
1352  }
1353 }
1354 
1421 void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1422  double pos4, double pos5, double pos6)
1423 {
1424  try {
1425  vpColVector position(6);
1426  position[0] = pos1;
1427  position[1] = pos2;
1428  position[2] = pos3;
1429  position[3] = pos4;
1430  position[4] = pos5;
1431  position[5] = pos6;
1432 
1433  setPosition(frame, position);
1434  }
1435  catch (...) {
1436  vpERROR_TRACE("Error caught");
1437  throw;
1438  }
1439 }
1440 
1479 void vpSimulatorViper850::setPosition(const char *filename)
1480 {
1481  vpColVector q;
1482  bool ret;
1483 
1484  ret = this->readPosFile(filename, q);
1485 
1486  if (ret == false) {
1487  vpERROR_TRACE("Bad position in \"%s\"", filename);
1488  throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1489  }
1492 }
1493 
1557 {
1558  q.resize(6);
1559 
1560  switch (frame) {
1561  case vpRobot::CAMERA_FRAME: {
1562  q = 0;
1563  break;
1564  }
1565 
1566  case vpRobot::ARTICULAR_FRAME: {
1567  q = get_artCoord();
1568  break;
1569  }
1570 
1571  case vpRobot::REFERENCE_FRAME: {
1572  vpHomogeneousMatrix fMc_;
1573  vpViper::get_fMc(get_artCoord(), fMc_);
1574 
1575  vpRotationMatrix fRc;
1576  fMc_.extract(fRc);
1577  vpRxyzVector rxyz(fRc);
1578 
1579  vpTranslationVector txyz;
1580  fMc_.extract(txyz);
1581 
1582  for (unsigned int i = 0; i < 3; i++) {
1583  q[i] = txyz[i];
1584  q[i + 3] = rxyz[i];
1585  }
1586  break;
1587  }
1588 
1589  case vpRobot::MIXT_FRAME: {
1590  vpERROR_TRACE("Positioning error. Mixt frame not implemented");
1591  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1592  "Mixt frame not implemented.");
1593  }
1595  vpERROR_TRACE("Positioning error. Mixt frame not implemented");
1596  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1597  "End-effector frame not implemented.");
1598  }
1599  }
1600 }
1601 
1629 {
1630  timestamp = vpTime::measureTimeSecond();
1631  getPosition(frame, q);
1632 }
1633 
1646 {
1647  vpColVector posRxyz;
1648  // recupere position en Rxyz
1649  this->getPosition(frame, posRxyz);
1650 
1651  // recupere le vecteur thetaU correspondant
1652  vpThetaUVector RtuVect(vpRxyzVector(posRxyz[3], posRxyz[4], posRxyz[5]));
1653 
1654  // remplit le vpPoseVector avec translation et rotation ThetaU
1655  for (unsigned int j = 0; j < 3; j++) {
1656  position[j] = posRxyz[j];
1657  position[j + 3] = RtuVect[j];
1658  }
1659 }
1660 
1673  double &timestamp)
1674 {
1675  timestamp = vpTime::measureTimeSecond();
1676  getPosition(frame, position);
1677 }
1678 
1687 void vpSimulatorViper850::setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
1688 {
1689  if (limitMin.getRows() != 6 || limitMax.getRows() != 6) {
1690  vpTRACE("Joint limit vector has not a size of 6 !");
1691  return;
1692  }
1693 
1694  joint_min[0] = limitMin[0];
1695  joint_min[1] = limitMin[1];
1696  joint_min[2] = limitMin[2];
1697  joint_min[3] = limitMin[3];
1698  joint_min[4] = limitMin[4];
1699  joint_min[5] = limitMin[5];
1700 
1701  joint_max[0] = limitMax[0];
1702  joint_max[1] = limitMax[1];
1703  joint_max[2] = limitMax[2];
1704  joint_max[3] = limitMax[3];
1705  joint_max[4] = limitMax[4];
1706  joint_max[5] = limitMax[5];
1707 }
1708 
1715 {
1716  double q2 = q[1];
1717  double q3 = q[2];
1718  double q5 = q[4];
1719 
1720  double c2 = cos(q2);
1721  double c3 = cos(q3);
1722  double s3 = sin(q3);
1723  double c23 = cos(q2 + q3);
1724  double s23 = sin(q2 + q3);
1725  double s5 = sin(q5);
1726 
1727  bool cond1 = fabs(s5) < 1e-1;
1728  bool cond2 = fabs(a3 * s3 + c3 * d4) < 1e-1;
1729  bool cond3 = fabs(a2 * c2 - a3 * c23 + s23 * d4 + a1) < 1e-1;
1730 
1731  if (cond1) {
1732  J[3][0] = 0;
1733  J[5][0] = 0;
1734  J[3][1] = 0;
1735  J[5][1] = 0;
1736  J[3][2] = 0;
1737  J[5][2] = 0;
1738  J[3][3] = 0;
1739  J[5][3] = 0;
1740  J[3][4] = 0;
1741  J[5][4] = 0;
1742  J[3][5] = 0;
1743  J[5][5] = 0;
1744  return true;
1745  }
1746 
1747  if (cond2) {
1748  J[1][0] = 0;
1749  J[2][0] = 0;
1750  J[3][0] = 0;
1751  J[4][0] = 0;
1752  J[5][0] = 0;
1753  J[1][1] = 0;
1754  J[2][1] = 0;
1755  J[3][1] = 0;
1756  J[4][1] = 0;
1757  J[5][1] = 0;
1758  J[1][2] = 0;
1759  J[2][2] = 0;
1760  J[3][2] = 0;
1761  J[4][2] = 0;
1762  J[5][2] = 0;
1763  return true;
1764  }
1765 
1766  if (cond3) {
1767  J[0][0] = 0;
1768  J[3][0] = 0;
1769  J[4][0] = 0;
1770  J[5][0] = 0;
1771  J[0][1] = 0;
1772  J[3][1] = 0;
1773  J[4][1] = 0;
1774  J[5][1] = 0;
1775  }
1776 
1777  return false;
1778 }
1779 
1784 {
1785  int artNumb = 0;
1786  double diff = 0;
1787  double difft = 0;
1788 
1789  vpColVector articularCoordinates = get_artCoord();
1790 
1791  for (unsigned int i = 0; i < 6; i++) {
1792  if (articularCoordinates[i] <= joint_min[i]) {
1793  difft = joint_min[i] - articularCoordinates[i];
1794  if (difft > diff) {
1795  diff = difft;
1796  artNumb = -(int)i - 1;
1797  }
1798  }
1799  }
1800 
1801  for (unsigned int i = 0; i < 6; i++) {
1802  if (articularCoordinates[i] >= joint_max[i]) {
1803  difft = articularCoordinates[i] - joint_max[i];
1804  if (difft > diff) {
1805  diff = difft;
1806  artNumb = (int)(i + 1);
1807  }
1808  }
1809  }
1810 
1811  if (artNumb != 0)
1812  std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!"
1813  << std::endl;
1814 
1815  return artNumb;
1816 }
1817 
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  switch (frame) {
1845  case vpRobot::CAMERA_FRAME: {
1846  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
1847  return;
1848  }
1849 
1850  case vpRobot::ARTICULAR_FRAME: {
1851  displacement = q_cur - q_prev_getdis;
1852  break;
1853  }
1854 
1855  case vpRobot::REFERENCE_FRAME: {
1856  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
1857  return;
1858  }
1859 
1860  case vpRobot::MIXT_FRAME: {
1861  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
1862  return;
1863  }
1865  std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
1866  return;
1867  }
1868  }
1869  }
1870  else {
1871  first_time_getdis = false;
1872  }
1873 
1874  // Memorize the joint position for the next call
1875  q_prev_getdis = q_cur;
1876 }
1877 
1943 bool vpSimulatorViper850::readPosFile(const std::string &filename, vpColVector &q)
1944 {
1945  std::ifstream fd(filename.c_str(), std::ios::in);
1946 
1947  if (!fd.is_open()) {
1948  return false;
1949  }
1950 
1951  std::string line;
1952  std::string key("R:");
1953  std::string id("#Viper850 - Position");
1954  bool pos_found = false;
1955  int lineNum = 0;
1956 
1957  q.resize(njoint);
1958 
1959  while (std::getline(fd, line)) {
1960  lineNum++;
1961  if (lineNum == 1) {
1962  if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper850 position file
1963  std::cout << "Error: this position file " << filename << " is not for Viper850 robot" << std::endl;
1964  return false;
1965  }
1966  }
1967  if ((line.compare(0, 1, "#") == 0)) { // skip comment
1968  continue;
1969  }
1970  if ((line.compare(0, key.size(), key) == 0)) { // decode position
1971  // check if there are at least njoint values in the line
1972  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1973  if (chain.size() < njoint + 1) // try to split with tab separator
1974  chain = vpIoTools::splitChain(line, std::string("\t"));
1975  if (chain.size() < njoint + 1)
1976  continue;
1977 
1978  std::istringstream ss(line);
1979  std::string key_;
1980  ss >> key_;
1981  for (unsigned int i = 0; i < njoint; i++)
1982  ss >> q[i];
1983  pos_found = true;
1984  break;
1985  }
1986  }
1987 
1988  // converts rotations from degrees into radians
1989  q.deg2rad();
1990 
1991  fd.close();
1992 
1993  if (!pos_found) {
1994  std::cout << "Error: unable to find a position for Viper850 robot in " << filename << std::endl;
1995  return false;
1996  }
1997 
1998  return true;
1999 }
2000 
2022 bool vpSimulatorViper850::savePosFile(const std::string &filename, const vpColVector &q)
2023 {
2024 
2025  FILE *fd;
2026  fd = fopen(filename.c_str(), "w");
2027  if (fd == nullptr)
2028  return false;
2029 
2030  fprintf(fd, "\
2031 #Viper - Position - Version 1.0\n\
2032 #\n\
2033 # R: A B C D E F\n\
2034 # Joint position in degrees\n\
2035 #\n\
2036 #\n\n");
2037 
2038  // Save positions in mm and deg
2039  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2040  vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2041 
2042  fclose(fd);
2043  return (true);
2044 }
2045 
2053 void vpSimulatorViper850::move(const char *filename)
2054 {
2055  vpColVector q;
2056 
2057  try {
2058  this->readPosFile(filename, q);
2061  }
2062  catch (...) {
2063  throw;
2064  }
2065 }
2066 
2077 
2086 {
2087  vpHomogeneousMatrix cMe;
2088  vpViper850::get_cMe(cMe);
2089 
2090  cVe.build(cMe);
2091 }
2092 
2103 {
2104  try {
2106  }
2107  catch (...) {
2108  vpERROR_TRACE("catch exception ");
2109  throw;
2110  }
2111 }
2112 
2124 {
2125  try {
2126  vpColVector articularCoordinates = get_artCoord();
2127  vpViper850::get_fJe(articularCoordinates, fJe_);
2128  }
2129  catch (...) {
2130  vpERROR_TRACE("Error caught");
2131  throw;
2132  }
2133 }
2134 
2139 {
2141  return;
2142 
2143  vpColVector stop(6);
2144  stop = 0;
2145  set_artVel(stop);
2146  set_velocity(stop);
2148 }
2149 
2150 /**********************************************************************************/
2151 /**********************************************************************************/
2152 /**********************************************************************************/
2153 /**********************************************************************************/
2154 
2164 {
2165  // set scene_dir from #define VISP_SCENE_DIR if it exists
2166  // VISP_SCENES_DIR may contain multiple locations separated by ";"
2167  std::string scene_dir_;
2168  std::vector<std::string> scene_dirs = vpIoTools::splitChain(std::string(VISP_SCENES_DIR), std::string(";"));
2169  bool sceneDirExists = false;
2170  for (size_t i = 0; i < scene_dirs.size(); i++)
2171  if (vpIoTools::checkDirectory(scene_dirs[i]) == true) { // directory exists
2172  scene_dir_ = scene_dirs[i];
2173  sceneDirExists = true;
2174  break;
2175  }
2176  if (!sceneDirExists) {
2177  try {
2178  scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR");
2179  std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2180  }
2181  catch (...) {
2182  std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2183  }
2184  }
2185 
2186  unsigned int name_length = 30; // the size of this kind of string "/viper850_arm2.bnd"
2187  if (scene_dir_.size() > FILENAME_MAX)
2188  throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2189 
2190  unsigned int full_length = (unsigned int)scene_dir_.size() + name_length;
2191  if (full_length > FILENAME_MAX)
2192  throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2193 
2194  char *name_cam = new char[full_length];
2195 
2196  strcpy(name_cam, scene_dir_.c_str());
2197  strcat(name_cam, "/camera.bnd");
2198  set_scene(name_cam, &camera, cameraFactor);
2199 
2200  if (arm_dir.size() > FILENAME_MAX)
2201  throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2202  full_length = (unsigned int)arm_dir.size() + name_length;
2203  if (full_length > FILENAME_MAX)
2204  throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2205 
2206  char *name_arm = new char[full_length];
2207  strcpy(name_arm, arm_dir.c_str());
2208  strcat(name_arm, "/viper850_arm1.bnd");
2209  set_scene(name_arm, robotArms, 1.0);
2210  strcpy(name_arm, arm_dir.c_str());
2211  strcat(name_arm, "/viper850_arm2.bnd");
2212  set_scene(name_arm, robotArms + 1, 1.0);
2213  strcpy(name_arm, arm_dir.c_str());
2214  strcat(name_arm, "/viper850_arm3.bnd");
2215  set_scene(name_arm, robotArms + 2, 1.0);
2216  strcpy(name_arm, arm_dir.c_str());
2217  strcat(name_arm, "/viper850_arm4.bnd");
2218  set_scene(name_arm, robotArms + 3, 1.0);
2219  strcpy(name_arm, arm_dir.c_str());
2220  strcat(name_arm, "/viper850_arm5.bnd");
2221  set_scene(name_arm, robotArms + 4, 1.0);
2222  strcpy(name_arm, arm_dir.c_str());
2223  strcat(name_arm, "/viper850_arm6.bnd");
2224  set_scene(name_arm, robotArms + 5, 1.0);
2225 
2226  // set_scene("./arm2.bnd", robotArms+1, 1.0);
2227  // set_scene("./arm3.bnd", robotArms+2, 1.0);
2228  // set_scene("./arm4.bnd", robotArms+3, 1.0);
2229  // set_scene("./arm5.bnd", robotArms+4, 1.0);
2230  // set_scene("./arm6.bnd", robotArms+5, 1.0);
2231 
2232  add_rfstack(IS_BACK);
2233 
2234  add_vwstack("start", "depth", 0.0, 100.0);
2235  add_vwstack("start", "window", -0.1, 0.1, -0.1, 0.1);
2236  add_vwstack("start", "type", PERSPECTIVE);
2237  //
2238  // sceneInitialized = true;
2239  // displayObject = true;
2240  displayCamera = true;
2241 
2242  delete[] name_cam;
2243  delete[] name_arm;
2244 }
2245 
2247 {
2248  m_mutex_scene.lock();
2249  bool changed = false;
2250  vpHomogeneousMatrix displacement = navigation(I_, changed);
2251 
2252  // if (displacement[2][3] != 0)
2253  if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2254  camMf2 = camMf2 * displacement;
2255 
2256  f2Mf = camMf2.inverse() * camMf;
2257 
2258  camMf = camMf2 * displacement * f2Mf;
2259 
2260  double u;
2261  double v;
2262  // if(px_ext != 1 && py_ext != 1)
2263  // we assume px_ext and py_ext > 0
2264  if ((std::fabs(px_ext - 1.) > vpMath::maximum(px_ext, 1.) * std::numeric_limits<double>::epsilon()) &&
2265  (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits<double>::epsilon())) {
2266  u = (double)I_.getWidth() / (2 * px_ext);
2267  v = (double)I_.getHeight() / (2 * py_ext);
2268  }
2269  else {
2270  u = (double)I_.getWidth() / (vpMath::minimum(I_.getWidth(), I_.getHeight()));
2271  v = (double)I_.getHeight() / (vpMath::minimum(I_.getWidth(), I_.getHeight()));
2272  }
2273 
2274  float w44o[4][4], w44cext[4][4], x, y, z;
2275 
2276  vp2jlc_matrix(camMf.inverse(), w44cext);
2277 
2278  add_vwstack("start", "cop", w44cext[3][0], w44cext[3][1], w44cext[3][2]);
2279  x = w44cext[2][0] + w44cext[3][0];
2280  y = w44cext[2][1] + w44cext[3][1];
2281  z = w44cext[2][2] + w44cext[3][2];
2282  add_vwstack("start", "vrp", x, y, z);
2283  add_vwstack("start", "vpn", w44cext[2][0], w44cext[2][1], w44cext[2][2]);
2284  add_vwstack("start", "vup", w44cext[1][0], w44cext[1][1], w44cext[1][2]);
2285  add_vwstack("start", "window", -u, u, -v, v);
2286 
2287  vpHomogeneousMatrix fMit[8];
2288  get_fMi(fMit);
2289 
2290  vp2jlc_matrix(vpHomogeneousMatrix(0, 0, 0, 0, 0, 0), w44o);
2291  display_scene(w44o, robotArms[0], I_, curColor);
2292 
2293  vp2jlc_matrix(fMit[0], w44o);
2294  display_scene(w44o, robotArms[1], I_, curColor);
2295 
2296  vp2jlc_matrix(fMit[1], w44o);
2297  display_scene(w44o, robotArms[2], I_, curColor);
2298 
2299  vp2jlc_matrix(fMit[2], w44o);
2300  display_scene(w44o, robotArms[3], I_, curColor);
2301 
2302  vp2jlc_matrix(fMit[3], w44o);
2303  display_scene(w44o, robotArms[4], I_, curColor);
2304 
2305  vp2jlc_matrix(fMit[6], w44o);
2306  display_scene(w44o, robotArms[5], I_, curColor);
2307 
2308  if (displayCamera) {
2309  vpHomogeneousMatrix cMe;
2310  get_cMe(cMe);
2311  cMe = cMe.inverse();
2312  cMe = fMit[6] * cMe;
2313  vp2jlc_matrix(cMe, w44o);
2314  display_scene(w44o, camera, I_, camColor);
2315  }
2316 
2317  if (displayObject) {
2318  vp2jlc_matrix(fMo, w44o);
2319  display_scene(w44o, scene, I_, curColor);
2320  }
2321  m_mutex_scene.unlock();
2322 }
2323 
2341 {
2342  vpColVector stop(6);
2343  bool status = true;
2344  stop = 0;
2345  set_artVel(stop);
2346  set_velocity(stop);
2347  vpHomogeneousMatrix fMc_;
2348  fMc_ = fMo * cMo_.inverse();
2349 
2350  vpColVector articularCoordinates = get_artCoord();
2351  unsigned int nbSol = getInverseKinematics(fMc_, articularCoordinates, verbose_);
2352 
2353  if (nbSol == 0) {
2354  status = false;
2355  vpERROR_TRACE("Positioning error. Position unreachable");
2356  }
2357 
2358  if (verbose_)
2359  std::cout << "Used joint coordinates (rad): " << articularCoordinates.t() << std::endl;
2360 
2361  set_artCoord(articularCoordinates);
2362 
2363  compute_fMi();
2364 
2365  return status;
2366 }
2367 
2382 {
2383  vpColVector stop(6);
2384  stop = 0;
2385  m_mutex_scene.lock();
2386  set_artVel(stop);
2387  set_velocity(stop);
2388  vpHomogeneousMatrix fMit[8];
2389  get_fMi(fMit);
2390  fMo = fMit[7] * cMo_;
2391  m_mutex_scene.unlock();
2392 }
2393 END_VISP_NAMESPACE
2394 #elif !defined(VISP_BUILD_SHARED_LIBS)
2395 // Work around to avoid warning: libvisp_robot.a(vpSimulatorViper850.cpp.o)
2396 // has no symbols
2397 void dummy_vpSimulatorViper850() { };
2398 #endif
unsigned int getRows() const
Definition: vpArray2D.h:347
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
double sumSquare() const
vpColVector & deg2rad()
Definition: vpColVector.h:380
vpRowVector t() const
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
static const vpColor none
Definition: vpColor.h:229
static const vpColor green
Definition: vpColor.h:220
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void flush(const vpImage< unsigned char > &I)
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ dimensionError
Bad dimension.
Definition: vpException.h:71
void track(const vpHomogeneousMatrix &cMo)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getHeight() const
Definition: vpImage.h:181
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1661
static bool checkDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:396
static std::string getenv(const std::string &env)
Definition: vpIoTools.cpp:326
static double rad(double deg)
Definition: vpMath.h:129
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:254
static Type minimum(const Type &a, const Type &b)
Definition: vpMath.h:262
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
vpMatrix pseudoInverse(double svThreshold=1e-6) const
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
double get_y() const
Get the point y coordinate in the image plane.
Definition: vpPoint.cpp:422
double get_x() const
Get the point x coordinate in the image plane.
Definition: vpPoint.cpp:420
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ positionOutOfRangeError
Position is out of range.
@ lowLevelError
Error thrown by the low level sdk.
double getSamplingTime() const
This class aims to be a basis used to create all the simulators of robots.
void set_velocity(const vpColVector &vel)
static void launcher(vpRobotWireFrameSimulator &simulator)
void set_displayBusy(const bool &status)
vpHomogeneousMatrix getExternalCameraPosition() const
void set_artCoord(const vpColVector &coord)
void setExternalCameraPosition(const vpHomogeneousMatrix &camMf_)
void set_artVel(const vpColVector &vel)
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:155
vpControlFrameType
Definition: vpRobot.h:77
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ MIXT_FRAME
Definition: vpRobot.h:88
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:83
vpControlFrameType getRobotFrame(void) const
Definition: vpRobot.h:183
vpRobotStateType
Definition: vpRobot.h:65
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_ACCELERATION_CONTROL
Initialize the acceleration controller.
Definition: vpRobot.h:69
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:274
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:252
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void computeArticularVelocity() VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setCameraParameters(const vpCameraParameters &cam)
void init() VP_OVERRIDE
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
void getExternalImage(vpImage< vpRGBa > &I)
void get_cMe(vpHomogeneousMatrix &cMe)
void updateArticularPosition() VP_OVERRIDE
void get_cVe(vpVelocityTwistMatrix &cVe)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
void findHighestPositioningSpeed(vpColVector &q)
bool singularityTest(const vpColVector &q, vpMatrix &J)
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) VP_OVERRIDE
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void initArms() VP_OVERRIDE
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
void get_fMi(vpHomogeneousMatrix *fMit) VP_OVERRIDE
int isInJointLimit() VP_OVERRIDE
virtual ~vpSimulatorViper850() VP_OVERRIDE
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
static bool readPosFile(const std::string &filename, vpColVector &q)
void move(const char *filename)
double getPositioningVelocity(void)
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) VP_OVERRIDE
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
Modelization of the ADEPT Viper 850 robot.
Definition: vpViper850.h:95
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition: vpViper850.h:114
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition: vpViper850.h:161
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:129
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper850.h:168
vpToolType getToolType() const
Get the current tool type.
Definition: vpViper850.h:152
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:120
@ TOOL_SCHUNK_GRIPPER_CAMERA
Definition: vpViper850.h:123
@ TOOL_PTGREY_FLEA2_CAMERA
Definition: vpViper850.h:122
@ TOOL_MARLIN_F033C_CAMERA
Definition: vpViper850.h:121
@ TOOL_GENERIC_CAMERA
Definition: vpViper850.h:124
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition: vpViper850.h:113
vpTranslationVector etc
Definition: vpViper.h:158
double d6
for joint 6
Definition: vpViper.h:166
double a3
for joint 3
Definition: vpViper.h:164
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:153
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:921
double d4
for joint 4
Definition: vpViper.h:165
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1158
vpColVector joint_max
Definition: vpViper.h:171
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:568
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:156
double a1
Definition: vpViper.h:162
vpRxyzVector erc
Definition: vpViper.h:159
vpColVector joint_min
Definition: vpViper.h:172
double a2
for joint 2
Definition: vpViper.h:163
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:969
double d1
for joint 1
Definition: vpViper.h:162
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:605
vpHomogeneousMatrix camMf2
vpHomogeneousMatrix f2Mf
void display_scene(Matrix mat, Bound_scene &sc, const vpImage< vpRGBa > &I, const vpColor &color)
vpHomogeneousMatrix fMo
vpHomogeneousMatrix camMf
void setExternalCameraParameters(const vpCameraParameters &cam)
vpHomogeneousMatrix navigation(const vpImage< vpRGBa > &I, bool &changed)
#define vpTRACE
Definition: vpDebug.h:436
#define vpERROR_TRACE
Definition: vpDebug.h:409
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double getMinTimeForUsleepCall()
VISP_EXPORT double measureTimeSecond()
VISP_EXPORT double measureTimeMs()