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");
112 c56 = -341.33 / 9102.22;
184 #ifdef VISP_HAVE_VIPER650_DATA
186 std::string filename_eMc;
198 "Feature TOOL_MARLIN_F033C_CAMERA is not implemented for Kannala-Brandt projection model yet.");
213 "Feature TOOL_PTGREY_FLEA2_CAMERA is not implemented for Kannala-Brandt projection model yet.");
229 "Feature TOOL_SCHUNK_GRIPPER_CAMERA is not implemented for Kannala-Brandt projection model yet.");
244 "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
251 "No predefined file available for a custom tool"
252 "You should use init(vpViper650::vpToolType, const std::string&) or"
253 "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
269 this->
init(filename_eMc);
295 "Feature TOOL_MARLIN_F033C_CAMERA is not implemented for Kannala-Brandt projection model yet.");
321 "Feature TOOL_PTGREY_FLEA2_CAMERA is not implemented for Kannala-Brandt projection model yet.");
340 "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
347 "No predefined parameters available for a custom tool"
348 "You should use init(vpViper650::vpToolType, const std::string&) or"
349 "init(vpViper650::vpToolType, const vpHomogeneousMatrix&) instead");
430 std::ifstream fdconfig(filename.c_str(), std::ios::in);
432 if (!fdconfig.is_open()) {
439 bool get_erc =
false;
440 bool get_etc =
false;
443 while (std::getline(fdconfig, line)) {
445 if ((line.compare(0, 1,
"#") == 0) || line.empty()) {
448 std::istringstream ss(line);
452 for (code = 0; NULL != opt_viper650[code]; ++code) {
453 if (key.compare(opt_viper650[code]) == 0) {
463 ss >> erc_[0] >> erc_[1] >> erc_[2];
466 erc_ = erc_ * M_PI / 180.0;
472 ss >> etc_[0] >> etc_[1] >> etc_[2];
479 filename.c_str(), lineNum));
485 if (get_etc && get_erc) {
489 "Could not read translation and rotation "
490 "parameters from config file %s",
565 const unsigned int &image_height)
const
567 #if defined(VISP_HAVE_VIPER650_DATA)
630 if (image_width == 640 && image_height == 480) {
642 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
646 vpTRACE(
"Cannot get default intrinsic camera parameters for this image "
655 if (image_width == 640 && image_height == 480) {
667 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
671 vpTRACE(
"Cannot get default intrinsic camera parameters for this image "
679 if (image_width == 640 && image_height == 480) {
691 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
695 vpTRACE(
"Cannot get default intrinsic camera parameters for this image "
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
vpCameraParametersProjType
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ ProjWithKannalaBrandtDistortion
Projection with Kannala-Brandt distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
void initPersProjWithDistortion(double px, double py, double u0, double v0, double kud, double kdu)
error that can be emited by ViSP classes.
@ badValue
Used to indicate that a value is not in the allowed range.
@ notImplementedError
Not implemented.
Implementation of an homogeneous matrix and operations on such kind of matrices.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
unsigned int getWidth() const
unsigned int getHeight() const
static double rad(double deg)
Error that can be emited by the vpRobot class and its derivates.
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Class that consider the case of a translation vector.
Modelisation of the ADEPT Viper 650 robot.
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
vpCameraParameters::vpCameraParametersProjType projModel
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
static const vpToolType defaultTool
Default tool attached to the robot end effector.
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
vpToolType getToolType() const
Get the current tool type.
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
void parseConfigFile(const std::string &filename)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
static const char *const CONST_GENERIC_CAMERA_NAME
static const std::string CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
vpToolType
List of possible tools that can be attached to the robot end-effector.
@ TOOL_MARLIN_F033C_CAMERA
@ TOOL_SCHUNK_GRIPPER_CAMERA
@ TOOL_PTGREY_FLEA2_CAMERA
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
static const std::string CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
static const std::string CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
static const std::string CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
static const std::string CONST_CAMERA_FILENAME
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
double c56
Mechanical coupling between joint 5 and joint 6.
vpHomogeneousMatrix eMc
End effector to camera transformation.
XML parser to load and save intrinsic camera parameters.
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, bool verbose=true)