Visual Servoing Platform  version 3.6.1 under development (2024-11-14)
vpViper650.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  * Interface for the ADEPT Viper 650 robot.
33  *
34 *****************************************************************************/
35 
44 #include <visp3/core/vpDebug.h>
45 #include <visp3/core/vpMath.h>
46 #include <visp3/core/vpXmlParserCamera.h>
47 #include <visp3/robot/vpViper650.h>
48 
49 static const char *opt_viper650[] = { "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr };
50 
51 BEGIN_VISP_NAMESPACE
52 #ifdef VISP_HAVE_VIPER650_DATA
54 std::string(VISP_VIPER650_DATA_PATH) +
55 std::string("/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf");
56 
58 std::string(VISP_VIPER650_DATA_PATH) + std::string("/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf");
59 
61 std::string(VISP_VIPER650_DATA_PATH) +
62 std::string("/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf");
63 
65 std::string(VISP_VIPER650_DATA_PATH) + std::string("/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf");
66 
68 std::string(VISP_VIPER650_DATA_PATH) + std::string("/include/"
69  "const_eMc_schunk_gripper_without_distortion_Viper650."
70  "cnf");
71 
73 std::string(VISP_VIPER650_DATA_PATH) +
74 std::string("/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf");
75 
77 std::string(VISP_VIPER650_DATA_PATH) + std::string("/include/const_eMc_generic_without_distortion_Viper650.cnf");
78 
80 std::string(VISP_VIPER650_DATA_PATH) + std::string("/include/const_eMc_generic_with_distortion_Viper650.cnf");
81 
82 const std::string vpViper650::CONST_CAMERA_FILENAME =
83 std::string(VISP_VIPER650_DATA_PATH) + std::string("/include/const_camera_Viper650.xml");
84 
85 #endif // VISP_HAVE_VIPER650_DATA
86 
87 const char *const vpViper650::CONST_MARLIN_F033C_CAMERA_NAME = "Marlin-F033C-12mm";
88 const char *const vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME = "PTGrey-Flea2-6mm";
89 const char *const vpViper650::CONST_SCHUNK_GRIPPER_CAMERA_NAME = "Schunk-Gripper-PTGrey-Flea2-6mm";
90 const char *const vpViper650::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
91 
93 
101  : tool_current(vpViper650::defaultTool), projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
102 {
103  // Denavit-Hartenberg parameters
104  a1 = 0.075;
105  a2 = 0.270;
106  a3 = 0.090;
107  d1 = 0.335;
108  d4 = 0.295;
109  d6 = 0.080 + 0.1016; // To take into account the offset to go to the tool changer
110  c56 = -341.33 / 9102.22;
111 
112  // Software joint limits in radians
113  joint_min[0] = vpMath::rad(-170);
114  joint_min[1] = vpMath::rad(-190);
115  joint_min[2] = vpMath::rad(-29);
116  joint_min[3] = vpMath::rad(-190);
117  joint_min[4] = vpMath::rad(-120);
118  joint_min[5] = vpMath::rad(-360);
119  joint_max[0] = vpMath::rad(170);
120  joint_max[1] = vpMath::rad(45);
121  joint_max[2] = vpMath::rad(256);
122  joint_max[3] = vpMath::rad(190);
123  joint_max[4] = vpMath::rad(120);
124  joint_max[5] = vpMath::rad(360);
125 
126  init(); // Set the default tool
127 }
128 
134 {
136  return;
137 }
138 
148 void vpViper650::init(const std::string &camera_extrinsic_parameters)
149 {
150  // vpTRACE ("Parse camera file \""%s\"".", camera_filename);
151  this->parseConfigFile(camera_extrinsic_parameters);
152 
153  return;
154 }
155 
178 {
179 
180  this->projModel = proj_model;
181 
182 #ifdef VISP_HAVE_VIPER650_DATA
183  // Read the robot parameters from files
184  std::string filename_eMc;
185  switch (tool) {
187  switch (projModel) {
190  break;
193  break;
196  "Feature TOOL_MARLIN_F033C_CAMERA is not implemented for Kannala-Brandt projection model yet.");
197  break;
198  }
199  break;
200  }
202  switch (projModel) {
205  break;
208  break;
211  "Feature TOOL_PTGREY_FLEA2_CAMERA is not implemented for Kannala-Brandt projection model yet.");
212  break;
213  }
214  break;
215  }
217  switch (projModel) {
220  break;
223  break;
225  throw vpException(
227  "Feature TOOL_SCHUNK_GRIPPER_CAMERA is not implemented for Kannala-Brandt projection model yet.");
228  break;
229  }
230  break;
231  }
233  switch (projModel) {
236  break;
239  break;
242  "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
243  break;
244  }
245  break;
246  }
249  "No predefined file available for a custom tool"
250  "You should use init(vpViper650::vpToolType, const std::string&) or"
251  "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
252  }
253  default: {
254  vpERROR_TRACE("This error should not occur!");
255  break;
256  }
257  }
258 
259  this->init(filename_eMc);
260 
261 #else // VISP_HAVE_VIPER650_DATA
262 
263  // Use here default values of the robot constant parameters.
264  switch (tool) {
266  switch (projModel) {
268  erc[0] = vpMath::rad(0.07); // rx
269  erc[1] = vpMath::rad(2.76); // ry
270  erc[2] = vpMath::rad(-91.50); // rz
271  etc[0] = -0.0453; // tx
272  etc[1] = 0.0005; // ty
273  etc[2] = 0.0728; // tz
274  break;
276  erc[0] = vpMath::rad(0.26); // rx
277  erc[1] = vpMath::rad(2.12); // ry
278  erc[2] = vpMath::rad(-91.31); // rz
279  etc[0] = -0.0444; // tx
280  etc[1] = -0.0005; // ty
281  etc[2] = 0.1022; // tz
282  break;
285  "Feature TOOL_MARLIN_F033C_CAMERA is not implemented for Kannala-Brandt projection model yet.");
286  break;
287  }
288  break;
289  }
292  switch (projModel) {
294  erc[0] = vpMath::rad(0.15); // rx
295  erc[1] = vpMath::rad(1.28); // ry
296  erc[2] = vpMath::rad(-90.8); // rz
297  etc[0] = -0.0456; // tx
298  etc[1] = -0.0013; // ty
299  etc[2] = 0.001; // tz
300  break;
302  erc[0] = vpMath::rad(0.72); // rx
303  erc[1] = vpMath::rad(2.10); // ry
304  erc[2] = vpMath::rad(-90.5); // rz
305  etc[0] = -0.0444; // tx
306  etc[1] = -0.0012; // ty
307  etc[2] = 0.078; // tz
308  break;
311  "Feature TOOL_PTGREY_FLEA2_CAMERA is not implemented for Kannala-Brandt projection model yet.");
312  break;
313  }
314  break;
315  }
317  // Set eMc to identity
318  switch (projModel) {
321  erc[0] = 0; // rx
322  erc[1] = 0; // ry
323  erc[2] = 0; // rz
324  etc[0] = 0; // tx
325  etc[1] = 0; // ty
326  etc[2] = 0; // tz
327  break;
330  "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
331  break;
332  }
333  break;
334  }
337  "No predefined parameters available for a custom tool"
338  "You should use init(vpViper650::vpToolType, const std::string&) or"
339  "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
340  }
341  }
342  vpRotationMatrix eRc(erc);
343  this->eMc.buildFrom(etc, eRc);
344 #endif // VISP_HAVE_VIPER650_DATA
345 
346  setToolType(tool);
347  return;
348 }
349 
380 void vpViper650::init(vpViper650::vpToolType tool, const std::string &filename)
381 {
382  this->setToolType(tool);
383  this->parseConfigFile(filename.c_str());
384 }
385 
402 {
403  this->setToolType(tool);
404  this->set_eMc(eMc_);
405 }
406 
415 void vpViper650::parseConfigFile(const std::string &filename)
416 {
417  vpRxyzVector erc_; // eMc rotation
418  vpTranslationVector etc_; // eMc translation
419 
420  std::ifstream fdconfig(filename.c_str(), std::ios::in);
421 
422  if (!fdconfig.is_open()) {
423  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the config file: %s",
424  filename.c_str());
425  }
426 
427  std::string line;
428  int lineNum = 0;
429  bool get_erc = false;
430  bool get_etc = false;
431  int code;
432 
433  while (std::getline(fdconfig, line)) {
434  lineNum++;
435  if ((line.compare(0, 1, "#") == 0) || line.empty()) { // skip comment or empty line
436  continue;
437  }
438  std::istringstream ss(line);
439  std::string key;
440  ss >> key;
441 
442  for (code = 0; nullptr != opt_viper650[code]; ++code) {
443  if (key.compare(opt_viper650[code]) == 0) {
444  break;
445  }
446  }
447 
448  switch (code) {
449  case 0:
450  break; // Nothing to do: camera name
451 
452  case 1: {
453  ss >> erc_[0] >> erc_[1] >> erc_[2];
454 
455  // Convert rotation from degrees to radians
456  erc_ = erc_ * M_PI / 180.0;
457  get_erc = true;
458  break;
459  }
460 
461  case 2: {
462  ss >> etc_[0] >> etc_[1] >> etc_[2];
463  get_etc = true;
464  break;
465  }
466 
467  default:
468  throw(vpRobotException(vpRobotException::readingParametersError, "Bad configuration file %s line #%d",
469  filename.c_str(), lineNum));
470  }
471  }
472  fdconfig.close();
473 
474  // Compute the eMc matrix from the translations and rotations
475  if (get_etc && get_erc) {
476  this->set_eMc(etc_, erc_);
477  }
478  else {
480  "Could not read translation and rotation "
481  "parameters from config file %s",
482  filename.c_str());
483  }
484 }
485 
559 void vpViper650::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
560  const unsigned int &image_height) const
561 {
562 #if defined(VISP_HAVE_VIPER650_DATA) && defined(VISP_HAVE_PUGIXML)
563  vpXmlParserCamera parser;
564  switch (getToolType()) {
566  std::cout << "Get camera parameters for camera \"" << vpViper650::CONST_MARLIN_F033C_CAMERA_NAME << "\""
567  << std::endl
568  << "from the XML file: \"" << vpViper650::CONST_CAMERA_FILENAME << "\"" << std::endl;
570  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
571  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
572  }
573  break;
574  }
576  std::cout << "Get camera parameters for camera \"" << vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME << "\""
577  << std::endl
578  << "from the XML file: \"" << vpViper650::CONST_CAMERA_FILENAME << "\"" << std::endl;
580  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
581  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
582  }
583  break;
584  }
586  std::cout << "Get camera parameters for camera \"" << vpViper650::CONST_SCHUNK_GRIPPER_CAMERA_NAME << "\""
587  << std::endl
588  << "from the XML file: \"" << vpViper650::CONST_CAMERA_FILENAME << "\"" << std::endl;
590  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
591  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
592  }
593  break;
594  }
596  std::cout << "Get camera parameters for camera \"" << vpViper650::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
597  << "from the XML file: \"" << vpViper650::CONST_CAMERA_FILENAME << "\"" << std::endl;
599  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
600  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
601  }
602  break;
603  }
605  throw vpRobotException(vpRobotException::badValue, "No intrinsic parameters available for a custom tool");
606  }
607  default: {
608  vpERROR_TRACE("This error should not occur!");
609  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
610  // "que les specs de la classe ont ete modifiee, "
611  // "et que le code n'a pas ete mis a jour "
612  // "correctement.");
613  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
614  // "vpViper650::vpViper650ToolType, et controlez que "
615  // "tous les cas ont ete pris en compte dans la "
616  // "fonction init(camera).");
617  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
618  }
619  }
620 #else
621  // Set default parameters
622  switch (getToolType()) {
624  // Set default intrinsic camera parameters for 640x480 images
625  if (image_width == 640 && image_height == 480) {
626  std::cout << "Get default camera parameters for camera \"" << vpViper650::CONST_MARLIN_F033C_CAMERA_NAME << "\""
627  << std::endl;
628  switch (this->projModel) {
630  cam.initPersProjWithoutDistortion(1232.0, 1233.0, 317.7, 253.9);
631  break;
633  cam.initPersProjWithDistortion(1214.0, 1213.0, 323.1, 240.0, -0.1824, 0.1881);
634  break;
637  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
638  break;
639  }
640  }
641  else {
642  vpTRACE("Cannot get default intrinsic camera parameters for this image "
643  "resolution");
644  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
645  }
646  break;
647  }
650  // Set default intrinsic camera parameters for 640x480 images
651  if (image_width == 640 && image_height == 480) {
652  std::cout << "Get default camera parameters for camera \"" << vpViper650::CONST_PTGREY_FLEA2_CAMERA_NAME << "\""
653  << std::endl;
654  switch (this->projModel) {
656  cam.initPersProjWithoutDistortion(868.0, 869.0, 314.8, 254.1);
657  break;
659  cam.initPersProjWithDistortion(831.3, 831.6, 322.7, 265.8, -0.1955, 0.2047);
660  break;
663  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
664  break;
665  }
666  }
667  else {
668  vpTRACE("Cannot get default intrinsic camera parameters for this image "
669  "resolution");
670  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
671  }
672  break;
673  }
675  // Set default intrinsic camera parameters for 640x480 images
676  if (image_width == 640 && image_height == 480) {
677  std::cout << "Get default camera parameters for camera \"" << vpViper650::CONST_GENERIC_CAMERA_NAME << "\""
678  << std::endl;
679  switch (this->projModel) {
681  cam.initPersProjWithoutDistortion(868.0, 869.0, 314.8, 254.1);
682  break;
684  cam.initPersProjWithDistortion(831.3, 831.6, 322.7, 265.8, -0.1955, 0.2047);
685  break;
688  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
689  break;
690  }
691  }
692  else {
693  vpTRACE("Cannot get default intrinsic camera parameters for this image "
694  "resolution");
695  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
696  }
697  break;
698  }
700  throw vpRobotException(vpRobotException::badValue, "No intrinsic parameters available for a custom tool");
701  }
702  }
703 #endif
704  return;
705 }
706 
772 {
773  getCameraParameters(cam, I.getWidth(), I.getHeight());
774 }
841 {
842  getCameraParameters(cam, I.getWidth(), I.getHeight());
843 }
844 END_VISP_NAMESPACE
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ ProjWithKannalaBrandtDistortion
Projection with Kannala-Brandt distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
void initPersProjWithDistortion(double px, double py, double u0, double v0, double kud, double kdu)
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ badValue
Used to indicate that a value is not in the allowed range.
Definition: vpException.h:73
@ notImplementedError
Not implemented.
Definition: vpException.h:69
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getHeight() const
Definition: vpImage.h:181
static double rad(double deg)
Definition: vpMath.h:129
Error that can be emitted by the vpRobot class and its derivatives.
@ readingParametersError
Cannot parse parameters.
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
Class that consider the case of a translation vector.
Modelization of the ADEPT Viper 650 robot.
Definition: vpViper650.h:95
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:106
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition: vpViper650.h:114
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper650.h:168
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:104
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:129
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:105
vpToolType getToolType() const
Get the current tool type.
Definition: vpViper650.h:152
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:107
void parseConfigFile(const std::string &filename)
Definition: vpViper650.cpp:415
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpViper650.cpp:559
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpViper650.h:116
void init(void)
Definition: vpViper650.cpp:133
static const std::string CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:100
static const std::string CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:101
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
Definition: vpViper650.h:161
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:120
@ TOOL_MARLIN_F033C_CAMERA
Definition: vpViper650.h:121
@ TOOL_SCHUNK_GRIPPER_CAMERA
Definition: vpViper650.h:123
@ TOOL_GENERIC_CAMERA
Definition: vpViper650.h:124
@ TOOL_PTGREY_FLEA2_CAMERA
Definition: vpViper650.h:122
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition: vpViper650.h:113
static const std::string CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
Definition: vpViper650.h:102
static const std::string CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
Definition: vpViper650.h:103
static const std::string CONST_CAMERA_FILENAME
Definition: vpViper650.h:108
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
Definition: vpViper650.h:115
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1229
vpTranslationVector etc
Definition: vpViper.h:158
double d6
for joint 6
Definition: vpViper.h:166
double a3
for joint 3
Definition: vpViper.h:164
double d4
for joint 4
Definition: vpViper.h:165
vpColVector joint_max
Definition: vpViper.h:171
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:168
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
double d1
for joint 1
Definition: vpViper.h:162
XML parser to load and save intrinsic camera parameters.
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, unsigned int image_width=0, unsigned int image_height=0, bool verbose=true)