38 #include <visp3/core/vpConfig.h>
40 #ifdef VISP_HAVE_AFMA6
44 #include <sys/types.h>
47 #include <visp3/core/vpExponentialMap.h>
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpVelocityTwistMatrix.h>
50 #include <visp3/core/vpThetaUVector.h>
51 #include <visp3/core/vpIoTools.h>
52 #include <visp3/core/vpRotationMatrix.h>
53 #include <visp3/robot/vpRobotAfma6.h>
54 #include <visp3/robot/vpRobotException.h>
60 bool vpRobotAfma6::robotAlreadyCreated =
false;
82 void emergencyStopAfma6(
int signo)
84 std::cout <<
"Stop the Afma6 application by signal ("
85 << signo <<
"): " << (char)7 ;
89 std::cout <<
"SIGINT (stop by ^C) " << std::endl ; break ;
91 std::cout <<
"SIGBUS (stop due to a bus error) " << std::endl ; break ;
93 std::cout <<
"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
95 std::cout <<
"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
97 std::cout <<
"SIGQUIT " << std::endl ; break ;
99 std::cout << signo << std::endl ;
103 PrimitiveSTOP_Afma6();
104 std::cout <<
"Robot was stopped\n";
109 fprintf(stdout,
"Application ");
111 kill(getpid(), SIGKILL);
155 vpRobotAfma6::vpRobotAfma6 (
bool verbose)
180 signal(SIGINT, emergencyStopAfma6);
181 signal(SIGBUS, emergencyStopAfma6) ;
182 signal(SIGSEGV, emergencyStopAfma6) ;
183 signal(SIGKILL, emergencyStopAfma6);
184 signal(SIGQUIT, emergencyStopAfma6);
188 std::cout <<
"Open communication with MotionBlox.\n";
199 vpRobotAfma6::robotAlreadyCreated =
true;
236 time_prev_getvel = 0;
237 first_time_getvel =
true;
242 first_time_getdis =
true;
245 Try( InitializeConnection(
verbose_) );
248 Try( InitializeNode_Afma6() );
250 Try( PrimitiveRESET_Afma6() );
256 UInt32 HIPowerStatus;
258 Try( PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
264 std::cout <<
"Robot status: ";
265 switch(EStopStatus) {
268 if (HIPowerStatus == 0)
269 std::cout <<
"Power is OFF" << std::endl;
271 std::cout <<
"Power is ON" << std::endl;
273 case ESTOP_ACTIVATED:
274 std::cout <<
"Emergency stop is activated" << std::endl;
277 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
278 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
281 std::cout << std::endl;
294 if (TryStt == -20001)
295 printf(
"No connection detected. Check if the robot is powered on \n"
296 "and if the firewire link exist between the MotionBlox and this computer.\n");
297 else if (TryStt == -675)
298 printf(
" Timeout enabling power...\n");
302 PrimitivePOWEROFF_Afma6();
304 ShutDownConnection();
306 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
308 "Cannot open connection with the motionblox");
364 for (
unsigned int i=0; i < 3; i ++) {
365 eMc_pose[i] =
_etc[i];
366 eMc_pose[i+3] =
_erc[i];
369 Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
403 for (
unsigned int i=0; i < 3; i ++) {
404 eMc_pose[i] =
_etc[i];
405 eMc_pose[i+3] =
_erc[i];
408 Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
462 for (
unsigned int i=0; i < 3; i ++) {
463 eMc_pose[i] =
_etc[i];
464 eMc_pose[i+3] =
_erc[i];
467 Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
541 for (
unsigned int i=0; i < 3; i ++) {
542 eMc_pose[i] =
_etc[i];
543 eMc_pose[i+3] =
_erc[i];
546 Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
573 UInt32 HIPowerStatus;
574 Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
586 ShutDownConnection();
588 vpRobotAfma6::robotAlreadyCreated =
false;
611 Try( PrimitiveSTOP_Afma6() );
617 std::cout <<
"Change the control mode from velocity to position control.\n";
618 Try( PrimitiveSTOP_Afma6() );
628 std::cout <<
"Change the control mode from stop to velocity control.\n";
658 Try( PrimitiveSTOP_Afma6() );
665 "Cannot stop robot motion.");
684 UInt32 HIPowerStatus;
686 bool firsttime =
true;
687 unsigned int nitermax = 10;
689 for (
unsigned int i=0; i<nitermax; i++) {
690 Try( PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
692 if (EStopStatus == ESTOP_AUTO) {
695 else if (EStopStatus == ESTOP_MANUAL) {
698 else if (EStopStatus == ESTOP_ACTIVATED) {
700 std::cout <<
"Emergency stop is activated! \n"
701 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
704 fprintf(stdout,
"Remaining time %us \r", nitermax-i);
709 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
710 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
712 ShutDownConnection();
717 if (EStopStatus == ESTOP_ACTIVATED)
718 std::cout << std::endl;
720 if (EStopStatus == ESTOP_ACTIVATED) {
721 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
723 "Cannot power on the robot.");
726 if (HIPowerStatus == 0) {
727 fprintf(stdout,
"Power ON the Afma6 robot\n");
730 Try( PrimitivePOWERON_Afma6() );
737 "Cannot power off the robot.");
756 UInt32 HIPowerStatus;
757 Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
761 if (HIPowerStatus == 1) {
762 fprintf(stdout,
"Power OFF the Afma6 robot\n");
765 Try( PrimitivePOWEROFF_Afma6() );
772 "Cannot power off the robot.");
793 UInt32 HIPowerStatus;
794 Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
798 if (HIPowerStatus == 1) {
806 "Cannot get the power status.");
864 Try( PrimitiveACQ_POS_Afma6(position, ×tamp) );
868 for (
unsigned int i=0; i <
njoint; i++)
912 Try( PrimitiveACQ_POS_Afma6(position, ×tamp) );
916 for (
unsigned int i=0; i <
njoint; i++)
961 positioningVelocity = velocity;
972 return positioningVelocity;
1061 for (
unsigned int i=0; i < 3; i++) {
1062 position[i] = pose[i];
1063 position[i+3] = rxyz[i];
1067 "Positionning error: "
1068 "Joint frame not implemented for pose positionning.");
1162 "Modification of the robot state");
1166 double _destination[6];
1174 Try( PrimitiveACQ_POS_Afma6(_q, ×tamp) );
1177 for (
unsigned int i=0; i <
njoint; i++)
1187 for (
unsigned int i=0; i < 3; i++) {
1188 txyz[i] = position[i];
1189 rxyz[i] = position[i+3];
1200 bool nearest =
true;
1203 for (
unsigned int i=0; i <
njoint; i ++) {
1204 _destination[i] = q[i];
1206 Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1207 Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1217 for (
unsigned int i=0; i <
njoint; i ++) {
1218 _destination[i] = position[i];
1220 Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1221 Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1229 for (
unsigned int i=0; i < 3; i++) {
1230 txyz[i] = position[i];
1231 rxyz[i] = position[i+3];
1239 bool nearest =
true;
1242 for (
unsigned int i=0; i <
njoint; i ++) {
1243 _destination[i] = q[i];
1245 Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1246 Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1257 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1259 "Positionning error: "
1260 "Mixt frame not implemented.");
1265 if (TryStt == InvalidPosition || TryStt == -1023)
1266 std::cout <<
" : Position out of range.\n";
1267 else if (TryStt < 0)
1268 std::cout <<
" : Unknown error (see Fabien).\n";
1269 else if (error == -1)
1270 std::cout <<
"Position out of range.\n";
1272 if (TryStt < 0 || error < 0) {
1275 "Position out of range.");
1358 position[0] = pos1 ;
1359 position[1] = pos2 ;
1360 position[2] = pos3 ;
1361 position[3] = pos4 ;
1362 position[4] = pos5 ;
1363 position[5] = pos6 ;
1425 "Bad position in filename.");
1500 Try( PrimitiveACQ_POS_Afma6(_q, ×tamp) );
1501 for (
unsigned int i=0; i <
njoint; i ++) {
1502 position[i] = _q[i];
1509 Try( PrimitiveACQ_POS_Afma6(_q, ×tamp) );
1512 for (
unsigned int i=0; i <
njoint; i++)
1525 for (
unsigned int i=0; i < 3; i++) {
1526 position[i] = fMc[i][3];
1527 position[i+3] = rxyz[i];
1532 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1534 "Cannot get position in mixt frame: "
1543 "Cannot get position.");
1554 PrimitiveACQ_TIME_Afma6(×tamp);
1590 for(
unsigned int j=0;j<3;j++)
1591 RxyzVect[j]=posRxyz[j+3];
1596 for(
unsigned int j=0;j<3;j++)
1598 position[j]=posRxyz[j];
1599 position[j+3]=RtuVect[j];
1680 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1682 "Cannot send a velocity to the robot "
1683 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1688 for (
unsigned int i=0; i<3; i++)
1690 for (
unsigned int i=3; i<6; i++)
1699 Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.
data, REPCAM_AFMA6) );
1704 Try( PrimitiveMOVESPEED_Afma6(vel_sat.
data) );
1708 Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.
data, REPFIX_AFMA6) );
1712 Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.
data, REPMIX_AFMA6) );
1717 "Case not taken in account.");
1724 if (TryStt == VelStopOnJoint) {
1725 Int32 axisInJoint[
njoint];
1726 PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1727 for (
unsigned int i=0; i <
njoint; i ++) {
1729 std::cout <<
"\nWarning: Velocity control stopped: axis "
1730 << i+1 <<
" on joint limit!" <<std::endl;
1734 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1735 if (TryString != NULL) {
1737 printf(
" Error sentence %s\n", TryString);
1823 Try( PrimitiveACQ_POS_Afma6(q, ×tamp) );
1824 time_cur = timestamp;
1825 for (
unsigned int i=0; i <
njoint; i ++) {
1832 if ( ! first_time_getvel ) {
1837 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1846 velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1852 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1867 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1875 for (
unsigned int i=0; i < 3; i++) {
1877 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1879 velocity[i+3] = thetaU[i];
1883 velocity /= (time_cur - time_prev_getvel);
1889 first_time_getvel =
false;
1893 fMc_prev_getvel = fMc_cur;
1896 q_prev_getvel = q_cur;
1899 time_prev_getvel = time_cur;
1906 "Cannot get velocity.");
2044 std::ifstream fd(filename.c_str(), std::ios::in);
2046 if(! fd.is_open()) {
2051 std::string key(
"R:");
2052 std::string id(
"#AFMA6 - Position");
2053 bool pos_found =
false;
2058 while(std::getline(fd, line)) {
2061 if(! (line.compare(0,
id.size(), id) == 0)) {
2062 std::cout <<
"Error: this position file " << filename <<
" is not for Afma6 robot" << std::endl;
2066 if((line.compare(0, 1,
"#") == 0)) {
2069 if((line.compare(0, key.size(), key) == 0)) {
2072 if (chain.size() <
njoint+1)
2074 if(chain.size() <
njoint+1)
2077 std::istringstream ss(line);
2080 for (
unsigned int i=0; i<
njoint; i++)
2095 std::cout <<
"Error: unable to find a position for Afma6 robot in " << filename << std::endl;
2131 fd = fopen(filename.c_str(),
"w") ;
2136 #AFMA6 - Position - Version 2.01\n\
2139 # Joint position: X, Y, Z: translations in meters\n\
2140 # A, B, C: rotations in degrees\n\
2145 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2211 Try( PrimitiveGripper_Afma6(1) );
2212 std::cout <<
"Open the gripper..." << std::endl;
2217 "Cannot open the gripper.");
2232 Try( PrimitiveGripper_Afma6(0) );
2233 std::cout <<
"Close the gripper..." << std::endl;
2238 "Cannot close the gripper.");
2256 vpRobotAfma6::getCameraDisplacement(
vpColVector &displacement)
2272 vpRobotAfma6::getArticularDisplacement(
vpColVector &displacement)
2312 Try( PrimitiveACQ_POS_Afma6(q, ×tamp) );
2313 for (
unsigned int i=0; i <
njoint; i ++) {
2320 if ( ! first_time_getdis ) {
2324 c_prevMc_cur = fMc_prev_getdis.
inverse() * fMc_cur;
2334 for (
unsigned int i=0; i<3; i++) {
2335 displacement[i] = t[i];
2336 displacement[i+3] = rxyz[i];
2342 displacement = q_cur - q_prev_getdis;
2347 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2352 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2358 first_time_getdis =
false;
2362 q_prev_getdis = q_cur;
2365 fMc_prev_getdis = fMc_cur;
2371 "Cannot get velocity.");
2388 Int32 axisInJoint[
njoint];
2393 Try (PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint,
2395 for (
unsigned int i=0; i <
njoint; i ++) {
2396 if (axisInJoint[i]){
2397 std::cout <<
"\nWarning: Velocity control stopped: axis "
2398 << i+1 <<
" on joint limit!" <<std::endl;
2399 jointsStatus[i] = axisInJoint[i];
2403 jointsStatus[i] = 0;
2411 "Cannot check joint limits.");
2418 #elif !defined(VISP_BUILD_SHARED_LIBS)
2420 void dummy_vpRobotAfma6() {};
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Modelisation of Irisa's gantry robot named Afma6.
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of a matrix and operations on matrices.
vpRxyzVector buildFrom(const vpRotationMatrix &R)
bool checkJointLimits(vpColVector &jointsStatus)
static const unsigned int njoint
Number of joint.
void get_eJe(vpMatrix &_eJe)
Error that can be emited by the vpRobot class and its derivates.
void set_eMc(const vpHomogeneousMatrix &eMc)
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
void setPosition(const vpRobot::vpControlFrameType frame, const vpPoseVector &pose)
double getMaxTranslationVelocity(void) const
Initialize the position controller.
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Class that defines a generic virtual robot.
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Type * data
Address of the first element of the data array.
double getPositioningVelocity(void)
double getMaxRotationVelocity(void) const
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual ~vpRobotAfma6(void)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setPositioningVelocity(const double velocity)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Implementation of a rotation matrix and operations on such kind of matrices.
void get_cMe(vpHomogeneousMatrix &_cMe) const
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
static bool readPosFile(const std::string &filename, vpColVector &q)
static bool savePosFile(const std::string &filename, const vpColVector &q)
Initialize the velocity controller.
void move(const std::string &filename)
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M)
vpCameraParametersProjType
void get_cMe(vpHomogeneousMatrix &cMe) const
void get_fJe(vpMatrix &_fJe)
void extract(vpRotationMatrix &R) const
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Implementation of a velocity twist matrix and operations on such kind of matrices.
static double rad(double deg)
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
static double deg(double rad)
Implementation of column vector and the associated operations.
Implementation of a pose vector and operations on poses.
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Implementation of a rotation vector as Euler angle minimal representation.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
static const double defaultPositioningVelocity
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void resize(const unsigned int i, const bool flagNullify=true)
void get_cVe(vpVelocityTwistMatrix &_cVe) const