Visual Servoing Platform  version 3.0.0
vpViper650.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the ADEPT Viper 650 robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
46 #include <visp3/core/vpDebug.h>
47 #include <visp3/robot/vpViper650.h>
48 #include <visp3/core/vpMath.h>
49 #include <visp3/core/vpXmlParserCamera.h>
50 
51 static const char *opt_viper650[] = {"CAMERA", "eMc_ROT_XYZ","eMc_TRANS_XYZ",
52  NULL};
53 
54 #ifdef VISP_HAVE_ACCESS_TO_NAS
56 #if defined(_WIN32)
57 = "Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
58 #else
59 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
60 #endif
61 
63 #if defined(_WIN32)
64 = "Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
65 #else
66 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
67 #endif
68 
70 #if defined(_WIN32)
71 = "Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
72 #else
73 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
74 #endif
75 
77 #if defined(_WIN32)
78 = "Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
79 #else
80 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
81 #endif
82 
84 #if defined(_WIN32)
85 = "Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
86 #else
87 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
88 #endif
89 
91 #if defined(_WIN32)
92 = "Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
93 #else
94 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
95 #endif
96 
98 #if defined(_WIN32)
99 = "Z:/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
100 #else
101 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
102 #endif
103 
105 #if defined(_WIN32)
106 = "Z:/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
107 #else
108 = "/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
109 #endif
110 
111 
112 const char * const vpViper650::CONST_CAMERA_FILENAME
113 #if defined(_WIN32)
114 = "Z:/robot/Viper650/current/include/const_camera_Viper650.xml";
115 #else
116 = "/udd/fspindle/robot/Viper650/current/include/const_camera_Viper650.xml";
117 #endif
118 
119 
120 #endif // VISP_HAVE_ACCESS_TO_NAS
121 
122 const char * const vpViper650::CONST_MARLIN_F033C_CAMERA_NAME = "Marlin-F033C-12mm";
123 const char * const vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME = "PTGrey-Flea2-6mm";
124 const char * const vpViper650::CONST_SCHUNK_GRIPPER_CAMERA_NAME = "Schunk-Gripper-PTGrey-Flea2-6mm";
125 const char * const vpViper650::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
126 
128 
129 
130 
138  : tool_current(vpViper650::defaultTool), projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
139 {
140  // Denavit Hartenberg parameters
141  a1 = 0.075;
142  a2 = 0.270;
143  a3 = 0.090;
144  d1 = 0.335;
145  d4 = 0.295;
146  d6 = 0.080 + 0.1016; // To take into account the offset to go to the tool changer
147  c56 = -341.33 / 9102.22;
148 
149  // Software joint limits in radians
150  joint_min[0] = vpMath::rad(-170);
151  joint_min[1] = vpMath::rad(-190);
152  joint_min[2] = vpMath::rad(-29);
153  joint_min[3] = vpMath::rad(-190);
154  joint_min[4] = vpMath::rad(-120);
155  joint_min[5] = vpMath::rad(-360);
156  joint_max[0] = vpMath::rad(170);
157  joint_max[1] = vpMath::rad(45);
158  joint_max[2] = vpMath::rad(256);
159  joint_max[3] = vpMath::rad(190);
160  joint_max[4] = vpMath::rad(120);
161  joint_max[5] = vpMath::rad(360);
162 
163  init(); // Set the default tool
164 }
165 
170 void
172 {
174  return;
175 }
176 
186 #ifdef VISP_HAVE_ACCESS_TO_NAS
187 void
188 vpViper650::init (const char *camera_extrinsic_parameters)
189 {
190  //vpTRACE ("Parse camera file \""%s\"".", camera_filename);
191  this->parseConfigFile (camera_extrinsic_parameters);
192 
193  return ;
194 }
195 #endif
196 
218 void
221 {
222 
223  this->projModel = proj_model;
224 
225 #ifdef VISP_HAVE_ACCESS_TO_NAS
226  // Read the robot parameters from files
227  char filename_eMc [FILENAME_MAX];
228  switch (tool) {
230  switch(projModel) {
232 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
233  snprintf(filename_eMc, FILENAME_MAX, "%s",
235 #else // _WIN32
236  _snprintf(filename_eMc, FILENAME_MAX, "%s",
238 #endif
239  break;
241 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
242  snprintf(filename_eMc, FILENAME_MAX, "%s",
244 #else // _WIN32
245  _snprintf(filename_eMc, FILENAME_MAX, "%s",
247 #endif
248  break;
249  }
250  break;
251  }
253  switch(projModel) {
255 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
256  snprintf(filename_eMc, FILENAME_MAX, "%s",
258 #else // _WIN32
259  _snprintf(filename_eMc, FILENAME_MAX, "%s",
261 #endif
262  break;
264 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
265  snprintf(filename_eMc, FILENAME_MAX, "%s",
267 #else // _WIN32
268  _snprintf(filename_eMc, FILENAME_MAX, "%s",
270 #endif
271  break;
272  }
273  break;
274  }
276  switch(projModel) {
278 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
279  snprintf(filename_eMc, FILENAME_MAX, "%s",
281 #else // _WIN32
282  _snprintf(filename_eMc, FILENAME_MAX, "%s",
284 #endif
285  break;
287 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
288  snprintf(filename_eMc, FILENAME_MAX, "%s",
290 #else // _WIN32
291  _snprintf(filename_eMc, FILENAME_MAX, "%s",
293 #endif
294  break;
295  }
296  break;
297  }
299  switch(projModel) {
301 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
302  snprintf(filename_eMc, FILENAME_MAX, "%s",
304 #else // _WIN32
305  _snprintf(filename_eMc, FILENAME_MAX, "%s",
307 #endif
308  break;
310 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
311  snprintf(filename_eMc, FILENAME_MAX, "%s",
313 #else // _WIN32
314  _snprintf(filename_eMc, FILENAME_MAX, "%s",
316 #endif
317  break;
318  }
319  break;
320  }
322  vpERROR_TRACE ("No predefined file available for a custom tool"
323  "You should use init(vpViper650::vpToolType, const std::string&) or"
324  "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
325  throw vpRobotException (vpRobotException::badValue, "No predefined file available for a custom tool");
326  break;
327  }
328  default: {
329  vpERROR_TRACE ("This error should not occur!");
330  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
331  // "que les specs de la classe ont ete modifiee, "
332  // "et que le code n'a pas ete mis a jour "
333  // "correctement.");
334  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
335  // "vpViper650::vpViper650ToolType, et controlez que "
336  // "tous les cas ont ete pris en compte dans la "
337  // "fonction init(camera).");
338  break;
339  }
340  }
341 
342  this->init (filename_eMc);
343 
344 #else // VISP_HAVE_ACCESS_TO_NAS
345 
346  // Use here default values of the robot constant parameters.
347  switch (tool) {
349  switch(projModel) {
351  erc[0] = vpMath::rad(0.07); // rx
352  erc[1] = vpMath::rad(2.76); // ry
353  erc[2] = vpMath::rad(-91.50); // rz
354  etc[0] = -0.0453; // tx
355  etc[1] = 0.0005; // ty
356  etc[2] = 0.0728; // tz
357  break;
359  erc[0] = vpMath::rad(0.26); // rx
360  erc[1] = vpMath::rad(2.12); // ry
361  erc[2] = vpMath::rad(-91.31); // rz
362  etc[0] = -0.0444; // tx
363  etc[1] = -0.0005; // ty
364  etc[2] = 0.1022; // tz
365  break;
366  }
367  break;
368  }
371  switch(projModel) {
373  erc[0] = vpMath::rad(0.15); // rx
374  erc[1] = vpMath::rad(1.28); // ry
375  erc[2] = vpMath::rad(-90.8); // rz
376  etc[0] = -0.0456; // tx
377  etc[1] = -0.0013; // ty
378  etc[2] = 0.001; // tz
379  break;
381  erc[0] = vpMath::rad(0.72); // rx
382  erc[1] = vpMath::rad(2.10); // ry
383  erc[2] = vpMath::rad(-90.5); // rz
384  etc[0] = -0.0444; // tx
385  etc[1] = -0.0012; // ty
386  etc[2] = 0.078; // tz
387  break;
388  }
389  break;
390  }
392  // Set eMc to identity
393  switch(projModel) {
396  erc[0] = 0; // rx
397  erc[1] = 0; // ry
398  erc[2] = 0; // rz
399  etc[0] = 0; // tx
400  etc[1] = 0; // ty
401  etc[2] = 0; // tz
402  break;
403  }
404  break;
405  }
407  vpERROR_TRACE ("No predefined parameters available for a custom tool"
408  "You should use init(vpViper650::vpToolType, const std::string&) or"
409  "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
410  throw vpRobotException (vpRobotException::badValue, "No predefined parameters available for a custom tool");
411  break;
412  }
413  }
414  vpRotationMatrix eRc(erc);
415  this->eMc.buildFrom(etc, eRc);
416 #endif // VISP_HAVE_ACCESS_TO_NAS
417 
418  setToolType(tool);
419  return ;
420 }
421 
452 void
454  const std::string &filename)
455 {
456  this->setToolType(tool);
457  this->parseConfigFile(filename.c_str());
458 }
459 
475 void
477  const vpHomogeneousMatrix &eMc_)
478 {
479  this->setToolType(tool);
480  this->set_eMc(eMc_);
481 }
482 
491 void
492 vpViper650::parseConfigFile (const char * filename)
493 {
494  size_t dim;
495  int code;
496  char Ligne[FILENAME_MAX];
497  char namoption[100];
498  FILE * fdtask;
499  int numLn = 0;
500  vpRxyzVector rot_eMc; // rotation
501  vpTranslationVector trans_eMc; // translation
502  bool get_rot_eMc = false;
503  bool get_trans_eMc = false;
504 
505  //vpTRACE("Read the config file for constant parameters %s.", filename);
506  if ((fdtask = fopen(filename, "r" )) == NULL)
507  {
508  vpERROR_TRACE ("Impossible to read the config file %s.",
509  filename);
511  "Impossible to read the config file.");
512  }
513 
514  while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
515  numLn ++;
516  if ('#' == Ligne[0]) { continue; }
517  if (sscanf(Ligne, "%s", namoption) != 1) {
518  fclose (fdtask);
520  "Cannot parse configuration file %s to retrieve option name"));
521  }
522 
523  dim = strlen(namoption);
524 
525  for (code = 0;
526  NULL != opt_viper650[code];
527  ++ code)
528  {
529  if (strncmp(opt_viper650[code], namoption, dim) == 0)
530  {
531  break;
532  }
533  }
534 
535  switch(code) {
536  case 0:
537  break; // Nothing to do: camera name
538 
539  case 1:
540  if (sscanf(Ligne, "%s %lf %lf %lf", namoption,
541  &rot_eMc[0], &rot_eMc[1], &rot_eMc[2]) != 4) {
542  fclose (fdtask);
544  "Cannot parse configuration file %s to retrieve translation"));
545  }
546 
547  // Convert rotation from degrees to radians
548  rot_eMc[0] *= M_PI / 180.0;
549  rot_eMc[1] *= M_PI / 180.0;
550  rot_eMc[2] *= M_PI / 180.0;
551  get_rot_eMc = true;
552  break;
553 
554  case 2:
555  if (sscanf(Ligne, "%s %lf %lf %lf", namoption,
556  &trans_eMc[0], &trans_eMc[1], &trans_eMc[2]) != 4) {
557  fclose (fdtask);
559  "Cannot parse configuration file %s to retrieve rotation"));
560  }
561  get_trans_eMc = true;
562  break;
563 
564  default:
565  vpERROR_TRACE ("Bad configuration file %s "
566  "ligne #%d.", filename, numLn);
567  } /* SWITCH */
568  } /* WHILE */
569 
570  fclose (fdtask);
571 
572  // Compute the eMc matrix from the translations and rotations
573  if (get_rot_eMc && get_trans_eMc) {
574  this->set_eMc(trans_eMc,rot_eMc);
575  }
576  else {
577  vpERROR_TRACE ("Could not read translation and rotation parameters from config file %s.",
578  filename);
580  "Could not read translation and rotation parameters from config file ");
581  }
582 
583  return;
584 }
585 
586 
659 void
661  const unsigned int &image_width,
662  const unsigned int &image_height) const
663 {
664 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
665  vpXmlParserCamera parser;
666  switch (getToolType()) {
668  std::cout << "Get camera parameters for camera \""
669  << vpViper650::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl
670  << "from the XML file: \""
671  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
672  if (parser.parse(cam,
675  projModel,
676  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
678  "Impossible to read the camera parameters.");
679  }
680  break;
681  }
683  std::cout << "Get camera parameters for camera \""
684  << vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl
685  << "from the XML file: \""
686  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
687  if (parser.parse(cam,
690  projModel,
691  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
693  "Impossible to read the camera parameters.");
694  }
695  break;
696  }
698  std::cout << "Get camera parameters for camera \""
699  << vpViper650::CONST_SCHUNK_GRIPPER_CAMERA_NAME << "\"" << std::endl
700  << "from the XML file: \""
701  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
702  if (parser.parse(cam,
705  projModel,
706  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
708  "Impossible to read the camera parameters.");
709  }
710  break;
711  }
713  std::cout << "Get camera parameters for camera \""
714  << vpViper650::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
715  << "from the XML file: \""
716  << vpViper650::CONST_CAMERA_FILENAME << "\""<< std::endl;
717  if (parser.parse(cam,
720  projModel,
721  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
723  "Impossible to read the camera parameters.");
724  }
725  break;
726  }
728  vpERROR_TRACE ("No intrinsic parameters available for a custom tool");
729  throw vpRobotException (vpRobotException::badValue, "No intrinsic parameters available for a custom tool");
730  break;
731  }
732  default: {
733  vpERROR_TRACE ("This error should not occur!");
734  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
735  // "que les specs de la classe ont ete modifiee, "
736  // "et que le code n'a pas ete mis a jour "
737  // "correctement.");
738  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
739  // "vpViper650::vpViper650ToolType, et controlez que "
740  // "tous les cas ont ete pris en compte dans la "
741  // "fonction init(camera).");
743  "Impossible to read the camera parameters.");
744  break;
745  }
746  }
747 #else
748  // Set default parameters
749  switch (getToolType()) {
751  // Set default intrinsic camera parameters for 640x480 images
752  if (image_width == 640 && image_height == 480) {
753  std::cout << "Get default camera parameters for camera \""
754  << vpViper650::CONST_MARLIN_F033C_CAMERA_NAME << "\"" << std::endl;
755  switch(this->projModel) {
757  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 317.7, 253.9);
758  break;
760  cam.initPersProjWithDistortion(1214.0, 1213.0, 323.1, 240.0, -0.1824, 0.1881);
761  break;
762  }
763  }
764  else {
765  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
767  "Impossible to read the camera parameters.");
768  }
769  break;
770  }
773  // Set default intrinsic camera parameters for 640x480 images
774  if (image_width == 640 && image_height == 480) {
775  std::cout << "Get default camera parameters for camera \""
776  << vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" << std::endl;
777  switch(this->projModel) {
779  cam.initPersProjWithoutDistortion(868.0, 869.0, 314.8, 254.1);
780  break;
782  cam.initPersProjWithDistortion(831.3, 831.6, 322.7, 265.8, -0.1955, 0.2047);
783  break;
784  }
785  }
786  else {
787  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
789  "Impossible to read the camera parameters.");
790  }
791  break;
792  }
794  // Set default intrinsic camera parameters for 640x480 images
795  if (image_width == 640 && image_height == 480) {
796  std::cout << "Get default camera parameters for camera \""
797  << vpViper650::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl;
798  switch(this->projModel) {
800  cam.initPersProjWithoutDistortion(868.0, 869.0, 314.8, 254.1);
801  break;
803  cam.initPersProjWithDistortion(831.3, 831.6, 322.7, 265.8, -0.1955, 0.2047);
804  break;
805  }
806  }
807  else {
808  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
810  "Impossible to read the camera parameters.");
811  }
812  break;
813  }
815  vpERROR_TRACE ("No intrinsic parameters available for a custom tool");
816  throw vpRobotException (vpRobotException::badValue, "No intrinsic parameters available for a custom tool");
817  break;
818  }
819  default:
820  vpERROR_TRACE ("This error should not occur!");
822  "Impossible to read the camera parameters.");
823  break;
824  }
825 #endif
826  return;
827 }
828 
892 void
894  const vpImage<unsigned char> &I) const
895 {
897 }
962 void
964  const vpImage<vpRGBa> &I) const
965 {
967 }
double a3
for joint 3
Definition: vpViper.h:153
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:145
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
Implementation of an homogeneous matrix and operations on such kind of matrices.
#define vpERROR_TRACE
Definition: vpDebug.h:391
static const char *const CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:69
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper650.h:143
static const char *const CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:71
static const char *const CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:75
error that can be emited by ViSP classes.
Definition: vpException.h:73
vpToolType getToolType() const
Get the current tool type.
Definition: vpViper650.h:127
vpRxyzVector erc
Definition: vpViper.h:148
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:73
XML parser to load and save intrinsic camera parameters.
double a2
for joint 2
Definition: vpViper.h:152
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpViper650.cpp:660
Implementation of a rotation matrix and operations on such kind of matrices.
double d1
for joint 1
Definition: vpViper.h:151
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:156
double a1
Definition: vpViper.h:151
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:96
static const char *const CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:70
vpTranslationVector etc
Definition: vpViper.h:147
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1258
#define vpTRACE
Definition: vpDebug.h:414
vpColVector joint_max
Definition: vpViper.h:159
Generic class defining intrinsic camera parameters.
Modelisation of the ADEPT Viper 650 robot.
Definition: vpViper650.h:62
static const char *const CONST_CAMERA_FILENAME
Definition: vpViper650.h:76
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition: vpViper650.h:81
void init(void)
Definition: vpViper650.cpp:171
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:87
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition: vpViper650.h:82
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
Definition: vpMath.h:104
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
Definition: vpViper650.h:83
static const char *const CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:68
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:72
void parseConfigFile(const char *filename)
Definition: vpViper650.cpp:492
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:74
unsigned int getHeight() const
Definition: vpImage.h:152
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
double d4
for joint 4
Definition: vpViper.h:154
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:135
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpViper650.h:84
Class that consider the case of a translation vector.
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:155
vpColVector joint_min
Definition: vpViper.h:160