47 #include <visp3/core/vpDebug.h> 48 #include <visp3/core/vpMath.h> 49 #include <visp3/core/vpXmlParserCamera.h> 50 #include <visp3/robot/vpViper650.h> 52 static const char *opt_viper650[] = {
"CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ", NULL};
54 #ifdef VISP_HAVE_VIPER650_DATA 56 std::string(VISP_VIPER650_DATA_PATH) +
57 std::string(
"/include/const_eMc_MarlinF033C_without_distortion_Viper650.cnf");
60 std::string(VISP_VIPER650_DATA_PATH) + std::string(
"/include/const_eMc_MarlinF033C_with_distortion_Viper650.cnf");
63 std::string(VISP_VIPER650_DATA_PATH) +
64 std::string(
"/include/const_eMc_PTGreyFlea2_without_distortion_Viper650.cnf");
67 std::string(VISP_VIPER650_DATA_PATH) + std::string(
"/include/const_eMc_PTGreyFlea2_with_distortion_Viper650.cnf");
70 std::string(VISP_VIPER650_DATA_PATH) + std::string(
"/include/" 71 "const_eMc_schunk_gripper_without_distortion_Viper650." 75 std::string(VISP_VIPER650_DATA_PATH) +
76 std::string(
"/include/const_eMc_schunk_gripper_with_distortion_Viper650.cnf");
79 std::string(VISP_VIPER650_DATA_PATH) + std::string(
"/include/const_eMc_generic_without_distortion_Viper650.cnf");
82 std::string(VISP_VIPER650_DATA_PATH) + std::string(
"/include/const_eMc_generic_with_distortion_Viper650.cnf");
85 std::string(VISP_VIPER650_DATA_PATH) + std::string(
"/include/const_camera_Viper650.xml");
87 #endif // VISP_HAVE_VIPER650_DATA 112 c56 = -341.33 / 9102.22;
184 #ifdef VISP_HAVE_VIPER650_DATA 186 std::string filename_eMc;
246 "No predefined file available for a custom tool" 247 "You should use init(vpViper650::vpToolType, const std::string&) or" 248 "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
264 this->
init(filename_eMc);
266 #else // VISP_HAVE_VIPER650_DATA 339 "No predefined parameters available for a custom tool" 340 "You should use init(vpViper650::vpToolType, const std::string&) or" 341 "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
346 #endif // VISP_HAVE_VIPER650_DATA 422 std::ifstream fdconfig(filename.c_str(), std::ios::in);
424 if (!fdconfig.is_open()) {
431 bool get_erc =
false;
432 bool get_etc =
false;
435 while (std::getline(fdconfig, line)) {
437 if ((line.compare(0, 1,
"#") == 0) || line.empty()) {
440 std::istringstream ss(line);
444 for (code = 0; NULL != opt_viper650[code]; ++code) {
445 if (key.compare(opt_viper650[code]) == 0) {
455 ss >> erc_[0] >> erc_[1] >> erc_[2];
458 erc_ = erc_ * M_PI / 180.0;
471 filename.c_str(), lineNum));
478 if (get_etc && get_erc) {
482 "Could not read translation and rotation " 483 "parameters from config file %s",
558 const unsigned int &image_height)
const 560 #if defined(VISP_HAVE_VIPER650_DATA) 623 if (image_width == 640 && image_height == 480) {
638 vpTRACE(
"Cannot get default intrinsic camera parameters for this image " 647 if (image_width == 640 && image_height == 480) {
662 vpTRACE(
"Cannot get default intrinsic camera parameters for this image " 670 if (image_width == 640 && image_height == 480) {
685 vpTRACE(
"Cannot get default intrinsic camera parameters for this image " Used to indicate that a value is not in the allowed range.
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
vpHomogeneousMatrix eMc
End effector to camera transformation.
Error that can be emited by the vpRobot class and its derivates.
unsigned int getWidth() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpCameraParameters::vpCameraParametersProjType projModel
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
static const std::string CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
error that can be emited by ViSP classes.
vpToolType getToolType() const
Get the current tool type.
static const std::string CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
static const std::string CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
XML parser to load and save intrinsic camera parameters.
void initPersProjWithDistortion(double px, double py, double u0, double v0, double kud, double kdu)
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.
double c56
Mechanical coupling between joint 5 and joint 6.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
vpCameraParametersProjType
void parseConfigFile(const std::string &filename)
Generic class defining intrinsic camera parameters.
Modelisation of the ADEPT Viper 650 robot.
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
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, unsigned int image_width=0, unsigned int image_height=0)
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
static const std::string CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
unsigned int getHeight() const
Implementation of a rotation vector as Euler angle minimal representation.
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.
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
static const std::string CONST_CAMERA_FILENAME