42 #include <visp/vpConfig.h>
44 #ifdef VISP_HAVE_VIPER650
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/vpRobotViper650.h>
63 bool vpRobotViper650::robotAlreadyCreated =
false;
85 void emergencyStopViper650(
int signo)
87 std::cout <<
"Stop the Viper650 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_Viper650();
107 std::cout <<
"Robot was stopped\n";
112 fprintf(stdout,
"Application ");
114 kill(getpid(), SIGKILL);
177 vpRobotViper650::vpRobotViper650 (
bool verbose)
202 signal(SIGINT, emergencyStopViper650);
203 signal(SIGBUS, emergencyStopViper650) ;
204 signal(SIGSEGV, emergencyStopViper650) ;
205 signal(SIGKILL, emergencyStopViper650);
206 signal(SIGQUIT, emergencyStopViper650);
210 std::cout <<
"Open communication with MotionBlox.\n";
223 vpRobotViper650::robotAlreadyCreated =
true;
260 time_prev_getvel = 0;
261 first_time_getvel =
true;
266 first_time_getdis =
true;
269 Try( InitializeConnection(
verbose_) );
272 Try( InitializeNode_Viper650() );
274 Try( PrimitiveRESET_Viper650() );
277 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
283 UInt32 HIPowerStatus;
285 Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
291 std::cout <<
"Robot status: ";
292 switch(EStopStatus) {
295 if (HIPowerStatus == 0)
296 std::cout <<
"Power is OFF" << std::endl;
298 std::cout <<
"Power is ON" << std::endl;
303 if (HIPowerStatus == 0)
304 std::cout <<
"Power is OFF" << std::endl;
306 std::cout <<
"Power is ON" << std::endl;
308 case ESTOP_ACTIVATED:
310 std::cout <<
"Emergency stop is activated" << std::endl;
313 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
314 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
317 std::cout << std::endl;
334 if (TryStt == -20001)
335 printf(
"No connection detected. Check if the robot is powered on \n"
336 "and if the firewire link exist between the MotionBlox and this computer.\n");
337 else if (TryStt == -675)
338 printf(
" Timeout enabling power...\n");
342 PrimitivePOWEROFF_Viper650();
344 ShutDownConnection();
346 std::cout <<
"Cannot open connexion with the motionblox..." << std::endl;
348 "Cannot open connexion with the motionblox");
422 for (
unsigned int i=0; i < 3; i ++) {
423 eMc_pose[i] =
etc[i];
424 eMc_pose[i+3] =
erc[i];
427 Try( PrimitiveCONST_Viper650(eMc_pose) );
462 UInt32 HIPowerStatus;
463 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
475 ShutDownConnection();
477 vpRobotViper650::robotAlreadyCreated =
false;
501 Try( PrimitiveSTOP_Viper650() );
507 std::cout <<
"Change the control mode from velocity to position control.\n";
508 Try( PrimitiveSTOP_Viper650() );
518 std::cout <<
"Change the control mode from stop to velocity control.\n";
551 Try( PrimitiveSTOP_Viper650() );
558 "Cannot stop robot motion.");
577 UInt32 HIPowerStatus;
579 bool firsttime =
true;
580 unsigned int nitermax = 10;
582 for (
unsigned int i=0; i<nitermax; i++) {
583 Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
585 if (EStopStatus == ESTOP_AUTO) {
589 else if (EStopStatus == ESTOP_MANUAL) {
593 else if (EStopStatus == ESTOP_ACTIVATED) {
596 std::cout <<
"Emergency stop is activated! \n"
597 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
600 fprintf(stdout,
"Remaining time %ds \r", nitermax-i);
605 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
606 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
608 ShutDownConnection();
613 if (EStopStatus == ESTOP_ACTIVATED)
614 std::cout << std::endl;
616 if (EStopStatus == ESTOP_ACTIVATED) {
617 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
619 "Cannot power on the robot.");
622 if (HIPowerStatus == 0) {
623 fprintf(stdout,
"Power ON the Viper650 robot\n");
626 Try( PrimitivePOWERON_Viper650() );
633 "Cannot power off the robot.");
652 UInt32 HIPowerStatus;
653 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
657 if (HIPowerStatus == 1) {
658 fprintf(stdout,
"Power OFF the Viper650 robot\n");
661 Try( PrimitivePOWEROFF_Viper650() );
668 "Cannot power off the robot.");
689 UInt32 HIPowerStatus;
690 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
694 if (HIPowerStatus == 1) {
702 "Cannot get the power status.");
762 Try( PrimitiveACQ_POS_J_Viper650(position, ×tamp) );
766 for (
unsigned int i=0; i <
njoint; i++)
799 Try( PrimitiveACQ_POS_Viper650(position, ×tamp) );
803 for (
unsigned int i=0; i <
njoint; i++)
857 positioningVelocity = velocity;
868 return positioningVelocity;
957 "Modification of the robot state");
969 Try( PrimitiveACQ_POS_Viper650(q.
data, ×tamp) );
981 for (
unsigned int i=0; i < 3; i++) {
982 txyz[i] = position[i];
983 rxyz[i] = position[i+3];
999 Try( PrimitiveMOVE_J_Viper650(destination.
data, positioningVelocity) );
1000 Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1010 destination = position;
1015 Try( PrimitiveMOVE_J_Viper650(destination.
data, positioningVelocity) );
1016 Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1022 vpRxyzVector rxyz(position[3],position[4],position[5]);
1026 for (
unsigned int i=0; i <3; i++) {
1027 destination[i] = position[i];
1030 int configuration = 0;
1033 Try( PrimitiveMOVE_C_Viper650(destination.
data, configuration,
1034 positioningVelocity) );
1035 Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1041 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1043 "Positionning error: "
1044 "Mixt frame not implemented.");
1050 if (TryStt == InvalidPosition || TryStt == -1023)
1051 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.");
1302 Try( PrimitiveACQ_POS_J_Viper650(position.
data, ×tamp) );
1309 Try( PrimitiveACQ_POS_C_Viper650(position.
data, ×tamp) );
1313 for (
unsigned int i=3; i <6; i++)
1316 vpRzyzVector rzyz(position[3], position[4], position[5]);
1321 for (
unsigned int i=0; i <3; i++)
1322 position[i+3] = rxyz[i];
1332 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1334 "Cannot get position in mixt frame: "
1344 "Cannot get position.");
1385 for (
unsigned int j=0;j<3;j++)
1386 RxyzVect[j]=posRxyz[j+3];
1391 for (
unsigned int j=0;j<3;j++)
1393 position[j]=posRxyz[j];
1394 position[j+3]=RtuVect[j];
1420 PrimitiveACQ_TIME_Viper650(×tamp);
1502 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1504 "Cannot send a velocity to the robot "
1505 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1518 for (
unsigned int i=0; i<3; i++)
1520 for (
unsigned int i=3; i<6; i++)
1532 for (
unsigned int i=0; i<6; i++)
1536 for (
unsigned int i=0; i<5; i++)
1552 Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPCAM_VIPER650) );
1560 Try( PrimitiveMOVESPEED_Viper650(vel_sat.
data) );
1565 std::cout <<
"Vitesse ref appliquee: " << vel_sat.
t();
1566 Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPFIX_VIPER650) );
1575 "Case not taken in account.");
1582 if (TryStt == VelStopOnJoint) {
1583 UInt32 axisInJoint[
njoint];
1584 PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1585 for (
unsigned int i=0; i <
njoint; i ++) {
1587 std::cout <<
"\nWarning: Velocity control stopped: axis "
1588 << i+1 <<
" on joint limit!" <<std::endl;
1592 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1593 if (TryString != NULL) {
1595 printf(
" Error sentence %s\n", TryString);
1686 Try( PrimitiveACQ_POS_J_Viper650(q_cur.
data, ×tamp) );
1687 time_cur = timestamp;
1693 if ( ! first_time_getvel ) {
1698 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1707 velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1713 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1728 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1736 for (
unsigned int i=0; i < 3; i++) {
1738 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1740 velocity[i+3] = thetaU[i];
1744 velocity /= (time_cur - time_prev_getvel);
1750 first_time_getvel =
false;
1754 fMc_prev_getvel = fMc_cur;
1757 q_prev_getvel = q_cur;
1760 time_prev_getvel = time_cur;
1767 "Cannot get velocity.");
1930 fd = fopen(filename,
"r") ;
1934 char line[FILENAME_MAX];
1935 char dummy[FILENAME_MAX];
1937 bool sortie =
false;
1941 if (fgets (line, FILENAME_MAX, fd) != NULL) {
1942 if ( strncmp (line,
"#", 1) != 0) {
1944 if ( strncmp (line, head,
sizeof(head)-1) == 0) {
1956 while ( sortie !=
true );
1960 sscanf(line,
"%s %lf %lf %lf %lf %lf %lf",
1962 &q[0], &q[1], &q[2],
1963 &q[3], &q[4], &q[5]);
2000 fd = fopen(filename,
"w") ;
2005 #Viper650 - Position - Version 1.00\n\
2008 # Joint position in degrees\n\
2013 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2065 vpRobotViper650::getCameraDisplacement(
vpColVector &displacement)
2081 vpRobotViper650::getArticularDisplacement(
vpColVector &displacement)
2120 Try( PrimitiveACQ_POS_Viper650(q, ×tamp) );
2121 for (
unsigned int i=0; i <
njoint; i ++) {
2125 if ( ! first_time_getdis ) {
2128 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2134 displacement = q_cur - q_prev_getdis;
2139 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2145 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2152 first_time_getdis =
false;
2156 q_prev_getdis = q_cur;
2162 "Cannot get velocity.");
2184 Try( PrimitiveTFS_BIAS_Viper650() );
2193 "Cannot bias the force/torque sensor.");
2243 Try( PrimitiveTFS_ACQ_Viper650(H.
data) );
2249 "Cannot get force/torque measures.");
2261 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
2262 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2267 "Cannot enable joint limits on axis 6.");
2283 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1) );
2284 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2289 "Cannot disable joint limits on axis 6.");
2331 maxRotationVelocity_joint6 = w6_max;
2344 return maxRotationVelocity_joint6;
static const double defaultPositioningVelocity
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.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
virtual ~vpRobotViper650(void)
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 setMaxRotationVelocityJoint6(double w6_max)
Initialize the position controller.
class that defines a generic virtual robot
Automatic control mode (default).
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
void get_cVe(vpVelocityTwistMatrix &cVe) const
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
static int wait(double t0, double t)
void move(const char *filename)
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.
double * data
address of the first element of the data array
static const vpToolType defaultTool
Default tool attached to the robot end effector.
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Initialize the velocity controller.
Emergency stop activated.
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpCameraParametersProjType
vpRowVector t() const
Transpose of a vector.
Modelisation of the ADEPT Viper 650 robot.
void enableJoint6Limits() const
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
double getPositioningVelocity(void) const
Manual control mode activated when the dead man switch is in use.
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
vpToolType
List of possible tools that can be attached to the robot end-effector.
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
static double rad(double deg)
void get_fJe(vpMatrix &fJe)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
static bool savePosFile(const char *filename, const vpColVector &q)
void setMaxRotationVelocity(const double maxVr)
void get_cMe(vpHomogeneousMatrix &cMe) const
static double deg(double rad)
void biasForceTorqueSensor() const
Class that provides a data structure for the column vectors as well as a set of operations on these v...
static bool readPosFile(const char *filename, vpColVector &q)
The pose is a complete representation of every rigid motion in the euclidian space.
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
void disableJoint6Limits() const
double getMaxRotationVelocityJoint6() const
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
void setMaxRotationVelocity(double w_max)
Class that consider the case of the Euler angles using the z-y-z convention, where are respectively...
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_cMe(vpHomogeneousMatrix &cMe) const
Class that consider the case of a translation vector.
Class that consider the case of the parameterization for the rotation.
void getForceTorque(vpColVector &H) const
static const unsigned int njoint
Number of joint.
void get_eJe(vpMatrix &eJe)
bool getPowerState() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void resize(const unsigned int i, const bool flagNullify=true)