36 #include <visp3/core/vpConfig.h>
38 #ifdef VISP_HAVE_VIPER850
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/vpThetaUVector.h>
49 #include <visp3/core/vpVelocityTwistMatrix.h>
50 #include <visp3/robot/vpRobot.h>
51 #include <visp3/robot/vpRobotException.h>
52 #include <visp3/robot/vpRobotViper850.h>
59 bool vpRobotViper850::m_robotAlreadyCreated =
false;
81 void emergencyStopViper850(
int signo)
83 std::cout <<
"Stop the Viper850 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_Viper850();
106 std::cout <<
"Robot was stopped\n";
111 fprintf(stdout,
"Application ");
113 kill(getpid(), SIGKILL);
200 signal(SIGINT, emergencyStopViper850);
201 signal(SIGBUS, emergencyStopViper850);
202 signal(SIGSEGV, emergencyStopViper850);
203 signal(SIGKILL, emergencyStopViper850);
204 signal(SIGQUIT, emergencyStopViper850);
208 std::cout <<
"Open communication with MotionBlox.\n";
221 vpRobotViper850::m_robotAlreadyCreated =
true;
259 m_q_prev_getvel.
resize(6);
261 m_time_prev_getvel = 0;
262 m_first_time_getvel =
true;
265 m_q_prev_getdis.
resize(6);
267 m_first_time_getdis =
true;
269 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
270 std::string calibfile;
271 #ifdef VISP_HAVE_VIPER850_DATA
272 calibfile = std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/ati/FT17824.cal");
277 "data to retrieve ATI F/T calib "
285 Try(InitializeConnection(
verbose_));
288 Try(InitializeNode_Viper850());
290 Try(PrimitiveRESET_Viper850());
293 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
299 UInt32 HIPowerStatus;
301 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
306 std::cout <<
"Robot status: ";
307 switch (EStopStatus) {
309 m_controlMode =
AUTO;
310 if (HIPowerStatus == 0)
311 std::cout <<
"Power is OFF" << std::endl;
313 std::cout <<
"Power is ON" << std::endl;
318 if (HIPowerStatus == 0)
319 std::cout <<
"Power is OFF" << std::endl;
321 std::cout <<
"Power is ON" << std::endl;
323 case ESTOP_ACTIVATED:
324 m_controlMode =
ESTOP;
325 std::cout <<
"Emergency stop is activated" << std::endl;
328 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
329 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
332 std::cout << std::endl;
350 if (TryStt == -20001)
351 printf(
"No connection detected. Check if the robot is powered on \n"
352 "and if the firewire link exist between the MotionBlox and this "
354 else if (TryStt == -675)
355 printf(
" Timeout enabling power...\n");
359 PrimitivePOWEROFF_Viper850();
361 ShutDownConnection();
363 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
451 for (
unsigned int i = 0; i < 3; i++) {
452 eMc_pose[i] =
etc[i];
453 eMc_pose[i + 3] =
erc[i];
456 Try(PrimitiveCONST_Viper850(eMc_pose));
535 for (
unsigned int i = 0; i < 3; i++) {
536 eMc_pose[i] =
etc[i];
537 eMc_pose[i + 3] =
erc[i];
540 Try(PrimitiveCONST_Viper850(eMc_pose));
605 for (
unsigned int i = 0; i < 3; i++) {
606 eMc_pose[i] =
etc[i];
607 eMc_pose[i + 3] =
erc[i];
610 Try(PrimitiveCONST_Viper850(eMc_pose));
635 for (
unsigned int i = 0; i < 3; i++) {
636 eMc_pose[i] =
etc[i];
637 eMc_pose[i + 3] =
erc[i];
640 Try(PrimitiveCONST_Viper850(eMc_pose));
667 for (
unsigned int i = 0; i < 3; i++) {
668 eMc_pose[i] =
etc[i];
669 eMc_pose[i + 3] =
erc[i];
672 Try(PrimitiveCONST_Viper850(eMc_pose));
691 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
700 UInt32 HIPowerStatus;
701 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
712 ShutDownConnection();
714 vpRobotViper850::m_robotAlreadyCreated =
false;
734 Try(PrimitiveSTOP_Viper850());
741 std::cout <<
"Change the control mode from velocity to position control.\n";
742 Try(PrimitiveSTOP_Viper850());
753 std::cout <<
"Change the control mode from stop to velocity control.\n";
784 Try(PrimitiveSTOP_Viper850());
789 vpERROR_TRACE(
"Cannot stop robot motion");
808 UInt32 HIPowerStatus;
810 bool firsttime =
true;
811 unsigned int nitermax = 10;
813 for (
unsigned int i = 0; i < nitermax; i++) {
814 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
815 if (EStopStatus == ESTOP_AUTO) {
816 m_controlMode =
AUTO;
819 else if (EStopStatus == ESTOP_MANUAL) {
823 else if (EStopStatus == ESTOP_ACTIVATED) {
824 m_controlMode =
ESTOP;
826 std::cout <<
"Emergency stop is activated! \n"
827 <<
"Check the emergency stop button and push the yellow "
828 "button before continuing."
832 fprintf(stdout,
"Remaining time %us \r", nitermax - i);
837 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
838 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
840 ShutDownConnection();
845 if (EStopStatus == ESTOP_ACTIVATED)
846 std::cout << std::endl;
848 if (EStopStatus == ESTOP_ACTIVATED) {
849 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
853 if (HIPowerStatus == 0) {
854 fprintf(stdout,
"Power ON the Viper850 robot\n");
857 Try(PrimitivePOWERON_Viper850());
862 vpERROR_TRACE(
"Cannot power on the robot");
881 UInt32 HIPowerStatus;
882 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
885 if (HIPowerStatus == 1) {
886 fprintf(stdout,
"Power OFF the Viper850 robot\n");
889 Try(PrimitivePOWEROFF_Viper850());
894 vpERROR_TRACE(
"Cannot power off the robot");
915 UInt32 HIPowerStatus;
916 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
919 if (HIPowerStatus == 1) {
925 vpERROR_TRACE(
"Cannot get the power status");
979 Try(PrimitiveACQ_POS_J_Viper850(position, ×tamp));
983 for (
unsigned int i = 0; i <
njoint; i++)
990 vpERROR_TRACE(
"catch exception ");
1013 Try(PrimitiveACQ_POS_Viper850(position, ×tamp));
1017 for (
unsigned int i = 0; i <
njoint; i++)
1024 vpERROR_TRACE(
"Error caught");
1162 vpERROR_TRACE(
"Robot was not in position-based control\n"
1163 "Modification of the robot state");
1175 Try(PrimitiveACQ_POS_Viper850(q.
data, ×tamp));
1187 for (
unsigned int i = 0; i < 3; i++) {
1188 txyz[i] = position[i];
1189 rxyz[i] = position[i + 3];
1205 Try(PrimitiveMOVE_J_Viper850(destination.
data, m_positioningVelocity));
1206 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1216 destination = position;
1222 Try(PrimitiveMOVE_J_Viper850(destination.
data, m_positioningVelocity));
1223 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1228 vpRxyzVector rxyz(position[3], position[4], position[5]);
1232 for (
unsigned int i = 0; i < 3; i++) {
1233 destination[i] = position[i];
1236 int configuration = 0;
1240 Try(PrimitiveMOVE_C_Viper850(destination.
data, configuration, m_positioningVelocity));
1241 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1247 "Mixt frame not implemented.");
1251 "End-effector frame not implemented.");
1256 if (TryStt == InvalidPosition || TryStt == -1023)
1257 std::cout <<
" : Position out of range.\n";
1258 else if (TryStt == -3019) {
1260 std::cout <<
" : Joint position out of range.\n";
1262 std::cout <<
" : Cartesian position leads to a joint position out of "
1265 else if (TryStt < 0)
1266 std::cout <<
" : Unknown error (see Fabien).\n";
1267 else if (error == -1)
1268 std::cout <<
"Position out of range.\n";
1270 if (TryStt < 0 || error < 0) {
1271 vpERROR_TRACE(
"Positioning error.");
1347 double pos4,
double pos5,
double pos6)
1361 vpERROR_TRACE(
"Error caught");
1416 vpERROR_TRACE(
"Bad position in \"%s\"", filename.c_str());
1507 Try(PrimitiveACQ_POS_J_Viper850(position.
data, ×tamp));
1515 Try(PrimitiveACQ_POS_J_Viper850(q.
data, ×tamp));
1526 for (
unsigned int i = 0; i < 3; i++) {
1527 position[i] = fMc[i][3];
1528 position[i + 3] = rxyz[i];
1545 vpERROR_TRACE(
"Cannot get position.");
1559 PrimitiveACQ_TIME_Viper850(×tamp);
1596 for (
unsigned int j = 0; j < 3; j++)
1597 RxyzVect[j] = posRxyz[j + 3];
1602 for (
unsigned int j = 0; j < 3; j++) {
1603 position[j] = posRxyz[j];
1604 position[j + 3] = RtuVect[j];
1625 for (
unsigned int j = 0; j < 3; j++)
1626 RxyzVect[j] = posRxyz[j + 3];
1631 for (
unsigned int j = 0; j < 3; j++) {
1632 position[j] = posRxyz[j];
1633 position[j + 3] = RtuVect[j];
1721 vpERROR_TRACE(
"Cannot send a velocity to the robot "
1722 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1724 "Cannot send a velocity to the robot "
1725 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1739 for (
unsigned int i = 0; i < 3; i++)
1741 for (
unsigned int i = 3; i < 6; i++)
1755 for (
unsigned int i = 0; i < 6; i++)
1759 for (
unsigned int i = 0; i < 5; i++)
1774 Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPCAM_VIPER850));
1784 Try(PrimitiveMOVESPEED_CART_Viper850(v_c.
data, REPCAM_VIPER850));
1792 Try(PrimitiveMOVESPEED_Viper850(vel_sat.
data));
1798 Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPFIX_VIPER850));
1806 vpERROR_TRACE(
"Error in spec of vpRobot. "
1807 "Case not taken in account.");
1814 if (TryStt == VelStopOnJoint) {
1815 UInt32 axisInJoint[
njoint];
1816 PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, axisInJoint,
nullptr);
1817 for (
unsigned int i = 0; i <
njoint; i++) {
1819 std::cout <<
"\nWarning: Velocity control stopped: axis " << i + 1 <<
" on joint limit!" << std::endl;
1823 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1824 if (TryString !=
nullptr) {
1826 printf(
" Error sentence %s\n", TryString);
1914 Try(PrimitiveACQ_POS_J_Viper850(q_cur.
data, ×tamp));
1915 time_cur = timestamp;
1923 if (!m_first_time_getvel) {
1928 eMe = m_fMe_prev_getvel.
inverse() * fMe_cur;
1938 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1947 velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1953 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1968 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1976 for (
unsigned int i = 0; i < 3; i++) {
1978 velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1980 velocity[i + 3] = thetaU[i];
1984 velocity /= (time_cur - m_time_prev_getvel);
1989 "vpRobotViper850::getVelocity() not implemented in end-effector"));
1994 m_first_time_getvel =
false;
1998 m_fMe_prev_getvel = fMe_cur;
2000 m_fMc_prev_getvel = fMc_cur;
2003 m_q_prev_getvel = q_cur;
2006 m_time_prev_getvel = time_cur;
2010 vpERROR_TRACE(
"Cannot get velocity.");
2178 std::ifstream fd(filename.c_str(), std::ios::in);
2180 if (!fd.is_open()) {
2185 std::string key(
"R:");
2186 std::string id(
"#Viper850 - Position");
2187 bool pos_found =
false;
2192 while (std::getline(fd, line)) {
2195 if (!(line.compare(0,
id.size(),
id) == 0)) {
2196 std::cout <<
"Error: this position file " << filename <<
" is not for Viper850 robot" << std::endl;
2200 if ((line.compare(0, 1,
"#") == 0)) {
2203 if ((line.compare(0, key.size(), key) == 0)) {
2206 if (chain.size() <
njoint + 1)
2208 if (chain.size() <
njoint + 1)
2211 std::istringstream ss(line);
2214 for (
unsigned int i = 0; i <
njoint; i++)
2227 std::cout <<
"Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2261 fd = fopen(filename.c_str(),
"w");
2266 #Viper850 - Position - Version 1.00\n\
2269 # Joint position in degrees\n\
2336 Try(PrimitiveACQ_POS_Viper850(q, ×tamp));
2337 for (
unsigned int i = 0; i <
njoint; i++) {
2341 if (!m_first_time_getdis) {
2344 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2349 displacement = q_cur - m_q_prev_getdis;
2354 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2359 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2363 std::cout <<
"getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2369 m_first_time_getdis =
false;
2373 m_q_prev_getdis = q_cur;
2377 vpERROR_TRACE(
"Cannot get velocity.");
2391 #if defined(USE_ATI_DAQ)
2392 #if defined(VISP_HAVE_COMEDI)
2396 "apt-get install libcomedi-dev"));
2401 Try(PrimitiveTFS_BIAS_Viper850());
2408 vpERROR_TRACE(
"Cannot bias the force/torque sensor.");
2423 #if defined(USE_ATI_DAQ)
2424 #if defined(VISP_HAVE_COMEDI)
2428 "apt-get install libcomedi-dev"));
2480 #if defined(USE_ATI_DAQ)
2481 #if defined(VISP_HAVE_COMEDI)
2486 "apt-get install libcomedi-dev"));
2493 Try(PrimitiveTFS_ACQ_Viper850(H.
data));
2497 vpERROR_TRACE(
"Cannot get the force/torque measures.");
2546 #if defined(USE_ATI_DAQ)
2547 #if defined(VISP_HAVE_COMEDI)
2552 "apt-get install libcomedi-dev"));
2559 Try(PrimitiveTFS_ACQ_Viper850(H.
data));
2564 vpERROR_TRACE(
"Cannot get the force/torque measures.");
2580 Try(PrimitivePneumaticGripper_Viper850(1));
2581 std::cout <<
"Open the pneumatic gripper..." << std::endl;
2598 Try(PrimitivePneumaticGripper_Viper850(0));
2599 std::cout <<
"Close the pneumatic gripper..." << std::endl;
2614 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
2615 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2618 vpERROR_TRACE(
"Cannot enable joint limits on axis 6");
2636 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1));
2637 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2640 vpERROR_TRACE(
"Cannot disable joint limits on axis 6");
2683 maxRotationVelocity_joint6 = w6_max;
2696 #elif !defined(VISP_BUILD_SHARED_LIBS)
2699 void dummy_vpRobotViper850() { };
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)
vpColVector getForceTorque() const
void setCalibrationFile(const std::string &calibfile, unsigned short index=1)
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.
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.
vpColVector getForceTorque() const
void get_cVe(vpVelocityTwistMatrix &cVe) const
virtual ~vpRobotViper850(void)
static const double m_defaultPositioningVelocity
bool getPowerState() const
void set_eMc(const vpHomogeneousMatrix &eMc_)
void setMaxRotationVelocity(double w_max)
void closeGripper() const
void setMaxRotationVelocityJoint6(double w6_max)
void biasForceTorqueSensor()
void unbiasForceTorqueSensor()
void disableJoint6Limits() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
void enableJoint6Limits() const
@ AUTO
Automatic control mode (default).
@ ESTOP
Emergency stop activated.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
double getPositioningVelocity(void) const
static bool readPosFile(const std::string &filename, vpColVector &q)
void setPositioningVelocity(double velocity)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
void get_cMe(vpHomogeneousMatrix &cMe) const
void move(const std::string &filename)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
double getMaxRotationVelocityJoint6() const
static bool savePosFile(const std::string &filename, const vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
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
double maxRotationVelocity
void setMaxRotationVelocity(double maxVr)
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
vpRxyzVector & buildFrom(const vpRotationMatrix &R)
Implementation of a rotation vector as Euler angle minimal representation.
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)
Modelization of the ADEPT Viper 850 robot.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
vpCameraParameters::vpCameraParametersProjType projModel
vpToolType
List of possible tools that can be attached to the robot end-effector.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
static const unsigned int njoint
Number of joint.
void get_cMe(vpHomogeneousMatrix &cMe) const
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT void sleepMs(double t)