36 #include <visp3/core/vpConfig.h>
38 #ifdef VISP_HAVE_AFMA6
42 #include <sys/types.h>
45 #include <visp3/core/vpDebug.h>
46 #include <visp3/core/vpExponentialMap.h>
47 #include <visp3/core/vpIoTools.h>
48 #include <visp3/core/vpRotationMatrix.h>
49 #include <visp3/core/vpThetaUVector.h>
50 #include <visp3/core/vpVelocityTwistMatrix.h>
51 #include <visp3/robot/vpRobotAfma6.h>
52 #include <visp3/robot/vpRobotException.h>
59 bool vpRobotAfma6::robotAlreadyCreated =
false;
81 void emergencyStopAfma6(
int signo)
83 std::cout <<
"Stop the Afma6 application by signal (" << signo <<
"): " << (char)7;
86 std::cout <<
"SIGINT (stop by ^C) " << std::endl;
89 std::cout <<
"SIGBUS (stop due to a bus error) " << std::endl;
92 std::cout <<
"SIGSEGV (stop due to a segmentation fault) " << std::endl;
95 std::cout <<
"SIGKILL (stop by CTRL \\) " << std::endl;
98 std::cout <<
"SIGQUIT " << std::endl;
101 std::cout << signo << std::endl;
105 PrimitiveSTOP_Afma6();
106 std::cout <<
"Robot was stopped\n";
111 fprintf(stdout,
"Application ");
113 kill(getpid(), SIGKILL);
179 signal(SIGINT, emergencyStopAfma6);
180 signal(SIGBUS, emergencyStopAfma6);
181 signal(SIGSEGV, emergencyStopAfma6);
182 signal(SIGKILL, emergencyStopAfma6);
183 signal(SIGQUIT, emergencyStopAfma6);
187 std::cout <<
"Open communication with MotionBlox.\n";
198 vpRobotAfma6::robotAlreadyCreated =
true;
233 time_prev_getvel = 0;
234 first_time_getvel =
true;
239 first_time_getdis =
true;
242 Try(InitializeConnection(
verbose_));
245 Try(InitializeNode_Afma6());
247 Try(PrimitiveRESET_Afma6());
253 UInt32 HIPowerStatus;
255 Try(PrimitiveSTATUS_Afma6(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
260 std::cout <<
"Robot status: ";
261 switch (EStopStatus) {
264 if (HIPowerStatus == 0)
265 std::cout <<
"Power is OFF" << std::endl;
267 std::cout <<
"Power is ON" << std::endl;
269 case ESTOP_ACTIVATED:
270 std::cout <<
"Emergency stop is activated" << std::endl;
273 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
274 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
277 std::cout << std::endl;
291 if (TryStt == -20001)
292 printf(
"No connection detected. Check if the robot is powered on \n"
293 "and if the firewire link exist between the MotionBlox and this "
295 else if (TryStt == -675)
296 printf(
" Timeout enabling power...\n");
300 PrimitivePOWEROFF_Afma6();
302 ShutDownConnection();
304 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
359 for (
unsigned int i = 0; i < 3; i++) {
360 eMc_pose[i] =
_etc[i];
361 eMc_pose[i + 3] =
_erc[i];
364 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
398 for (
unsigned int i = 0; i < 3; i++) {
399 eMc_pose[i] =
_etc[i];
400 eMc_pose[i + 3] =
_erc[i];
403 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
460 for (
unsigned int i = 0; i < 3; i++) {
461 eMc_pose[i] =
_etc[i];
462 eMc_pose[i + 3] =
_erc[i];
465 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
542 for (
unsigned int i = 0; i < 3; i++) {
543 eMc_pose[i] =
_etc[i];
544 eMc_pose[i + 3] =
_erc[i];
547 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
574 UInt32 HIPowerStatus;
575 Try(PrimitiveSTATUS_Afma6(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
586 ShutDownConnection();
588 vpRobotAfma6::robotAlreadyCreated =
false;
607 Try(PrimitiveSTOP_Afma6());
613 std::cout <<
"Change the control mode from velocity to position control.\n";
614 Try(PrimitiveSTOP_Afma6());
625 std::cout <<
"Change the control mode from stop to velocity control.\n";
653 Try(PrimitiveSTOP_Afma6());
658 vpERROR_TRACE(
"Cannot stop robot motion");
677 UInt32 HIPowerStatus;
679 bool firsttime =
true;
680 unsigned int nitermax = 10;
682 for (
unsigned int i = 0; i < nitermax; i++) {
683 Try(PrimitiveSTATUS_Afma6(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
684 if (EStopStatus == ESTOP_AUTO) {
687 else if (EStopStatus == ESTOP_MANUAL) {
690 else if (EStopStatus == ESTOP_ACTIVATED) {
692 std::cout <<
"Emergency stop is activated! \n"
693 <<
"Check the emergency stop button and push the yellow "
694 "button before continuing."
698 fprintf(stdout,
"Remaining time %us \r", nitermax - i);
703 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
704 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
706 ShutDownConnection();
711 if (EStopStatus == ESTOP_ACTIVATED)
712 std::cout << std::endl;
714 if (EStopStatus == ESTOP_ACTIVATED) {
715 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
719 if (HIPowerStatus == 0) {
720 fprintf(stdout,
"Power ON the Afma6 robot\n");
723 Try(PrimitivePOWERON_Afma6());
728 vpERROR_TRACE(
"Cannot power on the robot");
747 UInt32 HIPowerStatus;
748 Try(PrimitiveSTATUS_Afma6(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
751 if (HIPowerStatus == 1) {
752 fprintf(stdout,
"Power OFF the Afma6 robot\n");
755 Try(PrimitivePOWEROFF_Afma6());
760 vpERROR_TRACE(
"Cannot power off the robot");
781 UInt32 HIPowerStatus;
782 Try(PrimitiveSTATUS_Afma6(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
785 if (HIPowerStatus == 1) {
791 vpERROR_TRACE(
"Cannot get the power status");
843 Try(PrimitiveACQ_POS_Afma6(position, ×tamp));
847 for (
unsigned int i = 0; i <
njoint; i++)
854 vpERROR_TRACE(
"catch exception ");
888 Try(PrimitiveACQ_POS_Afma6(position, ×tamp));
892 for (
unsigned int i = 0; i <
njoint; i++)
899 vpERROR_TRACE(
"Error caught");
1028 for (
unsigned int i = 0; i < 3; i++) {
1029 position[i] = pose[i];
1030 position[i + 3] = rxyz[i];
1034 "Joint frame not implemented for pose positioning.");
1128 vpERROR_TRACE(
"Robot was not in position-based control\n"
1129 "Modification of the robot state");
1133 double _destination[6];
1141 Try(PrimitiveACQ_POS_Afma6(_q, ×tamp));
1144 for (
unsigned int i = 0; i <
njoint; i++)
1154 for (
unsigned int i = 0; i < 3; i++) {
1155 txyz[i] = position[i];
1156 rxyz[i] = position[i + 3];
1167 bool nearest =
true;
1170 for (
unsigned int i = 0; i <
njoint; i++) {
1171 _destination[i] = q[i];
1173 Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity));
1174 Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000));
1184 for (
unsigned int i = 0; i <
njoint; i++) {
1185 _destination[i] = position[i];
1187 Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity));
1188 Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000));
1195 for (
unsigned int i = 0; i < 3; i++) {
1196 txyz[i] = position[i];
1197 rxyz[i] = position[i + 3];
1205 bool nearest =
true;
1208 for (
unsigned int i = 0; i <
njoint; i++) {
1209 _destination[i] = q[i];
1211 Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity));
1212 Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000));
1223 "Mixt frame not implemented.");
1227 "end-effector frame not implemented.");
1232 if (TryStt == InvalidPosition || TryStt == -1023)
1233 std::cout <<
" : Position out of range.\n";
1234 else if (TryStt < 0)
1235 std::cout <<
" : Unknown error (see Fabien).\n";
1236 else if (error == -1)
1237 std::cout <<
"Position out of range.\n";
1239 if (TryStt < 0 || error < 0) {
1240 vpERROR_TRACE(
"Positioning error.");
1318 double pos4,
double pos5,
double pos6)
1332 vpERROR_TRACE(
"Error caught");
1389 vpERROR_TRACE(
"Bad position in \"%s\"", filename.c_str());
1464 Try(PrimitiveACQ_POS_Afma6(_q, ×tamp));
1465 for (
unsigned int i = 0; i <
njoint; i++) {
1466 position[i] = _q[i];
1473 Try(PrimitiveACQ_POS_Afma6(_q, ×tamp));
1476 for (
unsigned int i = 0; i <
njoint; i++)
1489 for (
unsigned int i = 0; i < 3; i++) {
1490 position[i] = fMc[i][3];
1491 position[i + 3] = rxyz[i];
1507 vpERROR_TRACE(
"Cannot get position.");
1520 PrimitiveACQ_TIME_Afma6(×tamp);
1555 for (
unsigned int j = 0; j < 3; j++)
1556 RxyzVect[j] = posRxyz[j + 3];
1561 for (
unsigned int j = 0; j < 3; j++) {
1562 position[j] = posRxyz[j];
1563 position[j + 3] = RtuVect[j];
1649 vpERROR_TRACE(
"Cannot send a velocity to the robot "
1650 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1652 "Cannot send a velocity to the robot "
1653 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1658 for (
unsigned int i = 0; i < 3; i++)
1660 for (
unsigned int i = 3; i < 6; i++)
1669 Try(PrimitiveMOVESPEED_CART_Afma6(vel_sat.
data, REPCAM_AFMA6));
1679 Try(PrimitiveMOVESPEED_CART_Afma6(v_c.
data, REPCAM_AFMA6));
1684 Try(PrimitiveMOVESPEED_Afma6(vel_sat.
data));
1688 Try(PrimitiveMOVESPEED_CART_Afma6(vel_sat.
data, REPFIX_AFMA6));
1692 Try(PrimitiveMOVESPEED_CART_Afma6(vel_sat.
data, REPMIX_AFMA6));
1696 vpERROR_TRACE(
"Error in spec of vpRobot. "
1697 "Case not taken in account.");
1704 if (TryStt == VelStopOnJoint) {
1705 Int32 axisInJoint[
njoint];
1706 PrimitiveSTATUS_Afma6(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, axisInJoint,
nullptr);
1707 for (
unsigned int i = 0; i <
njoint; i++) {
1709 std::cout <<
"\nWarning: Velocity control stopped: axis " << i + 1 <<
" on joint limit!" << std::endl;
1713 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1714 if (TryString !=
nullptr) {
1716 printf(
" Error sentence %s\n", TryString);
1794 Try(PrimitiveACQ_POS_Afma6(q, ×tamp));
1795 time_cur = timestamp;
1796 for (
unsigned int i = 0; i <
njoint; i++) {
1803 if (!first_time_getvel) {
1808 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1817 velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1823 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1838 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1846 for (
unsigned int i = 0; i < 3; i++) {
1848 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1850 velocity[i + 3] = thetaU[i];
1854 velocity /= (time_cur - time_prev_getvel);
1859 "vpRobotAfma6::getVelocity() not implemented in end-effector"));
1864 first_time_getvel =
false;
1868 fMc_prev_getvel = fMc_cur;
1871 q_prev_getvel = q_cur;
1874 time_prev_getvel = time_cur;
1878 vpERROR_TRACE(
"Cannot get velocity.");
2014 std::ifstream fd(filename.c_str(), std::ios::in);
2016 if (!fd.is_open()) {
2021 std::string key(
"R:");
2022 std::string id(
"#AFMA6 - Position");
2023 bool pos_found =
false;
2028 while (std::getline(fd, line)) {
2031 if (!(line.compare(0,
id.size(),
id) == 0)) {
2032 std::cout <<
"Error: this position file " << filename <<
" is not for Afma6 robot" << std::endl;
2036 if ((line.compare(0, 1,
"#") == 0)) {
2039 if ((line.compare(0, key.size(), key) == 0)) {
2042 if (chain.size() <
njoint + 1)
2044 if (chain.size() <
njoint + 1)
2047 std::istringstream ss(line);
2050 for (
unsigned int i = 0; i <
njoint; i++)
2065 std::cout <<
"Error: unable to find a position for Afma6 robot in " << filename << std::endl;
2100 fd = fopen(filename.c_str(),
"w");
2105 #AFMA6 - Position - Version 2.01\n\
2108 # Joint position: X, Y, Z: translations in meters\n\
2109 # A, B, C: rotations in degrees\n\
2172 Try(PrimitiveGripper_Afma6(1));
2173 std::cout <<
"Open the gripper..." << std::endl;
2176 vpERROR_TRACE(
"Cannot open the gripper");
2191 Try(PrimitiveGripper_Afma6(0));
2192 std::cout <<
"Close the gripper..." << std::endl;
2195 vpERROR_TRACE(
"Cannot close the gripper");
2231 Try(PrimitiveACQ_POS_Afma6(q, ×tamp));
2232 for (
unsigned int i = 0; i <
njoint; i++) {
2239 if (!first_time_getdis) {
2243 c_prevMc_cur = fMc_prev_getdis.
inverse() * fMc_cur;
2253 for (
unsigned int i = 0; i < 3; i++) {
2254 displacement[i] = t[i];
2255 displacement[i + 3] = rxyz[i];
2261 displacement = q_cur - q_prev_getdis;
2266 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2271 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2275 std::cout <<
"getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2281 first_time_getdis =
false;
2285 q_prev_getdis = q_cur;
2288 fMc_prev_getdis = fMc_cur;
2292 vpERROR_TRACE(
"Cannot get velocity.");
2309 Int32 axisInJoint[
njoint];
2314 Try(PrimitiveSTATUS_Afma6(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, axisInJoint,
nullptr));
2315 for (
unsigned int i = 0; i <
njoint; i++) {
2316 if (axisInJoint[i]) {
2317 std::cout <<
"\nWarning: Velocity control stopped: axis " << i + 1 <<
" on joint limit!" << std::endl;
2318 jointsStatus[i] = axisInJoint[i];
2322 jointsStatus[i] = 0;
2328 vpERROR_TRACE(
"Cannot check joint limits.");
2335 #elif !defined(VISP_BUILD_SHARED_LIBS)
2337 void dummy_vpRobotAfma6() { };
Modelization of Irisa's gantry robot named Afma6.
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
static const unsigned int njoint
Number of joint.
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
void get_cMe(vpHomogeneousMatrix &cMe) const
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
vpCameraParameters::vpCameraParametersProjType projModel
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Type * data
Address of the first element of the data array.
vpCameraParametersProjType
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
error that can be emitted by ViSP classes.
@ functionNotImplementedError
Function not implemented.
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
static double rad(double deg)
static double deg(double rad)
Implementation of a matrix and operations on matrices.
Implementation of a pose vector and operations on poses.
void get_cVe(vpVelocityTwistMatrix &_cVe) const
bool checkJointLimits(vpColVector &jointsStatus)
void get_eJe(vpMatrix &_eJe) VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpPoseVector &pose)
void get_fJe(vpMatrix &_fJe) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
static const double defaultPositioningVelocity
void get_cMe(vpHomogeneousMatrix &_cMe) const
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double getPositioningVelocity(void)
void set_eMc(const vpHomogeneousMatrix &eMc)
virtual ~vpRobotAfma6(void)
void move(const std::string &filename)
void setPositioningVelocity(double velocity)
static bool readPosFile(const std::string &filename, vpColVector &q)
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ constructionError
Error from constructor.
@ positionOutOfRangeError
Position is out of range.
@ lowLevelError
Error thrown by the low level sdk.
Class that defines a generic virtual robot.
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
void setVerbose(bool verbose)
virtual vpRobotStateType getRobotState(void) const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
@ STATE_POSITION_CONTROL
Initialize the position controller.
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
double getMaxRotationVelocity(void) const
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
double getMaxTranslationVelocity(void) const
Implementation of a rotation matrix and operations on such kind of matrices.
vpRotationMatrix & buildFrom(const vpHomogeneousMatrix &M)
Implementation of a rotation vector as Euler angle minimal representation.
vpRxyzVector & buildFrom(const vpRotationMatrix &R)
Implementation of a rotation vector as axis-angle minimal representation.
vpThetaUVector & buildFrom(const vpHomogeneousMatrix &M)
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)