47 #include <visp3/core/vpDebug.h> 48 #include <visp3/core/vpMath.h> 49 #include <visp3/core/vpXmlParserCamera.h> 50 #include <visp3/robot/vpViper850.h> 52 static const char *opt_viper850[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ", NULL};
54 #ifdef VISP_HAVE_VIPER850_DATA 56 std::string(VISP_VIPER850_DATA_PATH) +
57 std::string(
"/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf");
60 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf");
63 std::string(VISP_VIPER850_DATA_PATH) +
64 std::string(
"/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf");
67 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf");
70 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/" 71 "const_eMc_schunk_gripper_without_distortion_Viper850." 75 std::string(VISP_VIPER850_DATA_PATH) +
76 std::string(
"/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf");
79 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_generic_without_distortion_Viper850.cnf");
82 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_eMc_generic_with_distortion_Viper850.cnf");
85 std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/include/const_camera_Viper850.xml");
87 #endif // VISP_HAVE_VIPER850_DATA 113 c56 = -341.33 / 9102.22;
185 #ifdef VISP_HAVE_VIPER850_DATA 187 std::string filename_eMc;
235 "No predefined file available for a custom tool" 236 "You should use init(vpViper850::vpToolType, const std::string&) or" 237 "init(vpViper850::vpToolType, const vpHomogeneousMatrix&) instead");
253 this->
init(filename_eMc);
255 #else // VISP_HAVE_VIPER850_DATA 319 "No predefined parameters available for a custom tool" 320 "You should use init(vpViper850::vpToolType, const std::string&) or" 321 "init(vpViper850::vpToolType, const vpHomogeneousMatrix&) instead");
326 #endif // VISP_HAVE_VIPER850_DATA 402 std::ifstream fdconfig(filename.c_str(), std::ios::in);
404 if (!fdconfig.is_open()) {
411 bool get_erc =
false;
412 bool get_etc =
false;
415 while (std::getline(fdconfig, line)) {
417 if ((line.compare(0, 1,
"#") == 0) || line.empty()) {
420 std::istringstream ss(line);
424 for (code = 0; NULL != opt_viper850[code]; ++code) {
425 if (key.compare(opt_viper850[code]) == 0) {
435 ss >> erc[0] >> erc[1] >> erc[2];
438 erc = erc * M_PI / 180.0;
444 ss >> etc[0] >> etc[1] >> etc[2];
451 filename.c_str(), lineNum));
458 if (get_etc && get_erc) {
462 "Could not read translation and rotation " 463 "parameters from config file %s",
541 const unsigned int &image_height)
const 543 #if defined(VISP_HAVE_XML2) && defined(VISP_HAVE_VIPER850_DATA) 606 if (image_width == 640 && image_height == 480) {
618 vpTRACE(
"Cannot get default intrinsic camera parameters for this image " 627 if (image_width == 640 && image_height == 480) {
639 vpTRACE(
"Cannot get default intrinsic camera parameters for this image " 647 if (image_width == 640 && image_height == 480) {
659 vpTRACE(
"Cannot get default intrinsic camera parameters for this image "
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
void parseConfigFile(const std::string &filename)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Implementation of an homogeneous matrix and operations on such kind of matrices.
static const std::string CONST_CAMERA_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
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.
static const std::string CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
vpToolType getToolType() const
Get the current tool type.
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
unsigned int getHeight() const
static const std::string CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
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)
unsigned int getWidth() const
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