50 #include <visp/vpDebug.h>
51 #include <visp/vpViper850.h>
52 #include <visp/vpMath.h>
53 #include <visp/vpXmlParserCamera.h>
55 #ifdef VISP_HAVE_ACCESS_TO_NAS
56 static const char *opt_viper850[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ",
61 =
"Z:/robot/Viper850/current/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf";
63 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf";
68 =
"Z:/robot/Viper850/current/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf";
70 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf";
75 =
"Z:/robot/Viper850/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf";
77 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf";
82 =
"Z:/robot/Viper850/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf";
84 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf";
89 =
"Z:/robot/Viper850/current/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf";
91 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf";
96 =
"Z:/robot/Viper850/current/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf";
98 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf";
103 =
"Z:/robot/Viper850/current/include/const_eMc_generic_without_distortion_Viper850.cnf";
105 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_without_distortion_Viper850.cnf";
110 =
"Z:/robot/Viper850/current/include/const_eMc_generic_with_distortion_Viper850.cnf";
112 =
"/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_with_distortion_Viper850.cnf";
118 =
"Z:/robot/Viper850/current/include/const_camera_Viper850.xml";
120 =
"/udd/fspindle/robot/Viper850/current/include/const_camera_Viper850.xml";
124 #endif // VISP_HAVE_ACCESS_TO_NAS
152 c56 = -341.33 / 9102.22;
194 #ifdef VISP_HAVE_ACCESS_TO_NAS
224 #ifdef VISP_HAVE_ACCESS_TO_NAS
226 char filename_eMc [FILENAME_MAX];
231 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
232 snprintf(filename_eMc, FILENAME_MAX,
"%s",
235 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
240 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
241 snprintf(filename_eMc, FILENAME_MAX,
"%s",
244 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
254 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
255 snprintf(filename_eMc, FILENAME_MAX,
"%s",
258 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
263 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
264 snprintf(filename_eMc, FILENAME_MAX,
"%s",
267 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
277 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
278 snprintf(filename_eMc, FILENAME_MAX,
"%s",
281 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
286 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
287 snprintf(filename_eMc, FILENAME_MAX,
"%s",
290 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
300 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
301 snprintf(filename_eMc, FILENAME_MAX,
"%s",
304 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
309 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
310 snprintf(filename_eMc, FILENAME_MAX,
"%s",
313 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
334 this->
init (filename_eMc);
336 #else // VISP_HAVE_ACCESS_TO_NAS
401 #endif // VISP_HAVE_ACCESS_TO_NAS
418 #ifdef VISP_HAVE_ACCESS_TO_NAS
424 char Ligne[FILENAME_MAX];
430 bool get_rot_eMc =
false;
431 bool get_trans_eMc =
false;
434 if ((fdtask = fopen(filename,
"r" )) == NULL)
439 "Impossible to read the config file.");
442 while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
444 if (
'#' == Ligne[0]) {
continue; }
445 sscanf(Ligne,
"%s", namoption);
446 dim = strlen(namoption);
449 NULL != opt_viper850[code];
452 if (strncmp(opt_viper850[code], namoption, dim) == 0)
463 sscanf(Ligne,
"%s %lf %lf %lf", namoption,
469 rot_eMc[0] *= M_PI / 180.0;
470 rot_eMc[1] *= M_PI / 180.0;
471 rot_eMc[2] *= M_PI / 180.0;
476 sscanf(Ligne,
"%s %lf %lf %lf", namoption,
480 get_trans_eMc =
true;
485 "ligne #%d.", filename, numLn);
492 if (get_rot_eMc && get_trans_eMc) {
493 for (
unsigned int i=0; i < 3; i ++) {
495 etc[i] = trans_eMc[i];
581 const unsigned int &image_width,
582 const unsigned int &image_height)
const
584 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
588 std::cout <<
"Get camera parameters for camera \""
590 <<
"from the XML file: \""
592 if (parser.
parse(cam,
598 "Impossible to read the camera parameters.");
603 std::cout <<
"Get camera parameters for camera \""
605 <<
"from the XML file: \""
607 if (parser.
parse(cam,
613 "Impossible to read the camera parameters.");
618 std::cout <<
"Get camera parameters for camera \""
620 <<
"from the XML file: \""
622 if (parser.
parse(cam,
628 "Impossible to read the camera parameters.");
633 std::cout <<
"Get camera parameters for camera \""
635 <<
"from the XML file: \""
637 if (parser.
parse(cam,
643 "Impossible to read the camera parameters.");
658 "Impossible to read the camera parameters.");
667 if (image_width == 640 && image_height == 480) {
668 std::cout <<
"Get default camera parameters for camera \""
680 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
682 "Impossible to read the camera parameters.");
689 if (image_width == 640 && image_height == 480) {
690 std::cout <<
"Get default camera parameters for camera \""
702 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
704 "Impossible to read the camera parameters.");
710 if (image_width == 640 && image_height == 480) {
711 std::cout <<
"Get default camera parameters for camera \""
723 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
725 "Impossible to read the camera parameters.");
732 "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
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
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.
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)
Construction from translation vector and rotation matrix.
static double rad(double deg)
static const char *const CONST_EMC_PTGREY_FLEA2_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_GENERIC_WITHOUT_DISTORTION_FILENAME
unsigned int getHeight() const
void parseConfigFile(const char *filename)
vpCameraParameters::vpCameraParametersProjType projModel
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