42 #include <visp/vpConfig.h>
44 #ifdef VISP_HAVE_VIPER850
48 #include <sys/types.h>
51 #include <visp/vpRobotException.h>
52 #include <visp/vpExponentialMap.h>
53 #include <visp/vpDebug.h>
54 #include <visp/vpVelocityTwistMatrix.h>
55 #include <visp/vpThetaUVector.h>
56 #include <visp/vpRobot.h>
57 #include <visp/vpRobotViper850.h>
63 bool vpRobotViper850::robotAlreadyCreated =
false;
85 void emergencyStopViper850(
int signo)
87 std::cout <<
"Stop the Viper850 application by signal ("
88 << signo <<
"): " << (char)7 ;
92 std::cout <<
"SIGINT (stop by ^C) " << std::endl ; break ;
94 std::cout <<
"SIGBUS (stop due to a bus error) " << std::endl ; break ;
96 std::cout <<
"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
98 std::cout <<
"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
100 std::cout <<
"SIGQUIT " << std::endl ; break ;
102 std::cout << signo << std::endl ;
106 PrimitiveSTOP_Viper850();
107 std::cout <<
"Robot was stopped\n";
112 fprintf(stdout,
"Application ");
114 kill(getpid(), SIGKILL);
177 vpRobotViper850::vpRobotViper850 (
bool verbose)
202 signal(SIGINT, emergencyStopViper850);
203 signal(SIGBUS, emergencyStopViper850) ;
204 signal(SIGSEGV, emergencyStopViper850) ;
205 signal(SIGKILL, emergencyStopViper850);
206 signal(SIGQUIT, emergencyStopViper850);
210 std::cout <<
"Open communication with MotionBlox.\n";
223 vpRobotViper850::robotAlreadyCreated =
true;
260 time_prev_getvel = 0;
261 first_time_getvel =
true;
266 first_time_getdis =
true;
270 Try( InitializeConnection(
verbose_) );
273 Try( InitializeNode_Viper850() );
275 Try( PrimitiveRESET_Viper850() );
278 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
284 UInt32 HIPowerStatus;
286 Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
292 std::cout <<
"Robot status: ";
293 switch(EStopStatus) {
296 if (HIPowerStatus == 0)
297 std::cout <<
"Power is OFF" << std::endl;
299 std::cout <<
"Power is ON" << std::endl;
304 if (HIPowerStatus == 0)
305 std::cout <<
"Power is OFF" << std::endl;
307 std::cout <<
"Power is ON" << std::endl;
309 case ESTOP_ACTIVATED:
311 std::cout <<
"Emergency stop is activated" << std::endl;
314 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
315 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
318 std::cout << std::endl;
335 if (TryStt == -20001)
336 printf(
"No connection detected. Check if the robot is powered on \n"
337 "and if the firewire link exist between the MotionBlox and this computer.\n");
338 else if (TryStt == -675)
339 printf(
" Timeout enabling power...\n");
343 PrimitivePOWEROFF_Viper850();
345 ShutDownConnection();
347 std::cout <<
"Cannot open connexion with the motionblox..." << std::endl;
349 "Cannot open connexion with the motionblox");
423 for (
unsigned int i=0; i < 3; i ++) {
424 eMc_pose[i] =
etc[i];
425 eMc_pose[i+3] =
erc[i];
428 Try( PrimitiveCONST_Viper850(eMc_pose) );
463 UInt32 HIPowerStatus;
464 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
476 ShutDownConnection();
478 vpRobotViper850::robotAlreadyCreated =
false;
502 Try( PrimitiveSTOP_Viper850() );
508 std::cout <<
"Change the control mode from velocity to position control.\n";
509 Try( PrimitiveSTOP_Viper850() );
519 std::cout <<
"Change the control mode from stop to velocity control.\n";
552 Try( PrimitiveSTOP_Viper850() );
559 "Cannot stop robot motion.");
578 UInt32 HIPowerStatus;
580 bool firsttime =
true;
581 unsigned int nitermax = 10;
583 for (
unsigned int i=0; i<nitermax; i++) {
584 Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
586 if (EStopStatus == ESTOP_AUTO) {
590 else if (EStopStatus == ESTOP_MANUAL) {
594 else if (EStopStatus == ESTOP_ACTIVATED) {
597 std::cout <<
"Emergency stop is activated! \n"
598 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
601 fprintf(stdout,
"Remaining time %ds \r", nitermax-i);
606 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
607 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
609 ShutDownConnection();
614 if (EStopStatus == ESTOP_ACTIVATED)
615 std::cout << std::endl;
617 if (EStopStatus == ESTOP_ACTIVATED) {
618 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
620 "Cannot power on the robot.");
623 if (HIPowerStatus == 0) {
624 fprintf(stdout,
"Power ON the Viper850 robot\n");
627 Try( PrimitivePOWERON_Viper850() );
634 "Cannot power off the robot.");
653 UInt32 HIPowerStatus;
654 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
658 if (HIPowerStatus == 1) {
659 fprintf(stdout,
"Power OFF the Viper850 robot\n");
662 Try( PrimitivePOWEROFF_Viper850() );
669 "Cannot power off the robot.");
690 UInt32 HIPowerStatus;
691 Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
695 if (HIPowerStatus == 1) {
703 "Cannot get the power status.");
763 Try( PrimitiveACQ_POS_J_Viper850(position, ×tamp) );
767 for (
unsigned int i=0; i <
njoint; i++)
800 Try( PrimitiveACQ_POS_Viper850(position, ×tamp) );
804 for (
unsigned int i=0; i <
njoint; i++)
858 positioningVelocity = velocity;
869 return positioningVelocity;
958 "Modification of the robot state");
970 Try( PrimitiveACQ_POS_Viper850(q.
data, ×tamp) );
982 for (
unsigned int i=0; i < 3; i++) {
983 txyz[i] = position[i];
984 rxyz[i] = position[i+3];
1000 Try( PrimitiveMOVE_J_Viper850(destination.
data, positioningVelocity) );
1001 Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1011 destination = position;
1016 Try( PrimitiveMOVE_J_Viper850(destination.
data, positioningVelocity) );
1017 Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1023 vpRxyzVector rxyz(position[3],position[4],position[5]);
1027 for (
unsigned int i=0; i <3; i++) {
1028 destination[i] = position[i];
1031 int configuration = 0;
1034 Try( PrimitiveMOVE_C_Viper850(destination.
data, configuration,
1035 positioningVelocity) );
1036 Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1042 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1044 "Positionning error: "
1045 "Mixt frame not implemented.");
1051 if (TryStt == InvalidPosition || TryStt == -1023)
1052 std::cout <<
" : Position out of range.\n";
1053 else if (TryStt == -3019) {
1055 std::cout <<
" : Joint position out of range.\n";
1057 std::cout <<
" : Cartesian position leads to a joint position out of range.\n";
1059 else if (TryStt < 0)
1060 std::cout <<
" : Unknown error (see Fabien).\n";
1061 else if (error == -1)
1062 std::cout <<
"Position out of range.\n";
1064 if (TryStt < 0 || error < 0) {
1067 "Position out of range.");
1148 position[0] = pos1 ;
1149 position[1] = pos2 ;
1150 position[2] = pos3 ;
1151 position[3] = pos4 ;
1152 position[4] = pos5 ;
1153 position[5] = pos6 ;
1213 "Bad position in filename.");
1301 Try( PrimitiveACQ_POS_J_Viper850(position.
data, ×tamp) );
1308 Try( PrimitiveACQ_POS_C_Viper850(position.
data, ×tamp) );
1312 for (
unsigned int i=3; i <6; i++)
1315 vpRzyzVector rzyz(position[3], position[4], position[5]);
1320 for (
unsigned int i=0; i <3; i++)
1321 position[i+3] = rxyz[i];
1331 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1333 "Cannot get position in mixt frame: "
1343 "Cannot get position.");
1355 PrimitiveACQ_TIME_Viper850(×tamp);
1393 for (
unsigned int j=0;j<3;j++)
1394 RxyzVect[j]=posRxyz[j+3];
1399 for (
unsigned int j=0;j<3;j++)
1401 position[j]=posRxyz[j];
1402 position[j+3]=RtuVect[j];
1423 for (
unsigned int j=0;j<3;j++)
1424 RxyzVect[j]=posRxyz[j+3];
1429 for (
unsigned int j=0;j<3;j++)
1431 position[j]=posRxyz[j];
1432 position[j+3]=RtuVect[j];
1513 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1515 "Cannot send a velocity to the robot "
1516 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1529 for (
unsigned int i=0; i<3; i++)
1531 for (
unsigned int i=3; i<6; i++)
1543 for (
unsigned int i=0; i<6; i++)
1547 for (
unsigned int i=0; i<5; i++)
1562 Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPCAM_VIPER850) );
1570 Try( PrimitiveMOVESPEED_Viper850(vel_sat.
data) );
1575 std::cout <<
"Vitesse ref appliquee: " << vel_sat.
t();
1576 Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPFIX_VIPER850) );
1585 "Case not taken in account.");
1592 if (TryStt == VelStopOnJoint) {
1593 UInt32 axisInJoint[
njoint];
1594 PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1595 for (
unsigned int i=0; i <
njoint; i ++) {
1597 std::cout <<
"\nWarning: Velocity control stopped: axis "
1598 << i+1 <<
" on joint limit!" <<std::endl;
1602 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1603 if (TryString != NULL) {
1605 printf(
" Error sentence %s\n", TryString);
1697 Try( PrimitiveACQ_POS_J_Viper850(q_cur.
data, ×tamp) );
1698 time_cur = timestamp;
1704 if ( ! first_time_getvel ) {
1709 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1718 velocity = (q_cur - q_prev_getvel)
1719 / (time_cur - time_prev_getvel);
1725 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1740 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1748 for (
unsigned int i=0; i < 3; i++) {
1750 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1752 velocity[i+3] = thetaU[i];
1756 velocity /= (time_cur - time_prev_getvel);
1762 first_time_getvel =
false;
1766 fMc_prev_getvel = fMc_cur;
1769 q_prev_getvel = q_cur;
1772 time_prev_getvel = time_cur;
1779 "Cannot get velocity.");
1943 fd = fopen(filename,
"r") ;
1947 char line[FILENAME_MAX];
1948 char dummy[FILENAME_MAX];
1950 bool sortie =
false;
1954 if (fgets (line, FILENAME_MAX, fd) != NULL) {
1955 if ( strncmp (line,
"#", 1) != 0) {
1957 if ( strncmp (line, head,
sizeof(head)-1) == 0) {
1969 while ( sortie !=
true );
1973 sscanf(line,
"%s %lf %lf %lf %lf %lf %lf",
1975 &q[0], &q[1], &q[2],
1976 &q[3], &q[4], &q[5]);
2013 fd = fopen(filename,
"w") ;
2018 #Viper850 - Position - Version 1.00\n\
2021 # Joint position in degrees\n\
2026 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2078 vpRobotViper850::getCameraDisplacement(
vpColVector &displacement)
2094 vpRobotViper850::getArticularDisplacement(
vpColVector &displacement)
2133 Try( PrimitiveACQ_POS_Viper850(q, ×tamp) );
2134 for (
unsigned int i=0; i <
njoint; i ++) {
2138 if ( ! first_time_getdis ) {
2141 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2147 displacement = q_cur - q_prev_getdis;
2152 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2158 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2165 first_time_getdis =
false;
2169 q_prev_getdis = q_cur;
2175 "Cannot get velocity.");
2197 Try( PrimitiveTFS_BIAS_Viper850() );
2206 "Cannot bias the force/torque sensor.");
2256 Try( PrimitiveTFS_ACQ_Viper850(H.
data) );
2262 "Cannot get force/torque measures.");
2275 Try( PrimitiveGripper_Viper850(1) );
2276 std::cout <<
"Open the gripper..." << std::endl;
2281 "Cannot open the gripper.");
2295 Try( PrimitiveGripper_Viper850(0) );
2296 std::cout <<
"Close the gripper..." << std::endl;
2301 "Cannot close the gripper.");
2313 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2314 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2319 "Cannot enable joint limits on axis 6.");
2335 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2336 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2341 "Cannot disable joint limits on axis 6.");
2383 maxRotationVelocity_joint6 = w6_max;
2396 return maxRotationVelocity_joint6;
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocity(double w_max)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Definition of the vpMatrix class.
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
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
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
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)
void get_eJe(vpMatrix &eJe)
static int wait(double t0, double t)
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)
The vpRotationMatrix considers the particular case of a rotation matrix.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double * data
address of the first element of the data array
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
vpRowVector t() const
Transpose of a vector.
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
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
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)
Class that provides a data structure for the column vectors as well as a set of operations on these v...
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)
The pose is a complete representation of every rigid motion in the euclidian space.
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
double getMaxRotationVelocityJoint6() const
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Emergency stop activated.
Class that consider the case of the Euler angles using the z-y-z convention, where are respectively...
virtual ~vpRobotViper850(void)
Automatic control mode (default).
Class that consider the case of a translation vector.
Class that consider the case of the parameterization for the rotation.
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)