50 #include <visp/vpDebug.h>
51 #include <visp/vpViper650.h>
52 #include <visp/vpMath.h>
53 #include <visp/vpXmlParserCamera.h>
55 #ifdef VISP_HAVE_ACCESS_TO_NAS
56 static const char *opt_viper650[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ",
61 =
"Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
63 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
68 =
"Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
70 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
75 =
"Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
77 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
82 =
"Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
84 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
89 =
"Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
91 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
96 =
"Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
98 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
103 =
"Z:/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
105 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
110 =
"Z:/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
112 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
118 =
"Z:/robot/Viper650/current/include/const_camera_Viper650.xml";
120 =
"/udd/fspindle/robot/Viper650/current/include/const_camera_Viper650.xml";
124 #endif // VISP_HAVE_ACCESS_TO_NAS
151 c56 = -341.33 / 9102.22;
193 #ifdef VISP_HAVE_ACCESS_TO_NAS
223 #ifdef VISP_HAVE_ACCESS_TO_NAS
225 char filename_eMc [FILENAME_MAX];
230 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
231 snprintf(filename_eMc, FILENAME_MAX,
"%s",
234 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
239 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
240 snprintf(filename_eMc, FILENAME_MAX,
"%s",
243 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
253 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
254 snprintf(filename_eMc, FILENAME_MAX,
"%s",
257 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
262 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
263 snprintf(filename_eMc, FILENAME_MAX,
"%s",
266 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
276 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
277 snprintf(filename_eMc, FILENAME_MAX,
"%s",
280 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
285 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
286 snprintf(filename_eMc, FILENAME_MAX,
"%s",
289 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
299 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
300 snprintf(filename_eMc, FILENAME_MAX,
"%s",
303 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
308 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
309 snprintf(filename_eMc, FILENAME_MAX,
"%s",
312 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
333 this->
init (filename_eMc);
335 #else // VISP_HAVE_ACCESS_TO_NAS
400 #endif // VISP_HAVE_ACCESS_TO_NAS
417 #ifdef VISP_HAVE_ACCESS_TO_NAS
423 char Ligne[FILENAME_MAX];
429 bool get_rot_eMc =
false;
430 bool get_trans_eMc =
false;
433 if ((fdtask = fopen(filename,
"r" )) == NULL)
438 "Impossible to read the config file.");
441 while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
443 if (
'#' == Ligne[0]) {
continue; }
444 sscanf(Ligne,
"%s", namoption);
445 dim = strlen(namoption);
448 NULL != opt_viper650[code];
451 if (strncmp(opt_viper650[code], namoption, dim) == 0)
462 sscanf(Ligne,
"%s %lf %lf %lf", namoption,
468 rot_eMc[0] *= M_PI / 180.0;
469 rot_eMc[1] *= M_PI / 180.0;
470 rot_eMc[2] *= M_PI / 180.0;
475 sscanf(Ligne,
"%s %lf %lf %lf", namoption,
479 get_trans_eMc =
true;
484 "ligne #%d.", filename, numLn);
491 if (get_rot_eMc && get_trans_eMc) {
492 for (
unsigned int i=0; i < 3; i ++) {
494 etc[i] = trans_eMc[i];
580 const unsigned int &image_width,
581 const unsigned int &image_height)
const
583 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
587 std::cout <<
"Get camera parameters for camera \""
589 <<
"from the XML file: \""
591 if (parser.
parse(cam,
597 "Impossible to read the camera parameters.");
602 std::cout <<
"Get camera parameters for camera \""
604 <<
"from the XML file: \""
606 if (parser.
parse(cam,
612 "Impossible to read the camera parameters.");
617 std::cout <<
"Get camera parameters for camera \""
619 <<
"from the XML file: \""
621 if (parser.
parse(cam,
627 "Impossible to read the camera parameters.");
632 std::cout <<
"Get camera parameters for camera \""
634 <<
"from the XML file: \""
636 if (parser.
parse(cam,
642 "Impossible to read the camera parameters.");
657 "Impossible to read the camera parameters.");
666 if (image_width == 640 && image_height == 480) {
667 std::cout <<
"Get default camera parameters for camera \""
679 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
681 "Impossible to read the camera parameters.");
688 if (image_width == 640 && image_height == 480) {
689 std::cout <<
"Get default camera parameters for camera \""
701 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
703 "Impossible to read the camera parameters.");
709 if (image_width == 640 && image_height == 480) {
710 std::cout <<
"Get default camera parameters for camera \""
722 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
724 "Impossible to read the camera parameters.");
731 "Impossible to read the camera parameters.");
vpHomogeneousMatrix eMc
End effector to camera transformation.
Error that can be emited by the vpRobot class and its derivates.
Perspective projection without distortion model.
unsigned int getWidth() const
static const char *const CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
vpCameraParameters::vpCameraParametersProjType projModel
static const char *const CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
static const char *const CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
vpToolType getToolType() const
Get the current tool type.
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
XML parser to load and save intrinsic camera parameters.
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
The vpRotationMatrix considers the particular case of a rotation matrix.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
double c56
Mechanical coupling between joint 5 and joint 6.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
static const char *const CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
vpCameraParametersProjType
Generic class defining intrinsic camera parameters.
Modelisation of the ADEPT Viper 650 robot.
static const char *const CONST_CAMERA_FILENAME
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
vpToolType
List of possible tools that can be attached to the robot end-effector.
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
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)
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
static const char *const CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
int parse(vpCameraParameters &cam, const char *filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, const unsigned int image_width=0, const unsigned int image_height=0)
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
void parseConfigFile(const char *filename)
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
unsigned int getHeight() const
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
static const char *const CONST_GENERIC_CAMERA_NAME
void initPersProjWithDistortion(const double px, const double py, const double u0, const double v0, const double kud, const double kdu)