ViSP  2.10.0
vpViper650.cpp
1 /****************************************************************************
2  *
3  * $Id: vpViper650.cpp 4649 2014-02-07 14:57:11Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2014 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  * Interface for the ADEPT Viper 650 robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
50 #include <visp/vpDebug.h>
51 #include <visp/vpViper650.h>
52 #include <visp/vpMath.h>
53 #include <visp/vpXmlParserCamera.h>
54 
55 #ifdef VISP_HAVE_ACCESS_TO_NAS
56 static const char *opt_viper650[] = {"CAMERA", "eMc_ROT_XYZ","eMc_TRANS_XYZ",
57  NULL};
58 
60 #if defined(_WIN32)
61 = "Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
62 #else
63 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
64 #endif
65 
67 #if defined(_WIN32)
68 = "Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
69 #else
70 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
71 #endif
72 
74 #if defined(_WIN32)
75 = "Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
76 #else
77 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
78 #endif
79 
81 #if defined(_WIN32)
82 = "Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
83 #else
84 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
85 #endif
86 
88 #if defined(_WIN32)
89 = "Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
90 #else
91 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
92 #endif
93 
95 #if defined(_WIN32)
96 = "Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
97 #else
98 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
99 #endif
100 
102 #if defined(_WIN32)
103 = "Z:/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
104 #else
105 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
106 #endif
107 
109 #if defined(_WIN32)
110 = "Z:/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
111 #else
112 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
113 #endif
114 
115 
116 const char * const vpViper650::CONST_CAMERA_FILENAME
117 #if defined(_WIN32)
118 = "Z:/robot/Viper650/current/include/const_camera_Viper650.xml";
119 #else
120 = "/udd/fspindle/robot/Viper650/current/include/const_camera_Viper650.xml";
121 #endif
122 
123 
124 #endif // VISP_HAVE_ACCESS_TO_NAS
125 
126 const char * const vpViper650::CONST_MARLIN_F033C_CAMERA_NAME = "Marlin-F033C-12mm";
127 const char * const vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME = "PTGrey-Flea2-6mm";
128 const char * const vpViper650::CONST_SCHUNK_GRIPPER_CAMERA_NAME = "Schunk-Gripper-PTGrey-Flea2-6mm";
129 const char * const vpViper650::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
130 
132 
133 
134 
142  : tool_current(vpViper650::defaultTool), projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
143 {
144  // Denavit Hartenberg parameters
145  a1 = 0.075;
146  a2 = 0.270;
147  a3 = 0.090;
148  d1 = 0.335;
149  d4 = 0.295;
150  d6 = 0.080 + 0.1016; // To take into account the offset to go to the tool changer
151  c56 = -341.33 / 9102.22;
152 
153  // Software joint limits in radians
154  joint_min[0] = vpMath::rad(-170);
155  joint_min[1] = vpMath::rad(-190);
156  joint_min[2] = vpMath::rad(-29);
157  joint_min[3] = vpMath::rad(-190);
158  joint_min[4] = vpMath::rad(-120);
159  joint_min[5] = vpMath::rad(-360);
160  joint_max[0] = vpMath::rad(170);
161  joint_max[1] = vpMath::rad(45);
162  joint_max[2] = vpMath::rad(256);
163  joint_max[3] = vpMath::rad(190);
164  joint_max[4] = vpMath::rad(120);
165  joint_max[5] = vpMath::rad(360);
166 
167  init(); // Set the default tool
168 }
169 
174 void
176 {
178  return;
179 }
180 
193 #ifdef VISP_HAVE_ACCESS_TO_NAS
194 void
195 vpViper650::init (const char *camera_extrinsic_parameters)
196 {
197  //vpTRACE ("Parse camera file \""%s\"".", camera_filename);
198  this->parseConfigFile (camera_extrinsic_parameters);
199 
200  return ;
201 }
202 #endif
203 
216 void
219 {
220 
221  this->projModel = proj_model;
222 
223 #ifdef VISP_HAVE_ACCESS_TO_NAS
224  // Read the robot parameters from files
225  char filename_eMc [FILENAME_MAX];
226  switch (tool) {
228  switch(projModel) {
230 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
231  snprintf(filename_eMc, FILENAME_MAX, "%s",
233 #else // _WIN32
234  _snprintf(filename_eMc, FILENAME_MAX, "%s",
236 #endif
237  break;
239 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
240  snprintf(filename_eMc, FILENAME_MAX, "%s",
242 #else // _WIN32
243  _snprintf(filename_eMc, FILENAME_MAX, "%s",
245 #endif
246  break;
247  }
248  break;
249  }
251  switch(projModel) {
253 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
254  snprintf(filename_eMc, FILENAME_MAX, "%s",
256 #else // _WIN32
257  _snprintf(filename_eMc, FILENAME_MAX, "%s",
259 #endif
260  break;
262 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
263  snprintf(filename_eMc, FILENAME_MAX, "%s",
265 #else // _WIN32
266  _snprintf(filename_eMc, FILENAME_MAX, "%s",
268 #endif
269  break;
270  }
271  break;
272  }
274  switch(projModel) {
276 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
277  snprintf(filename_eMc, FILENAME_MAX, "%s",
279 #else // _WIN32
280  _snprintf(filename_eMc, FILENAME_MAX, "%s",
282 #endif
283  break;
285 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
286  snprintf(filename_eMc, FILENAME_MAX, "%s",
288 #else // _WIN32
289  _snprintf(filename_eMc, FILENAME_MAX, "%s",
291 #endif
292  break;
293  }
294  break;
295  }
297  switch(projModel) {
299 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
300  snprintf(filename_eMc, FILENAME_MAX, "%s",
302 #else // _WIN32
303  _snprintf(filename_eMc, FILENAME_MAX, "%s",
305 #endif
306  break;
308 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
309  snprintf(filename_eMc, FILENAME_MAX, "%s",
311 #else // _WIN32
312  _snprintf(filename_eMc, FILENAME_MAX, "%s",
314 #endif
315  break;
316  }
317  break;
318  }
319  default: {
320  vpERROR_TRACE ("This error should not occur!");
321  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
322  // "que les specs de la classe ont ete modifiee, "
323  // "et que le code n'a pas ete mis a jour "
324  // "correctement.");
325  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
326  // "vpViper650::vpViper650ToolType, et controlez que "
327  // "tous les cas ont ete pris en compte dans la "
328  // "fonction init(camera).");
329  break;
330  }
331  }
332 
333  this->init (filename_eMc);
334 
335 #else // VISP_HAVE_ACCESS_TO_NAS
336 
337  // Use here default values of the robot constant parameters.
338  switch (tool) {
340  switch(projModel) {
342  erc[0] = vpMath::rad(0.07); // rx
343  erc[1] = vpMath::rad(2.76); // ry
344  erc[2] = vpMath::rad(-91.50); // rz
345  etc[0] = -0.0453; // tx
346  etc[1] = 0.0005; // ty
347  etc[2] = 0.0728; // tz
348  break;
350  erc[0] = vpMath::rad(0.26); // rx
351  erc[1] = vpMath::rad(2.12); // ry
352  erc[2] = vpMath::rad(-91.31); // rz
353  etc[0] = -0.0444; // tx
354  etc[1] = -0.0005; // ty
355  etc[2] = 0.1022; // tz
356  break;
357  }
358  break;
359  }
362  switch(projModel) {
364  erc[0] = vpMath::rad(0.15); // rx
365  erc[1] = vpMath::rad(1.28); // ry
366  erc[2] = vpMath::rad(-90.8); // rz
367  etc[0] = -0.0456; // tx
368  etc[1] = -0.0013; // ty
369  etc[2] = 0.001; // tz
370  break;
372  erc[0] = vpMath::rad(0.72); // rx
373  erc[1] = vpMath::rad(2.10); // ry
374  erc[2] = vpMath::rad(-90.5); // rz
375  etc[0] = -0.0444; // tx
376  etc[1] = -0.0012; // ty
377  etc[2] = 0.078; // tz
378  break;
379  }
380  break;
381  }
383  // Set eMc to identity
384  switch(projModel) {
387  erc[0] = 0; // rx
388  erc[1] = 0; // ry
389  erc[2] = 0; // rz
390  etc[0] = 0; // tx
391  etc[1] = 0; // ty
392  etc[2] = 0; // tz
393  break;
394  }
395  break;
396  }
397  }
398  vpRotationMatrix eRc(erc);
399  this->eMc.buildFrom(etc, eRc);
400 #endif // VISP_HAVE_ACCESS_TO_NAS
401 
402  setToolType(tool);
403  return ;
404 }
405 
417 #ifdef VISP_HAVE_ACCESS_TO_NAS
418 void
419 vpViper650::parseConfigFile (const char * filename)
420 {
421  size_t dim;
422  int code;
423  char Ligne[FILENAME_MAX];
424  char namoption[100];
425  FILE * fdtask;
426  int numLn = 0;
427  double rot_eMc[3]; // rotation
428  double trans_eMc[3]; // translation
429  bool get_rot_eMc = false;
430  bool get_trans_eMc = false;
431 
432  //vpTRACE("Read the config file for constant parameters %s.", filename);
433  if ((fdtask = fopen(filename, "r" )) == NULL)
434  {
435  vpERROR_TRACE ("Impossible to read the config file %s.",
436  filename);
438  "Impossible to read the config file.");
439  }
440 
441  while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
442  numLn ++;
443  if ('#' == Ligne[0]) { continue; }
444  sscanf(Ligne, "%s", namoption);
445  dim = strlen(namoption);
446 
447  for (code = 0;
448  NULL != opt_viper650[code];
449  ++ code)
450  {
451  if (strncmp(opt_viper650[code], namoption, dim) == 0)
452  {
453  break;
454  }
455  }
456 
457  switch(code) {
458  case 0:
459  break; // Nothing to do: camera name
460 
461  case 1:
462  sscanf(Ligne, "%s %lf %lf %lf", namoption,
463  &rot_eMc[0],
464  &rot_eMc[1],
465  &rot_eMc[2]);
466 
467  // Convert rotation from degrees to radians
468  rot_eMc[0] *= M_PI / 180.0;
469  rot_eMc[1] *= M_PI / 180.0;
470  rot_eMc[2] *= M_PI / 180.0;
471  get_rot_eMc = true;
472  break;
473 
474  case 2:
475  sscanf(Ligne, "%s %lf %lf %lf", namoption,
476  &trans_eMc[0],
477  &trans_eMc[1],
478  &trans_eMc[2]);
479  get_trans_eMc = true;
480  break;
481 
482  default:
483  vpERROR_TRACE ("Bad configuration file %s "
484  "ligne #%d.", filename, numLn);
485  } /* SWITCH */
486  } /* WHILE */
487 
488  fclose (fdtask);
489 
490  // Compute the eMc matrix from the translations and rotations
491  if (get_rot_eMc && get_trans_eMc) {
492  for (unsigned int i=0; i < 3; i ++) {
493  erc[i] = rot_eMc[i];
494  etc[i] = trans_eMc[i];
495  }
496 
497  vpRotationMatrix eRc(erc);
498  this->eMc.buildFrom(etc, eRc);
499  }
500 
501  return;
502 }
503 #endif
504 
505 
578 void
580  const unsigned int &image_width,
581  const unsigned int &image_height) const
582 {
583 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
584  vpXmlParserCamera parser;
585  switch (getToolType()) {
587  std::cout << "Get camera parameters for camera \""
588  << vpViper650::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl
589  << "from the XML file: \""
590  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
591  if (parser.parse(cam,
594  projModel,
595  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
597  "Impossible to read the camera parameters.");
598  }
599  break;
600  }
602  std::cout << "Get camera parameters for camera \""
603  << vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl
604  << "from the XML file: \""
605  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
606  if (parser.parse(cam,
609  projModel,
610  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
612  "Impossible to read the camera parameters.");
613  }
614  break;
615  }
617  std::cout << "Get camera parameters for camera \""
618  << vpViper650::CONST_SCHUNK_GRIPPER_CAMERA_NAME << "\"" << std::endl
619  << "from the XML file: \""
620  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
621  if (parser.parse(cam,
624  projModel,
625  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
627  "Impossible to read the camera parameters.");
628  }
629  break;
630  }
632  std::cout << "Get camera parameters for camera \""
633  << vpViper650::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
634  << "from the XML file: \""
635  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
636  if (parser.parse(cam,
639  projModel,
640  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
642  "Impossible to read the camera parameters.");
643  }
644  break;
645  }
646  default: {
647  vpERROR_TRACE ("This error should not occur!");
648  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
649  // "que les specs de la classe ont ete modifiee, "
650  // "et que le code n'a pas ete mis a jour "
651  // "correctement.");
652  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
653  // "vpViper650::vpViper650ToolType, et controlez que "
654  // "tous les cas ont ete pris en compte dans la "
655  // "fonction init(camera).");
657  "Impossible to read the camera parameters.");
658  break;
659  }
660  }
661 #else
662  // Set default parameters
663  switch (getToolType()) {
665  // Set default intrinsic camera parameters for 640x480 images
666  if (image_width == 640 && image_height == 480) {
667  std::cout << "Get default camera parameters for camera \""
668  << vpViper650::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl;
669  switch(this->projModel) {
671  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 317.7, 253.9);
672  break;
674  cam.initPersProjWithDistortion(1214.0, 1213.0, 323.1, 240.0, -0.1824, 0.1881);
675  break;
676  }
677  }
678  else {
679  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
681  "Impossible to read the camera parameters.");
682  }
683  break;
684  }
687  // Set default intrinsic camera parameters for 640x480 images
688  if (image_width == 640 && image_height == 480) {
689  std::cout << "Get default camera parameters for camera \""
690  << vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl;
691  switch(this->projModel) {
693  cam.initPersProjWithoutDistortion(868.0, 869.0, 314.8, 254.1);
694  break;
696  cam.initPersProjWithDistortion(831.3, 831.6, 322.7, 265.8, -0.1955, 0.2047);
697  break;
698  }
699  }
700  else {
701  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
703  "Impossible to read the camera parameters.");
704  }
705  break;
706  }
708  // Set default intrinsic camera parameters for 640x480 images
709  if (image_width == 640 && image_height == 480) {
710  std::cout << "Get default camera parameters for camera \""
711  << vpViper650::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl;
712  switch(this->projModel) {
714  cam.initPersProjWithoutDistortion(868.0, 869.0, 314.8, 254.1);
715  break;
717  cam.initPersProjWithDistortion(831.3, 831.6, 322.7, 265.8, -0.1955, 0.2047);
718  break;
719  }
720  }
721  else {
722  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
724  "Impossible to read the camera parameters.");
725  }
726  break;
727  }
728  default:
729  vpERROR_TRACE ("This error should not occur!");
731  "Impossible to read the camera parameters.");
732  break;
733  }
734 #endif
735  return;
736 }
737 
801 void
803  const vpImage<unsigned char> &I) const
804 {
806 }
871 void
873  const vpImage<vpRGBa> &I) const
874 {
876 }
double a3
for joint 3
Definition: vpViper.h:154
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:146
Error that can be emited by the vpRobot class and its derivates.
Perspective projection without distortion model.
unsigned int getWidth() const
Definition: vpImage.h:161
#define vpERROR_TRACE
Definition: vpDebug.h:395
#define vpTRACE
Definition: vpDebug.h:418
static const char *const CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:73
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper650.h:144
static const char *const CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:75
static const char *const CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:79
vpToolType getToolType() const
Get the current tool type.
Definition: vpViper650.h:126
vpRxyzVector erc
Definition: vpViper.h:149
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:77
XML parser to load and save intrinsic camera parameters.
double a2
for joint 2
Definition: vpViper.h:153
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpViper650.cpp:579
The vpRotationMatrix considers the particular case of a rotation matrix.
double d1
for joint 1
Definition: vpViper.h:152
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:157
double a1
Definition: vpViper.h:152
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:99
static const char *const CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:74
vpTranslationVector etc
Definition: vpViper.h:148
vpColVector joint_max
Definition: vpViper.h:160
Generic class defining intrinsic camera parameters.
Modelisation of the ADEPT Viper 650 robot.
Definition: vpViper650.h:66
static const char *const CONST_CAMERA_FILENAME
Definition: vpViper650.h:80
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition: vpViper650.h:85
void init(void)
Definition: vpViper650.cpp:175
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:91
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition: vpViper650.h:86
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Construction from translation vector and rotation matrix.
static double rad(double deg)
Definition: vpMath.h:100
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
Definition: vpViper650.h:87
static const char *const CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:72
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:76
void parseConfigFile(const char *filename)
Definition: vpViper650.cpp:419
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:78
unsigned int getHeight() const
Definition: vpImage.h:152
double d4
for joint 4
Definition: vpViper.h:155
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, const unsigned int image_width=0, const unsigned int image_height=0)
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
Definition: vpViper650.h:136
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpViper650.h:88
void initPersProjWithDistortion(const double px, const double py, const double u0, const double v0, const double kud, const double kdu)
double d6
for joint 6
Definition: vpViper.h:156
vpColVector joint_min
Definition: vpViper.h:161