46 #include <visp3/core/vpDebug.h>
47 #include <visp3/robot/vpViper850.h>
48 #include <visp3/core/vpMath.h>
49 #include <visp3/core/vpXmlParserCamera.h>
51 #ifdef VISP_HAVE_ACCESS_TO_NAS
52 static const char *opt_viper850[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ",
57 =
"Z:/robot/Viper850/current/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf";
59 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf";
64 =
"Z:/robot/Viper850/current/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf";
66 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf";
71 =
"Z:/robot/Viper850/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf";
73 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf";
78 =
"Z:/robot/Viper850/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf";
80 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf";
85 =
"Z:/robot/Viper850/current/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf";
87 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf";
92 =
"Z:/robot/Viper850/current/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf";
94 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf";
99 =
"Z:/robot/Viper850/current/include/const_eMc_generic_without_distortion_Viper850.cnf";
101 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_without_distortion_Viper850.cnf";
106 =
"Z:/robot/Viper850/current/include/const_eMc_generic_with_distortion_Viper850.cnf";
108 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_with_distortion_Viper850.cnf";
114 =
"Z:/robot/Viper850/current/include/const_camera_Viper850.xml";
116 =
"/udd/fspindle/robot/Viper850/current/include/const_camera_Viper850.xml";
120 #endif // VISP_HAVE_ACCESS_TO_NAS
148 c56 = -341.33 / 9102.22;
190 #ifdef VISP_HAVE_ACCESS_TO_NAS
220 #ifdef VISP_HAVE_ACCESS_TO_NAS
222 char filename_eMc [FILENAME_MAX];
227 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
228 snprintf(filename_eMc, FILENAME_MAX,
"%s",
231 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
236 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
237 snprintf(filename_eMc, FILENAME_MAX,
"%s",
240 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
250 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
251 snprintf(filename_eMc, FILENAME_MAX,
"%s",
254 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
259 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
260 snprintf(filename_eMc, FILENAME_MAX,
"%s",
263 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
273 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
274 snprintf(filename_eMc, FILENAME_MAX,
"%s",
277 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
282 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
283 snprintf(filename_eMc, FILENAME_MAX,
"%s",
286 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
296 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
297 snprintf(filename_eMc, FILENAME_MAX,
"%s",
300 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
305 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
306 snprintf(filename_eMc, FILENAME_MAX,
"%s",
309 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
330 this->
init (filename_eMc);
332 #else // VISP_HAVE_ACCESS_TO_NAS
397 #endif // VISP_HAVE_ACCESS_TO_NAS
414 #ifdef VISP_HAVE_ACCESS_TO_NAS
420 char Ligne[FILENAME_MAX];
426 bool get_rot_eMc =
false;
427 bool get_trans_eMc =
false;
430 if ((fdtask = fopen(filename,
"r" )) == NULL)
435 "Impossible to read the config file.");
438 while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
440 if (
'#' == Ligne[0]) {
continue; }
441 if (sscanf(Ligne,
"%s", namoption) != 1) {
444 "Cannot parse configuration file %s to retrieve option name"));
446 dim = strlen(namoption);
449 NULL != opt_viper850[code];
452 if (strncmp(opt_viper850[code], namoption, dim) == 0)
463 if (sscanf(Ligne,
"%s %lf %lf %lf", namoption,
464 &rot_eMc[0], &rot_eMc[1], &rot_eMc[2]) != 4) {
467 "Cannot parse configuration file %s to retrieve translation"));
471 rot_eMc[0] *= M_PI / 180.0;
472 rot_eMc[1] *= M_PI / 180.0;
473 rot_eMc[2] *= M_PI / 180.0;
478 if (sscanf(Ligne,
"%s %lf %lf %lf", namoption,
479 &trans_eMc[0], &trans_eMc[1], &trans_eMc[2]) != 4) {
482 "Cannot parse configuration file %s to retrieve rotation"));
484 get_trans_eMc =
true;
489 "ligne #%d.", filename, numLn);
496 if (get_rot_eMc && get_trans_eMc) {
497 for (
unsigned int i=0; i < 3; i ++) {
499 etc[i] = trans_eMc[i];
585 const unsigned int &image_width,
586 const unsigned int &image_height)
const
588 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
592 std::cout <<
"Get camera parameters for camera \""
594 <<
"from the XML file: \""
596 if (parser.
parse(cam,
602 "Impossible to read the camera parameters.");
607 std::cout <<
"Get camera parameters for camera \""
609 <<
"from the XML file: \""
611 if (parser.
parse(cam,
617 "Impossible to read the camera parameters.");
622 std::cout <<
"Get camera parameters for camera \""
624 <<
"from the XML file: \""
626 if (parser.
parse(cam,
632 "Impossible to read the camera parameters.");
637 std::cout <<
"Get camera parameters for camera \""
639 <<
"from the XML file: \""
641 if (parser.
parse(cam,
647 "Impossible to read the camera parameters.");
662 "Impossible to read the camera parameters.");
671 if (image_width == 640 && image_height == 480) {
672 std::cout <<
"Get default camera parameters for camera \""
684 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
686 "Impossible to read the camera parameters.");
693 if (image_width == 640 && image_height == 480) {
694 std::cout <<
"Get default camera parameters for camera \""
706 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
708 "Impossible to read the camera parameters.");
714 if (image_width == 640 && image_height == 480) {
715 std::cout <<
"Get default camera parameters for camera \""
727 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
729 "Impossible to read the camera parameters.");
736 "Impossible to read the camera parameters.");
static const char *const CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
vpHomogeneousMatrix eMc
End effector to camera transformation.
static const char *const CONST_CAMERA_FILENAME
Error that can be emited by the vpRobot class and its derivates.
Perspective projection without distortion model.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
unsigned int getWidth() const
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
static const char *const CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
error that can be emited by ViSP classes.
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
XML parser to load and save intrinsic camera parameters.
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
Implementation of a rotation matrix and operations on such kind of matrices.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
double c56
Mechanical coupling between joint 5 and joint 6.
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
static const char *const CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
static const char *const CONST_GENERIC_CAMERA_NAME
vpCameraParametersProjType
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
vpToolType
List of possible tools that can be attached to the robot end-effector.
Generic class defining intrinsic camera parameters.
Modelisation of the ADEPT Viper 850 robot.
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
vpToolType getToolType() const
Get the current tool type.
static const char *const CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
static const char *const CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
unsigned int getHeight() const
void parseConfigFile(const char *filename)
vpCameraParameters::vpCameraParametersProjType projModel
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 initPersProjWithDistortion(const double px, const double py, const double u0, const double v0, const double kud, const double kdu)
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME