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 static const char *opt_viper850[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ",
54 #ifdef VISP_HAVE_VIPER850_DATA
56 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf");
59 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf");
62 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf");
65 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf");
68 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf");
71 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf");
74 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_generic_without_distortion_Viper850.cnf");
77 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_generic_with_distortion_Viper850.cnf");
80 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_camera_Viper850.xml");
82 #endif // VISP_HAVE_VIPER850_DATA
110 c56 = -341.33 / 9102.22;
186 #ifdef VISP_HAVE_VIPER850_DATA
188 std::string filename_eMc;
236 "No predefined file available for a custom tool"
237 "You should use init(vpViper850::vpToolType, const std::string&) or"
238 "init(vpViper850::vpToolType, const vpHomogeneousMatrix&) instead");
254 this->
init (filename_eMc);
256 #else // VISP_HAVE_VIPER850_DATA
320 "No predefined parameters available for a custom tool"
321 "You should use init(vpViper850::vpToolType, const std::string&) or"
322 "init(vpViper850::vpToolType, const vpHomogeneousMatrix&) instead");
327 #endif // VISP_HAVE_VIPER850_DATA
403 char Ligne[FILENAME_MAX];
409 bool get_rot_eMc =
false;
410 bool get_trans_eMc =
false;
413 if ((fdtask = fopen(filename.c_str(),
"r" )) == NULL) {
415 "Impossible to read the config file %s.", filename.c_str());
419 while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
421 if (
'#' == Ligne[0]) {
continue; }
423 std::stringstream ss(Ligne);
429 "Cannot parse configuration file %s to retrieve option name", filename.c_str()));
433 dim = strlen(namoption);
435 for (code = 0; NULL != opt_viper850[code]; ++ code) {
436 if (strncmp(opt_viper850[code], namoption, dim) == 0) {
446 std::stringstream ss(Ligne);
447 ss >> namoption >> rot_eMc[0] >> rot_eMc[1] >> rot_eMc[2];
451 "Cannot parse configuration file %s to retrieve rotation", filename.c_str()));
455 rot_eMc[0] *= M_PI / 180.0;
456 rot_eMc[1] *= M_PI / 180.0;
457 rot_eMc[2] *= M_PI / 180.0;
463 std::stringstream ss(Ligne);
464 ss >> namoption >> trans_eMc[0] >> trans_eMc[1] >> trans_eMc[2];
468 "Cannot parse configuration file %s to retrieve translation", filename.c_str()));
470 get_trans_eMc =
true;
475 "ligne #%d.", filename.c_str(), numLn);
482 if (get_rot_eMc && get_trans_eMc) {
483 this->
set_eMc(trans_eMc,rot_eMc);
487 "Could not read translation and rotation parameters from config file %s", filename.c_str());
565 const unsigned int &image_width,
566 const unsigned int &image_height)
const
568 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_VIPER850_DATA)
572 std::cout <<
"Get camera parameters for camera \""
574 <<
"from the XML file: \""
576 if (parser.
parse(cam,
582 "Impossible to read the camera parameters.");
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.");
633 "No intrinsic parameters available for a custom tool");
646 "Impossible to read the camera parameters.");
654 if (image_width == 640 && image_height == 480) {
655 std::cout <<
"Get default camera parameters for camera \""
667 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
669 "Impossible to read the camera parameters.");
676 if (image_width == 640 && image_height == 480) {
677 std::cout <<
"Get default camera parameters for camera \""
689 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
691 "Impossible to read the camera parameters.");
697 if (image_width == 640 && image_height == 480) {
698 std::cout <<
"Get default camera parameters for camera \""
710 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
712 "Impossible to read the camera parameters.");
718 "No intrinsic parameters available for a custom tool");
723 "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.
static const std::string CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
Perspective projection without distortion model.
void parseConfigFile(const std::string &filename)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
unsigned int getWidth() const
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Implementation of an homogeneous matrix and operations on such kind of matrices.
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
static const std::string CONST_CAMERA_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.
static const std::string CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
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.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
static const char *const CONST_GENERIC_CAMERA_NAME
vpCameraParametersProjType
vpToolType
List of possible tools that can be attached to the robot end-effector.
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Generic class defining intrinsic camera parameters.
Modelisation of the ADEPT Viper 850 robot.
vpToolType getToolType() const
Get the current tool type.
static const std::string CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
static const std::string CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
unsigned int getHeight() const
Implementation of a rotation vector as Euler angle minimal representation.
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)
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
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)
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME