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/vpVelocityTwistMatrix.h>
51 #include <visp3/core/vpThetaUVector.h>
52 #include <visp3/robot/vpRobot.h>
53 #include <visp3/robot/vpRobotViper850.h>
59 bool vpRobotViper850::robotAlreadyCreated =
false;
81 void emergencyStopViper850(
int signo)
83 std::cout <<
"Stop the Viper850 application by signal ("
84 << signo <<
"): " << (char)7 ;
88 std::cout <<
"SIGINT (stop by ^C) " << std::endl ; break ;
90 std::cout <<
"SIGBUS (stop due to a bus error) " << std::endl ; break ;
92 std::cout <<
"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
94 std::cout <<
"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
96 std::cout <<
"SIGQUIT " << std::endl ; break ;
98 std::cout << signo << std::endl ;
102 PrimitiveSTOP_Viper850();
103 std::cout <<
"Robot was stopped\n";
108 fprintf(stdout,
"Application ");
110 kill(getpid(), SIGKILL);
173 vpRobotViper850::vpRobotViper850 (
bool verbose)
198 signal(SIGINT, emergencyStopViper850);
199 signal(SIGBUS, emergencyStopViper850) ;
200 signal(SIGSEGV, emergencyStopViper850) ;
201 signal(SIGKILL, emergencyStopViper850);
202 signal(SIGQUIT, emergencyStopViper850);
206 std::cout <<
"Open communication with MotionBlox.\n";
219 vpRobotViper850::robotAlreadyCreated =
true;
256 time_prev_getvel = 0;
257 first_time_getvel =
true;
262 first_time_getdis =
true;
266 Try( InitializeConnection(
verbose_) );
269 Try( InitializeNode_Viper850() );
271 Try( PrimitiveRESET_Viper850() );
274 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
280 UInt32 HIPowerStatus;
282 Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
288 std::cout <<
"Robot status: ";
289 switch(EStopStatus) {
292 if (HIPowerStatus == 0)
293 std::cout <<
"Power is OFF" << std::endl;
295 std::cout <<
"Power is ON" << std::endl;
300 if (HIPowerStatus == 0)
301 std::cout <<
"Power is OFF" << std::endl;
303 std::cout <<
"Power is ON" << std::endl;
305 case ESTOP_ACTIVATED:
307 std::cout <<
"Emergency stop is activated" << std::endl;
310 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
311 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
314 std::cout << std::endl;
331 if (TryStt == -20001)
332 printf(
"No connection detected. Check if the robot is powered on \n"
333 "and if the firewire link exist between the MotionBlox and this computer.\n");
334 else if (TryStt == -675)
335 printf(
" Timeout enabling power...\n");
339 PrimitivePOWEROFF_Viper850();
341 ShutDownConnection();
343 std::cout <<
"Cannot open connexion with the motionblox..." << std::endl;
345 "Cannot open connexion with the motionblox");
419 for (
unsigned int i=0; i < 3; i ++) {
420 eMc_pose[i] =
etc[i];
421 eMc_pose[i+3] =
erc[i];
424 Try( PrimitiveCONST_Viper850(eMc_pose) );
459 UInt32 HIPowerStatus;
460 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
472 ShutDownConnection();
474 vpRobotViper850::robotAlreadyCreated =
false;
498 Try( PrimitiveSTOP_Viper850() );
504 std::cout <<
"Change the control mode from velocity to position control.\n";
505 Try( PrimitiveSTOP_Viper850() );
515 std::cout <<
"Change the control mode from stop to velocity control.\n";
548 Try( PrimitiveSTOP_Viper850() );
555 "Cannot stop robot motion.");
574 UInt32 HIPowerStatus;
576 bool firsttime =
true;
577 unsigned int nitermax = 10;
579 for (
unsigned int i=0; i<nitermax; i++) {
580 Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
582 if (EStopStatus == ESTOP_AUTO) {
586 else if (EStopStatus == ESTOP_MANUAL) {
590 else if (EStopStatus == ESTOP_ACTIVATED) {
593 std::cout <<
"Emergency stop is activated! \n"
594 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
597 fprintf(stdout,
"Remaining time %ds \r", nitermax-i);
602 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
603 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
605 ShutDownConnection();
610 if (EStopStatus == ESTOP_ACTIVATED)
611 std::cout << std::endl;
613 if (EStopStatus == ESTOP_ACTIVATED) {
614 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
616 "Cannot power on the robot.");
619 if (HIPowerStatus == 0) {
620 fprintf(stdout,
"Power ON the Viper850 robot\n");
623 Try( PrimitivePOWERON_Viper850() );
630 "Cannot power off the robot.");
649 UInt32 HIPowerStatus;
650 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
654 if (HIPowerStatus == 1) {
655 fprintf(stdout,
"Power OFF the Viper850 robot\n");
658 Try( PrimitivePOWEROFF_Viper850() );
665 "Cannot power off the robot.");
686 UInt32 HIPowerStatus;
687 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
691 if (HIPowerStatus == 1) {
699 "Cannot get the power status.");
759 Try( PrimitiveACQ_POS_J_Viper850(position, ×tamp) );
763 for (
unsigned int i=0; i <
njoint; i++)
796 Try( PrimitiveACQ_POS_Viper850(position, ×tamp) );
800 for (
unsigned int i=0; i <
njoint; i++)
854 positioningVelocity = velocity;
865 return positioningVelocity;
954 "Modification of the robot state");
966 Try( PrimitiveACQ_POS_Viper850(q.
data, ×tamp) );
978 for (
unsigned int i=0; i < 3; i++) {
979 txyz[i] = position[i];
980 rxyz[i] = position[i+3];
996 Try( PrimitiveMOVE_J_Viper850(destination.
data, positioningVelocity) );
997 Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1007 destination = position;
1012 Try( PrimitiveMOVE_J_Viper850(destination.
data, positioningVelocity) );
1013 Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1019 vpRxyzVector rxyz(position[3],position[4],position[5]);
1023 for (
unsigned int i=0; i <3; i++) {
1024 destination[i] = position[i];
1027 int configuration = 0;
1030 Try( PrimitiveMOVE_C_Viper850(destination.
data, configuration,
1031 positioningVelocity) );
1032 Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1038 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1040 "Positionning error: "
1041 "Mixt frame not implemented.");
1047 if (TryStt == InvalidPosition || TryStt == -1023)
1048 std::cout <<
" : Position out of range.\n";
1049 else if (TryStt == -3019) {
1051 std::cout <<
" : Joint position out of range.\n";
1053 std::cout <<
" : Cartesian position leads to a joint position out of range.\n";
1055 else if (TryStt < 0)
1056 std::cout <<
" : Unknown error (see Fabien).\n";
1057 else if (error == -1)
1058 std::cout <<
"Position out of range.\n";
1060 if (TryStt < 0 || error < 0) {
1063 "Position out of range.");
1144 position[0] = pos1 ;
1145 position[1] = pos2 ;
1146 position[2] = pos3 ;
1147 position[3] = pos4 ;
1148 position[4] = pos5 ;
1149 position[5] = pos6 ;
1209 "Bad position in filename.");
1297 Try( PrimitiveACQ_POS_J_Viper850(position.
data, ×tamp) );
1304 Try( PrimitiveACQ_POS_C_Viper850(position.
data, ×tamp) );
1308 for (
unsigned int i=3; i <6; i++)
1311 vpRzyzVector rzyz(position[3], position[4], position[5]);
1316 for (
unsigned int i=0; i <3; i++)
1317 position[i+3] = rxyz[i];
1327 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1329 "Cannot get position in mixt frame: "
1339 "Cannot get position.");
1351 PrimitiveACQ_TIME_Viper850(×tamp);
1389 for (
unsigned int j=0;j<3;j++)
1390 RxyzVect[j]=posRxyz[j+3];
1395 for (
unsigned int j=0;j<3;j++)
1397 position[j]=posRxyz[j];
1398 position[j+3]=RtuVect[j];
1419 for (
unsigned int j=0;j<3;j++)
1420 RxyzVect[j]=posRxyz[j+3];
1425 for (
unsigned int j=0;j<3;j++)
1427 position[j]=posRxyz[j];
1428 position[j+3]=RtuVect[j];
1509 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1511 "Cannot send a velocity to the robot "
1512 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1525 for (
unsigned int i=0; i<3; i++)
1527 for (
unsigned int i=3; i<6; i++)
1539 for (
unsigned int i=0; i<6; i++)
1543 for (
unsigned int i=0; i<5; i++)
1558 Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPCAM_VIPER850) );
1566 Try( PrimitiveMOVESPEED_Viper850(vel_sat.
data) );
1571 std::cout <<
"Vitesse ref appliquee: " << vel_sat.
t();
1572 Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPFIX_VIPER850) );
1581 "Case not taken in account.");
1588 if (TryStt == VelStopOnJoint) {
1589 UInt32 axisInJoint[
njoint];
1590 PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1591 for (
unsigned int i=0; i <
njoint; i ++) {
1593 std::cout <<
"\nWarning: Velocity control stopped: axis "
1594 << i+1 <<
" on joint limit!" <<std::endl;
1598 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1599 if (TryString != NULL) {
1601 printf(
" Error sentence %s\n", TryString);
1693 Try( PrimitiveACQ_POS_J_Viper850(q_cur.
data, ×tamp) );
1694 time_cur = timestamp;
1700 if ( ! first_time_getvel ) {
1705 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1714 velocity = (q_cur - q_prev_getvel)
1715 / (time_cur - time_prev_getvel);
1721 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1736 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1744 for (
unsigned int i=0; i < 3; i++) {
1746 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1748 velocity[i+3] = thetaU[i];
1752 velocity /= (time_cur - time_prev_getvel);
1758 first_time_getvel =
false;
1762 fMc_prev_getvel = fMc_cur;
1765 q_prev_getvel = q_cur;
1768 time_prev_getvel = time_cur;
1775 "Cannot get velocity.");
1939 fd = fopen(filename,
"r") ;
1943 char line[FILENAME_MAX];
1944 char dummy[FILENAME_MAX];
1946 bool sortie =
false;
1950 if (fgets (line, FILENAME_MAX, fd) != NULL) {
1951 if ( strncmp (line,
"#", 1) != 0) {
1953 if ( strncmp (line, head,
sizeof(head)-1) == 0) {
1965 while ( sortie !=
true );
1969 sscanf(line,
"%s %lf %lf %lf %lf %lf %lf",
1971 &q[0], &q[1], &q[2],
1972 &q[3], &q[4], &q[5]);
2009 fd = fopen(filename,
"w") ;
2014 #Viper850 - Position - Version 1.00\n\
2017 # Joint position in degrees\n\
2022 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2074 vpRobotViper850::getCameraDisplacement(
vpColVector &displacement)
2090 vpRobotViper850::getArticularDisplacement(
vpColVector &displacement)
2129 Try( PrimitiveACQ_POS_Viper850(q, ×tamp) );
2130 for (
unsigned int i=0; i <
njoint; i ++) {
2134 if ( ! first_time_getdis ) {
2137 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2143 displacement = q_cur - q_prev_getdis;
2148 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2154 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2161 first_time_getdis =
false;
2165 q_prev_getdis = q_cur;
2171 "Cannot get velocity.");
2193 Try( PrimitiveTFS_BIAS_Viper850() );
2202 "Cannot bias the force/torque sensor.");
2252 Try( PrimitiveTFS_ACQ_Viper850(H.
data) );
2258 "Cannot get force/torque measures.");
2271 Try( PrimitiveGripper_Viper850(1) );
2272 std::cout <<
"Open the gripper..." << std::endl;
2277 "Cannot open the gripper.");
2291 Try( PrimitiveGripper_Viper850(0) );
2292 std::cout <<
"Close the gripper..." << std::endl;
2297 "Cannot close the gripper.");
2309 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2310 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2315 "Cannot enable joint limits on axis 6.");
2331 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2332 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2337 "Cannot disable joint limits on axis 6.");
2379 maxRotationVelocity_joint6 = w6_max;
2392 return maxRotationVelocity_joint6;
2395 #elif !defined(VISP_BUILD_SHARED_LIBS)
2397 void dummy_vpRobotViper850() {};
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocity(double w_max)
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
void getForceTorque(vpColVector &H) const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
void setPositioningVelocity(const double velocity)
double maxRotationVelocity
double getMaxTranslationVelocity(void) const
void enableJoint6Limits() const
void biasForceTorqueSensor() const
Initialize the position controller.
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
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 get_eJe(vpMatrix &eJe)
static bool savePosFile(const char *filename, const vpColVector &q)
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)
static bool readPosFile(const char *filename, vpColVector &q)
Initialize the velocity controller.
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpCameraParametersProjType
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
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
void setMaxRotationVelocity(const double maxVr)
void get_cVe(vpVelocityTwistMatrix &cVe) const
void get_cMe(vpHomogeneousMatrix &cMe) const
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)
Automatic control mode (default).
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void move(const char *filename)
static const unsigned int njoint
Number of joint.
void get_cMe(vpHomogeneousMatrix &cMe) const
void resize(const unsigned int i, const bool flagNullify=true)