38 #include <visp3/core/vpConfig.h>
40 #ifdef VISP_HAVE_VIPER850
44 #include <sys/types.h>
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpExponentialMap.h>
49 #include <visp3/core/vpDebug.h>
50 #include <visp3/core/vpIoTools.h>
51 #include <visp3/core/vpVelocityTwistMatrix.h>
52 #include <visp3/core/vpThetaUVector.h>
53 #include <visp3/robot/vpRobot.h>
54 #include <visp3/robot/vpRobotViper850.h>
60 bool vpRobotViper850::robotAlreadyCreated =
false;
82 void emergencyStopViper850(
int signo)
84 std::cout <<
"Stop the Viper850 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_Viper850();
104 std::cout <<
"Robot was stopped\n";
109 fprintf(stdout,
"Application ");
111 kill(getpid(), SIGKILL);
174 vpRobotViper850::vpRobotViper850 (
bool verbose)
199 signal(SIGINT, emergencyStopViper850);
200 signal(SIGBUS, emergencyStopViper850) ;
201 signal(SIGSEGV, emergencyStopViper850) ;
202 signal(SIGKILL, emergencyStopViper850);
203 signal(SIGQUIT, emergencyStopViper850);
207 std::cout <<
"Open communication with MotionBlox.\n";
220 vpRobotViper850::robotAlreadyCreated =
true;
260 time_prev_getvel = 0;
261 first_time_getvel =
true;
266 first_time_getdis =
true;
268 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
269 std::string calibfile;
270 # ifdef VISP_HAVE_VIPER850_DATA
271 calibfile = std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/ati/FT17824.cal");
282 Try( InitializeConnection(
verbose_) );
285 Try( InitializeNode_Viper850() );
287 Try( PrimitiveRESET_Viper850() );
290 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
296 UInt32 HIPowerStatus;
298 Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
304 std::cout <<
"Robot status: ";
305 switch(EStopStatus) {
308 if (HIPowerStatus == 0)
309 std::cout <<
"Power is OFF" << std::endl;
311 std::cout <<
"Power is ON" << std::endl;
316 if (HIPowerStatus == 0)
317 std::cout <<
"Power is OFF" << std::endl;
319 std::cout <<
"Power is ON" << std::endl;
321 case ESTOP_ACTIVATED:
323 std::cout <<
"Emergency stop is activated" << std::endl;
326 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
327 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
330 std::cout << std::endl;
347 if (TryStt == -20001)
348 printf(
"No connection detected. Check if the robot is powered on \n"
349 "and if the firewire link exist between the MotionBlox and this computer.\n");
350 else if (TryStt == -675)
351 printf(
" Timeout enabling power...\n");
355 PrimitivePOWEROFF_Viper850();
357 ShutDownConnection();
359 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
361 "Cannot open connection with the motionblox");
447 for (
unsigned int i=0; i < 3; i ++) {
448 eMc_pose[i] =
etc[i];
449 eMc_pose[i+3] =
erc[i];
452 Try( PrimitiveCONST_Viper850(eMc_pose) );
527 for (
unsigned int i=0; i < 3; i ++) {
528 eMc_pose[i] =
etc[i];
529 eMc_pose[i+3] =
erc[i];
532 Try( PrimitiveCONST_Viper850(eMc_pose) );
593 for (
unsigned int i=0; i < 3; i ++) {
594 eMc_pose[i] =
etc[i];
595 eMc_pose[i+3] =
erc[i];
598 Try( PrimitiveCONST_Viper850(eMc_pose) );
624 for (
unsigned int i=0; i < 3; i ++) {
625 eMc_pose[i] =
etc[i];
626 eMc_pose[i+3] =
erc[i];
629 Try( PrimitiveCONST_Viper850(eMc_pose) );
657 for (
unsigned int i=0; i < 3; i ++) {
658 eMc_pose[i] =
etc[i];
659 eMc_pose[i+3] =
erc[i];
662 Try( PrimitiveCONST_Viper850(eMc_pose) );
681 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
690 UInt32 HIPowerStatus;
691 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
703 ShutDownConnection();
705 vpRobotViper850::robotAlreadyCreated =
false;
729 Try( PrimitiveSTOP_Viper850() );
736 std::cout <<
"Change the control mode from velocity to position control.\n";
737 Try( PrimitiveSTOP_Viper850() );
747 std::cout <<
"Change the control mode from stop to velocity control.\n";
780 Try( PrimitiveSTOP_Viper850() );
787 "Cannot stop robot motion.");
806 UInt32 HIPowerStatus;
808 bool firsttime =
true;
809 unsigned int nitermax = 10;
811 for (
unsigned int i=0; i<nitermax; i++) {
812 Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
814 if (EStopStatus == ESTOP_AUTO) {
818 else if (EStopStatus == ESTOP_MANUAL) {
822 else if (EStopStatus == ESTOP_ACTIVATED) {
825 std::cout <<
"Emergency stop is activated! \n"
826 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
829 fprintf(stdout,
"Remaining time %us \r", nitermax-i);
834 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
835 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
837 ShutDownConnection();
842 if (EStopStatus == ESTOP_ACTIVATED)
843 std::cout << std::endl;
845 if (EStopStatus == ESTOP_ACTIVATED) {
846 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
848 "Cannot power on the robot.");
851 if (HIPowerStatus == 0) {
852 fprintf(stdout,
"Power ON the Viper850 robot\n");
855 Try( PrimitivePOWERON_Viper850() );
862 "Cannot power off the robot.");
881 UInt32 HIPowerStatus;
882 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
886 if (HIPowerStatus == 1) {
887 fprintf(stdout,
"Power OFF the Viper850 robot\n");
890 Try( PrimitivePOWEROFF_Viper850() );
897 "Cannot power off the robot.");
918 UInt32 HIPowerStatus;
919 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
923 if (HIPowerStatus == 1) {
931 "Cannot get the power status.");
991 Try( PrimitiveACQ_POS_J_Viper850(position, ×tamp) );
995 for (
unsigned int i=0; i <
njoint; i++)
1028 Try( PrimitiveACQ_POS_Viper850(position, ×tamp) );
1032 for (
unsigned int i=0; i <
njoint; i++)
1086 positioningVelocity = velocity;
1097 return positioningVelocity;
1186 "Modification of the robot state");
1198 Try( PrimitiveACQ_POS_Viper850(q.
data, ×tamp) );
1210 for (
unsigned int i=0; i < 3; i++) {
1211 txyz[i] = position[i];
1212 rxyz[i] = position[i+3];
1228 Try( PrimitiveMOVE_J_Viper850(destination.
data, positioningVelocity) );
1229 Try( WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000) );
1239 destination = position;
1244 Try( PrimitiveMOVE_J_Viper850(destination.
data, positioningVelocity) );
1245 Try( WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000) );
1251 vpRxyzVector rxyz(position[3],position[4],position[5]);
1255 for (
unsigned int i=0; i <3; i++) {
1256 destination[i] = position[i];
1259 int configuration = 0;
1262 Try( PrimitiveMOVE_C_Viper850(destination.
data, configuration,
1263 positioningVelocity) );
1264 Try( WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000) );
1270 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1272 "Positionning error: "
1273 "Mixt frame not implemented.");
1278 if (TryStt == InvalidPosition || TryStt == -1023)
1279 std::cout <<
" : Position out of range.\n";
1280 else if (TryStt == -3019) {
1282 std::cout <<
" : Joint position out of range.\n";
1284 std::cout <<
" : Cartesian position leads to a joint position out of range.\n";
1286 else if (TryStt < 0)
1287 std::cout <<
" : Unknown error (see Fabien).\n";
1288 else if (error == -1)
1289 std::cout <<
"Position out of range.\n";
1291 if (TryStt < 0 || error < 0) {
1294 "Position out of range.");
1375 position[0] = pos1 ;
1376 position[1] = pos2 ;
1377 position[2] = pos3 ;
1378 position[3] = pos4 ;
1379 position[4] = pos5 ;
1380 position[5] = pos6 ;
1440 "Bad position in filename.");
1528 Try( PrimitiveACQ_POS_J_Viper850(position.
data, ×tamp) );
1535 Try( PrimitiveACQ_POS_C_Viper850(position.
data, ×tamp) );
1539 for (
unsigned int i=3; i <6; i++)
1542 vpRzyzVector rzyz(position[3], position[4], position[5]);
1547 for (
unsigned int i=0; i <3; i++)
1548 position[i+3] = rxyz[i];
1558 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1560 "Cannot get position in mixt frame: "
1569 "Cannot get position.");
1581 PrimitiveACQ_TIME_Viper850(×tamp);
1619 for (
unsigned int j=0;j<3;j++)
1620 RxyzVect[j]=posRxyz[j+3];
1625 for (
unsigned int j=0;j<3;j++)
1627 position[j]=posRxyz[j];
1628 position[j+3]=RtuVect[j];
1649 for (
unsigned int j=0;j<3;j++)
1650 RxyzVect[j]=posRxyz[j+3];
1655 for (
unsigned int j=0;j<3;j++)
1657 position[j]=posRxyz[j];
1658 position[j+3]=RtuVect[j];
1739 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1741 "Cannot send a velocity to the robot "
1742 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1755 for (
unsigned int i=0; i<3; i++)
1757 for (
unsigned int i=3; i<6; i++)
1771 for (
unsigned int i=0; i<6; i++)
1775 for (
unsigned int i=0; i<5; i++)
1790 Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPCAM_VIPER850) );
1798 Try( PrimitiveMOVESPEED_Viper850(vel_sat.
data) );
1803 std::cout <<
"Vitesse ref appliquee: " << vel_sat.
t();
1804 Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPFIX_VIPER850) );
1813 "Case not taken in account.");
1820 if (TryStt == VelStopOnJoint) {
1821 UInt32 axisInJoint[
njoint];
1822 PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1823 for (
unsigned int i=0; i <
njoint; i ++) {
1825 std::cout <<
"\nWarning: Velocity control stopped: axis "
1826 << i+1 <<
" on joint limit!" <<std::endl;
1830 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1831 if (TryString != NULL) {
1833 printf(
" Error sentence %s\n", TryString);
1925 Try( PrimitiveACQ_POS_J_Viper850(q_cur.
data, ×tamp) );
1926 time_cur = timestamp;
1932 if ( ! first_time_getvel ) {
1937 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1946 velocity = (q_cur - q_prev_getvel)
1947 / (time_cur - time_prev_getvel);
1953 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1968 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1976 for (
unsigned int i=0; i < 3; i++) {
1978 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1980 velocity[i+3] = thetaU[i];
1984 velocity /= (time_cur - time_prev_getvel);
1990 first_time_getvel =
false;
1994 fMc_prev_getvel = fMc_cur;
1997 q_prev_getvel = q_cur;
2000 time_prev_getvel = time_cur;
2007 "Cannot get velocity.");
2168 std::ifstream fd(filename.c_str(), std::ios::in);
2170 if(! fd.is_open()) {
2175 std::string key(
"R:");
2176 std::string id(
"#Viper850 - Position");
2177 bool pos_found =
false;
2182 while(std::getline(fd, line)) {
2185 if(! (line.compare(0,
id.size(), id) == 0)) {
2186 std::cout <<
"Error: this position file " << filename <<
" is not for Viper850 robot" << std::endl;
2190 if((line.compare(0, 1,
"#") == 0)) {
2193 if((line.compare(0, key.size(), key) == 0)) {
2196 if (chain.size() <
njoint+1)
2198 if(chain.size() <
njoint+1)
2201 std::istringstream ss(line);
2204 for (
unsigned int i=0; i<
njoint; i++)
2217 std::cout <<
"Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2252 fd = fopen(filename.c_str(),
"w") ;
2257 #Viper850 - Position - Version 1.00\n\
2260 # Joint position in degrees\n\
2265 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2317 vpRobotViper850::getCameraDisplacement(
vpColVector &displacement)
2333 vpRobotViper850::getArticularDisplacement(
vpColVector &displacement)
2372 Try( PrimitiveACQ_POS_Viper850(q, ×tamp) );
2373 for (
unsigned int i=0; i <
njoint; i ++) {
2377 if ( ! first_time_getdis ) {
2380 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2385 displacement = q_cur - q_prev_getdis;
2390 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2395 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2401 first_time_getdis =
false;
2405 q_prev_getdis = q_cur;
2411 "Cannot get velocity.");
2424 #if defined(USE_ATI_DAQ)
2425 # if defined(VISP_HAVE_COMEDI)
2430 #else // Use serial link
2433 Try( PrimitiveTFS_BIAS_Viper850() );
2442 "Cannot bias the force/torque sensor.");
2456 #if defined(USE_ATI_DAQ)
2457 # if defined(VISP_HAVE_COMEDI)
2462 #else // Use serial link
2508 #if defined(USE_ATI_DAQ)
2509 # if defined(VISP_HAVE_COMEDI)
2515 #else // Use serial link
2520 Try( PrimitiveTFS_ACQ_Viper850(H.
data) );
2526 "Cannot get force/torque measures.");
2570 #if defined(USE_ATI_DAQ)
2571 # if defined(VISP_HAVE_COMEDI)
2577 #else // Use serial link
2582 Try( PrimitiveTFS_ACQ_Viper850(H.
data) );
2589 "Cannot get force/torque measures.");
2604 Try( PrimitivePneumaticGripper_Viper850(1) );
2605 std::cout <<
"Open the pneumatic gripper..." << std::endl;
2609 "Cannot open the gripper.");
2623 Try( PrimitivePneumaticGripper_Viper850(0) );
2624 std::cout <<
"Close the pneumatic gripper..." << std::endl;
2628 "Cannot close the gripper.");
2640 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2641 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2646 "Cannot enable joint limits on axis 6.");
2662 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2663 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2668 "Cannot disable joint limits on axis 6.");
2710 maxRotationVelocity_joint6 = w6_max;
2723 return maxRotationVelocity_joint6;
2726 #elif !defined(VISP_BUILD_SHARED_LIBS)
2728 void dummy_vpRobotViper850() {};
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocity(double w_max)
void set_eMc(const vpHomogeneousMatrix &eMc_)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of a matrix and operations on matrices.
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
VISP_EXPORT int wait(double t0, double t)
Error that can be emited by the vpRobot class and its derivates.
double getPositioningVelocity(void) const
static const vpToolType defaultTool
Default tool attached to the robot end effector.
void closeGripper() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
vpColVector getForceTorque() const
void setPositioningVelocity(const double velocity)
double maxRotationVelocity
double getMaxTranslationVelocity(void) const
void enableJoint6Limits() const
Initialize the position controller.
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
error that can be emited by ViSP classes.
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.
void move(const std::string &filename)
void get_eJe(vpMatrix &eJe)
void unbiasForceTorqueSensor()
void disableJoint6Limits() const
double getMaxRotationVelocity(void) const
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Implementation of a rotation matrix and operations on such kind of matrices.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
Initialize the velocity controller.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpCameraParametersProjType
VISP_EXPORT void sleepMs(double t)
vpToolType
List of possible tools that can be attached to the robot end-effector.
Modelisation of the ADEPT Viper 850 robot.
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
vpColVector getForceTorque() const
bool getPowerState() const
Implementation of a velocity twist matrix and operations on such kind of matrices.
void get_fJe(vpMatrix &fJe)
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
static double rad(double deg)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
static bool readPosFile(const std::string &filename, vpColVector &q)
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setMaxRotationVelocity(const double maxVr)
void get_cVe(vpVelocityTwistMatrix &cVe) const
void get_cMe(vpHomogeneousMatrix &cMe) const
void biasForceTorqueSensor()
void setMaxRotationVelocityJoint6(double w6_max)
static double deg(double rad)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Implementation of column vector and the associated operations.
Manual control mode activated when the dead man switch is in use.
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Implementation of a pose vector and operations on poses.
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
double getMaxRotationVelocityJoint6() const
Implementation of a rotation vector as Euler angle minimal representation.
Emergency stop activated.
Implementation of a rotation vector as Euler angle minimal representation.
virtual ~vpRobotViper850(void)
void setCalibrationFile(const std::string &calibfile, unsigned short index=1)
Automatic control mode (default).
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
static const unsigned int njoint
Number of joint.
void get_cMe(vpHomogeneousMatrix &cMe) const
void resize(const unsigned int i, const bool flagNullify=true)