46 #include <visp3/core/vpDebug.h>
47 #include <visp3/robot/vpViper650.h>
48 #include <visp3/core/vpMath.h>
49 #include <visp3/core/vpXmlParserCamera.h>
51 static const char *opt_viper650[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ",
54 #ifdef VISP_HAVE_ACCESS_TO_NAS
57 =
"Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
59 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf";
64 =
"Z:/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
66 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf";
71 =
"Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
73 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf";
78 =
"Z:/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
80 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf";
85 =
"Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
87 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_without_distortion_Viper650.cnf";
92 =
"Z:/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
94 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf";
99 =
"Z:/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
101 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_without_distortion_Viper650.cnf";
106 =
"Z:/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
108 =
"/udd/fspindle/robot/Viper650/current/include/const_eMc_generic_with_distortion_Viper650.cnf";
114 =
"Z:/robot/Viper650/current/include/const_camera_Viper650.xml";
116 =
"/udd/fspindle/robot/Viper650/current/include/const_camera_Viper650.xml";
120 #endif // VISP_HAVE_ACCESS_TO_NAS
147 c56 = -341.33 / 9102.22;
186 #ifdef VISP_HAVE_ACCESS_TO_NAS
225 #ifdef VISP_HAVE_ACCESS_TO_NAS
227 char filename_eMc [FILENAME_MAX];
232 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
233 snprintf(filename_eMc, FILENAME_MAX,
"%s",
236 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
241 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
242 snprintf(filename_eMc, FILENAME_MAX,
"%s",
245 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
255 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
256 snprintf(filename_eMc, FILENAME_MAX,
"%s",
259 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
264 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
265 snprintf(filename_eMc, FILENAME_MAX,
"%s",
268 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
278 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
279 snprintf(filename_eMc, FILENAME_MAX,
"%s",
282 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
287 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
288 snprintf(filename_eMc, FILENAME_MAX,
"%s",
291 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
301 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
302 snprintf(filename_eMc, FILENAME_MAX,
"%s",
305 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
310 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
311 snprintf(filename_eMc, FILENAME_MAX,
"%s",
314 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
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");
342 this->
init (filename_eMc);
344 #else // VISP_HAVE_ACCESS_TO_NAS
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");
416 #endif // VISP_HAVE_ACCESS_TO_NAS
454 const std::string &filename)
496 char Ligne[FILENAME_MAX];
502 bool get_rot_eMc =
false;
503 bool get_trans_eMc =
false;
506 if ((fdtask = fopen(filename,
"r" )) == NULL)
511 "Impossible to read the config file.");
514 while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
516 if (
'#' == Ligne[0]) {
continue; }
517 if (sscanf(Ligne,
"%s", namoption) != 1) {
520 "Cannot parse configuration file %s to retrieve option name"));
523 dim = strlen(namoption);
526 NULL != opt_viper650[code];
529 if (strncmp(opt_viper650[code], namoption, dim) == 0)
540 if (sscanf(Ligne,
"%s %lf %lf %lf", namoption,
541 &rot_eMc[0], &rot_eMc[1], &rot_eMc[2]) != 4) {
544 "Cannot parse configuration file %s to retrieve translation"));
548 rot_eMc[0] *= M_PI / 180.0;
549 rot_eMc[1] *= M_PI / 180.0;
550 rot_eMc[2] *= M_PI / 180.0;
555 if (sscanf(Ligne,
"%s %lf %lf %lf", namoption,
556 &trans_eMc[0], &trans_eMc[1], &trans_eMc[2]) != 4) {
559 "Cannot parse configuration file %s to retrieve rotation"));
561 get_trans_eMc =
true;
566 "ligne #%d.", filename, numLn);
573 if (get_rot_eMc && get_trans_eMc) {
574 this->
set_eMc(trans_eMc,rot_eMc);
577 vpERROR_TRACE (
"Could not read translation and rotation parameters from config file %s.",
580 "Could not read translation and rotation parameters from config file ");
661 const unsigned int &image_width,
662 const unsigned int &image_height)
const
664 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
668 std::cout <<
"Get camera parameters for camera \""
670 <<
"from the XML file: \""
672 if (parser.
parse(cam,
678 "Impossible to read the camera parameters.");
683 std::cout <<
"Get camera parameters for camera \""
685 <<
"from the XML file: \""
687 if (parser.
parse(cam,
693 "Impossible to read the camera parameters.");
698 std::cout <<
"Get camera parameters for camera \""
700 <<
"from the XML file: \""
702 if (parser.
parse(cam,
708 "Impossible to read the camera parameters.");
713 std::cout <<
"Get camera parameters for camera \""
715 <<
"from the XML file: \""
717 if (parser.
parse(cam,
723 "Impossible to read the camera parameters.");
728 vpERROR_TRACE (
"No intrinsic parameters available for a custom tool");
743 "Impossible to read the camera parameters.");
752 if (image_width == 640 && image_height == 480) {
753 std::cout <<
"Get default camera parameters for camera \""
765 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
767 "Impossible to read the camera parameters.");
774 if (image_width == 640 && image_height == 480) {
775 std::cout <<
"Get default camera parameters for camera \""
787 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
789 "Impossible to read the camera parameters.");
795 if (image_width == 640 && image_height == 480) {
796 std::cout <<
"Get default camera parameters for camera \""
808 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
810 "Impossible to read the camera parameters.");
815 vpERROR_TRACE (
"No intrinsic parameters available for a custom tool");
822 "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
Implementation of an homogeneous matrix and operations on such kind of matrices.
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
error that can be emited by ViSP classes.
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
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.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
static const char *const CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
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)
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
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
Implementation of a rotation vector as Euler angle minimal representation.
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.
static const char *const CONST_GENERIC_CAMERA_NAME
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)