51 #include <visp/vpDebug.h>
52 #include <visp/vpVelocityTwistMatrix.h>
53 #include <visp/vpRobotException.h>
54 #include <visp/vpXmlParserCamera.h>
55 #include <visp/vpCameraParameters.h>
56 #include <visp/vpRxyzVector.h>
57 #include <visp/vpTranslationVector.h>
58 #include <visp/vpRotationMatrix.h>
59 #include <visp/vpAfma6.h>
65 #ifdef VISP_HAVE_ACCESS_TO_NAS
66 static const char *opt_Afma6[] = {
"JOINT_MAX",
"JOINT_MIN",
"LONG_56",
"COUPL_56",
67 "CAMERA",
"eMc_ROT_XYZ",
"eMc_TRANS_XYZ",
72 =
"Z:/robot/Afma6/current/include/const_Afma6.cnf";
74 =
"/udd/fspindle/robot/Afma6/current/include/const_Afma6.cnf";
79 =
"Z:/robot/Afma6/current/include/const_eMc_ccmop_without_distortion_Afma6.cnf";
81 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_without_distortion_Afma6.cnf";
86 =
"Z:/robot/Afma6/current/include/const_eMc_ccmop_with_distortion_Afma6.cnf";
88 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_with_distortion_Afma6.cnf";
93 =
"Z:/robot/Afma6/current/include/const_eMc_gripper_without_distortion_Afma6.cnf";
95 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_without_distortion_Afma6.cnf";
100 =
"Z:/robot/Afma6/current/include/const_eMc_gripper_with_distortion_Afma6.cnf";
102 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_with_distortion_Afma6.cnf";
107 =
"Z:/robot/Afma6/current/include/const_eMc_vacuum_without_distortion_Afma6.cnf";
109 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_without_distortion_Afma6.cnf";
114 =
"Z:/robot/Afma6/current/include/const_eMc_vacuum_with_distortion_Afma6.cnf";
116 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_with_distortion_Afma6.cnf";
121 =
"Z:/robot/Afma6/current/include/const_eMc_generic_without_distortion_Afma6.cnf";
123 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_without_distortion_Afma6.cnf";
128 =
"Z:/robot/Afma6/current/include/const_eMc_generic_with_distortion_Afma6.cnf";
130 =
"/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_with_distortion_Afma6.cnf";
135 =
"Z:/robot/Afma6/current/include/const_camera_Afma6.xml";
137 =
"/udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml";
140 #endif // VISP_HAVE_ACCESS_TO_NAS
157 : _coupl_56(0), _long_56(0), _etc(), _erc(), _eMc(),
158 tool_current(
vpAfma6::defaultTool),
219 #ifdef VISP_HAVE_ACCESS_TO_NAS
222 const char * paramCamera)
253 #ifdef VISP_HAVE_ACCESS_TO_NAS
255 char filename_eMc [FILENAME_MAX];
260 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
261 snprintf(filename_eMc, FILENAME_MAX,
"%s",
264 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
269 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
270 snprintf(filename_eMc, FILENAME_MAX,
"%s",
273 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
283 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
284 snprintf(filename_eMc, FILENAME_MAX,
"%s",
287 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
292 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
293 snprintf(filename_eMc, FILENAME_MAX,
"%s",
296 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
306 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
307 snprintf(filename_eMc, FILENAME_MAX,
"%s",
310 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
315 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
316 snprintf(filename_eMc, FILENAME_MAX,
"%s",
319 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
329 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
330 snprintf(filename_eMc, FILENAME_MAX,
"%s",
333 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
338 #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
339 snprintf(filename_eMc, FILENAME_MAX,
"%s",
342 _snprintf(filename_eMc, FILENAME_MAX,
"%s",
365 #else // VISP_HAVE_ACCESS_TO_NAS
450 #endif // VISP_HAVE_ACCESS_TO_NAS
565 vpColVector & q,
const bool &nearest,
const bool &verbose)
const
568 double q_[2][6],d[2],t;
593 if (fMe[2][2] >= .99999f)
596 q_[0][4] = q_[1][4] = M_PI/2.f;
597 t = atan2(fMe[0][0],fMe[0][1]);
598 q_[1][3] = q_[0][3] = q[3];
599 q_[1][5] = q_[0][5] = t - q_[0][3];
613 else if (fMe[2][2] <= -.99999)
616 q_[0][4] = q_[1][4] = -M_PI/2;
617 t = atan2(fMe[1][1],fMe[1][0]);
618 q_[1][3] = q_[0][3] = q[3];
619 q_[1][5] = q_[0][5] = q_[0][3] - t;
634 q_[0][3] = atan2(-fMe[0][2],fMe[1][2]);
635 if (q_[0][3] >= 0.0) q_[1][3] = q_[0][3] - M_PI;
636 else q_[1][3] = q_[0][3] + M_PI;
638 q_[0][4] = asin(fMe[2][2]);
639 if (q_[0][4] >= 0.0) q_[1][4] = M_PI - q_[0][4];
640 else q_[1][4] = -M_PI - q_[0][4];
642 q_[0][5] = atan2(-fMe[2][1],fMe[2][0]);
643 if (q_[0][5] >= 0.0) q_[1][5] = q_[0][5] - M_PI;
644 else q_[1][5] = q_[0][5] + M_PI;
646 q_[0][0] = fMe[0][3] - this->
_long_56*cos(q_[0][3]);
647 q_[1][0] = fMe[0][3] - this->
_long_56*cos(q_[1][3]);
648 q_[0][1] = fMe[1][3] - this->
_long_56*sin(q_[0][3]);
649 q_[1][1] = fMe[1][3] - this->
_long_56*sin(q_[1][3]);
650 q_[0][2] = q_[1][2] = fMe[2][3];
656 for (
int j=0;j<2;j++)
660 for (
unsigned int i=0;i<6;i++) {
664 std::cout <<
"Joint " << i <<
" not in limits: " << this->
_joint_min[i] <<
" < " << q_[j][i] <<
" < " << this->
_joint_max[i] << std::endl;
675 std::cout <<
"No solution..." << std::endl;
679 else if (ok[1] == 1) {
680 for (
unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
687 for (
unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
694 for (
int j=0;j<2;j++)
697 for (
unsigned int i=3;i<6;i++)
698 d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
703 for (
unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
705 for (
unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
710 for (
unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
712 for (
unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
716 for(
unsigned int i=0; i<6; i++)
782 fMc = fMe * this->
_eMc;
814 double q5 = q[5] - this->
_coupl_56 * q[4];
816 double c1 = cos(q[3]);
817 double s1 = sin(q[3]);
818 double c2 = cos(q[4]);
819 double s2 = sin(q[4]);
825 fMe[0][0] = s1*s2*c3 + c1*s3;
826 fMe[0][1] = -s1*s2*s3 + c1*c3;
830 fMe[1][0] = -c1*s2*c3 + s1*s3;
831 fMe[1][1] = c1*s2*s3 + s1*c3;
904 double s4,c4,s5,c5,s6,c6 ;
906 s4=sin(q[3]); c4=cos(q[3]);
907 s5=sin(q[4]); c5=cos(q[4]);
911 eJe[0][0] = s4*s5*c6+c4*s6;
912 eJe[0][1] = -c4*s5*c6+s4*s6;
916 eJe[1][0] = -s4*s5*s6+c4*c6;
917 eJe[1][1] = c4*s5*s6+s4*c6;
974 fJe[0][0] = fJe[1][1] = fJe[2][2] = 1 ;
976 double s4 = sin(q[3]) ;
977 double c4 = cos(q[3]) ;
985 double s5 = sin(q[4]) ;
986 double c5 = cos(q[4]) ;
988 fJe[3][4] = c4 ; fJe[3][5] = -s4*c5 ;
989 fJe[4][4] = s4 ; fJe[4][5] = c4*c5 ;
990 fJe[5][3] = 1 ; fJe[5][5] = s5 ;
1013 for (
unsigned int i=0; i < 6; i ++)
1030 for (
unsigned int i=0; i < 6; i ++)
1072 #ifdef VISP_HAVE_ACCESS_TO_NAS
1078 char Ligne[FILENAME_MAX];
1079 char namoption[100];
1083 double trans_eMc[3];
1084 bool get_rot_eMc =
false;
1085 bool get_trans_eMc =
false;
1088 if ((fdtask = fopen(filename,
"r" )) == NULL)
1093 "Impossible to read the config file.");
1096 while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
1098 if (
'#' == Ligne[0]) {
continue; }
1099 sscanf(Ligne,
"%s", namoption);
1100 dim = strlen(namoption);
1103 NULL != opt_Afma6[code];
1106 if (strncmp(opt_Afma6[code], namoption, dim) == 0)
1115 sscanf(Ligne,
"%s %lf %lf %lf %lf %lf %lf",
1123 sscanf(Ligne,
"%s %lf %lf %lf %lf %lf %lf", namoption,
1130 sscanf(Ligne,
"%s %lf", namoption, &this->
_long_56);
1134 sscanf(Ligne,
"%s %lf", namoption, &this->
_coupl_56);
1141 sscanf(Ligne,
"%s %lf %lf %lf", namoption,
1147 rot_eMc[0] *= M_PI / 180.0;
1148 rot_eMc[1] *= M_PI / 180.0;
1149 rot_eMc[2] *= M_PI / 180.0;
1154 sscanf(Ligne,
"%s %lf %lf %lf", namoption,
1158 get_trans_eMc =
true;
1163 "ligne #%d.", filename, numLn);
1170 if (get_rot_eMc && get_trans_eMc) {
1171 for (
unsigned int i=0; i < 3; i ++) {
1172 _erc[i] = rot_eMc[i];
1173 _etc[i] = trans_eMc[i];
1249 const unsigned int &image_width,
1250 const unsigned int &image_height)
const
1252 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
1256 std::cout <<
"Get camera parameters for camera \""
1258 <<
"from the XML file: \""
1260 if (parser.
parse(cam,
1266 "Impossible to read the camera parameters.");
1271 std::cout <<
"Get camera parameters for camera \""
1273 <<
"from the XML file: \""
1275 if (parser.
parse(cam,
1281 "Impossible to read the camera parameters.");
1286 std::cout <<
"Get camera parameters for camera \""
1288 <<
"from the XML file: \""
1290 if (parser.
parse(cam,
1296 "Impossible to read the camera parameters.");
1301 std::cout <<
"Get camera parameters for camera \""
1303 <<
"from the XML file: \""
1305 if (parser.
parse(cam,
1311 "Impossible to read the camera parameters.");
1326 "Impossible to read the camera parameters.");
1335 if (image_width == 640 && image_height == 480) {
1336 std::cout <<
"Get default camera parameters for camera \""
1348 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
1350 "Impossible to read the camera parameters.");
1356 if (image_width == 640 && image_height == 480) {
1357 std::cout <<
"Get default camera parameters for camera \""
1369 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
1371 "Impossible to read the camera parameters.");
1377 if (image_width == 640 && image_height == 480) {
1378 std::cout <<
"Get default camera parameters for camera \""
1390 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
1392 "Impossible to read the camera parameters.");
1398 if (image_width == 640 && image_height == 480) {
1399 std::cout <<
"Get default camera parameters for camera \""
1411 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
1413 "Impossible to read the camera parameters.");
1532 VISP_EXPORT std::ostream & operator << (std::ostream & os,
1540 <<
"Joint Max:" << std::endl
1547 <<
"\t" << std::endl
1549 <<
"Joint Min: " << std::endl
1556 <<
"\t" << std::endl
1558 <<
"Long 5-6: " << std::endl
1560 <<
"\t" << std::endl
1562 <<
"Coupling 5-6:" << std::endl
1564 <<
"\t" << std::endl
1566 <<
"eMc: "<< std::endl
1567 <<
"\tTranslation (m): "
1568 << afma6.
_eMc[0][3] <<
" "
1569 << afma6.
_eMc[1][3] <<
" "
1571 <<
"\t" << std::endl
1572 <<
"\tRotation Rxyz (rad) : "
1576 <<
"\t" << std::endl
1577 <<
"\tRotation Rxyz (deg) : "
1581 <<
"\t" << std::endl;
Modelisation of Irisa's gantry robot named Afma6.
Definition of the vpMatrix class.
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
static const unsigned int njoint
Number of joint.
void get_cVe(vpVelocityTwistMatrix &cVe) const
void resize(const unsigned int nrows, const unsigned int ncols, const bool nullify=true)
Error that can be emited by the vpRobot class and its derivates.
static const char *const CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
Perspective projection without distortion model.
static const char *const CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
unsigned int getWidth() const
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
vpAfma6ToolType getToolType() const
Get the current tool type.
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
void setIdentity()
Basic initialisation (identity)
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
vpCameraParameters::vpCameraParametersProjType projModel
static const char *const CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
XML parser to load and save intrinsic camera parameters.
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
static const char *const CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
static const char *const CONST_GRIPPER_CAMERA_NAME
The vpRotationMatrix considers the particular case of a rotation matrix.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
static const char *const CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
vpColVector getJointMin() const
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static const char *const CONST_CAMERA_AFMA6_FILENAME
vpCameraParametersProjType
void get_cMe(vpHomogeneousMatrix &cMe) const
static const char *const CONST_AFMA6_FILENAME
Generic class defining intrinsic camera parameters.
void parseConfigFile(const char *filename)
vpColVector getJointMax() const
void extract(vpRotationMatrix &R) const
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Construction from translation vector and rotation matrix.
static double rad(double deg)
int parse(vpCameraParameters &cam, const char *filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, const unsigned int image_width=0, const unsigned int image_height=0)
static double deg(double rad)
Class that provides a data structure for the column vectors as well as a set of operations on these v...
static const char *const CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
vpHomogeneousMatrix inverse() const
unsigned int getHeight() const
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
unsigned int getRows() const
Return the number of rows of the matrix.
static const char *const CONST_CCMOP_CAMERA_NAME
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
static const char *const CONST_VACUUM_CAMERA_NAME
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_EMC_GENERIC_WITH_DISTORTION_FILENAME
void resize(const unsigned int i, const bool flagNullify=true)
static const char *const CONST_GENERIC_CAMERA_NAME
double getCoupl56() const