38 #include <visp3/core/vpConfig.h>
40 #ifdef VISP_HAVE_VIPER650
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/vpRobotViper650.h>
59 bool vpRobotViper650::robotAlreadyCreated =
false;
81 void emergencyStopViper650(
int signo)
83 std::cout <<
"Stop the Viper650 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_Viper650();
103 std::cout <<
"Robot was stopped\n";
108 fprintf(stdout,
"Application ");
110 kill(getpid(), SIGKILL);
173 vpRobotViper650::vpRobotViper650 (
bool verbose)
198 signal(SIGINT, emergencyStopViper650);
199 signal(SIGBUS, emergencyStopViper650) ;
200 signal(SIGSEGV, emergencyStopViper650) ;
201 signal(SIGKILL, emergencyStopViper650);
202 signal(SIGQUIT, emergencyStopViper650);
206 std::cout <<
"Open communication with MotionBlox.\n";
219 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");
486 const std::string &filename)
585 for (
unsigned int i=0; i < 3; i ++) {
586 eMc_pose[i] =
etc[i];
587 eMc_pose[i+3] =
erc[i];
590 Try( PrimitiveCONST_Viper650(eMc_pose) );
618 for (
unsigned int i=0; i < 3; i ++) {
619 eMc_pose[i] =
etc[i];
620 eMc_pose[i+3] =
erc[i];
623 Try( PrimitiveCONST_Viper650(eMc_pose) );
647 UInt32 HIPowerStatus;
648 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
660 ShutDownConnection();
662 vpRobotViper650::robotAlreadyCreated =
false;
686 Try( PrimitiveSTOP_Viper650() );
692 std::cout <<
"Change the control mode from velocity to position control.\n";
693 Try( PrimitiveSTOP_Viper650() );
703 std::cout <<
"Change the control mode from stop to velocity control.\n";
736 Try( PrimitiveSTOP_Viper650() );
743 "Cannot stop robot motion.");
762 UInt32 HIPowerStatus;
764 bool firsttime =
true;
765 unsigned int nitermax = 10;
767 for (
unsigned int i=0; i<nitermax; i++) {
768 Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
770 if (EStopStatus == ESTOP_AUTO) {
774 else if (EStopStatus == ESTOP_MANUAL) {
778 else if (EStopStatus == ESTOP_ACTIVATED) {
781 std::cout <<
"Emergency stop is activated! \n"
782 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
785 fprintf(stdout,
"Remaining time %ds \r", nitermax-i);
790 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
791 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
793 ShutDownConnection();
798 if (EStopStatus == ESTOP_ACTIVATED)
799 std::cout << std::endl;
801 if (EStopStatus == ESTOP_ACTIVATED) {
802 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
804 "Cannot power on the robot.");
807 if (HIPowerStatus == 0) {
808 fprintf(stdout,
"Power ON the Viper650 robot\n");
811 Try( PrimitivePOWERON_Viper650() );
818 "Cannot power off the robot.");
837 UInt32 HIPowerStatus;
838 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
842 if (HIPowerStatus == 1) {
843 fprintf(stdout,
"Power OFF the Viper650 robot\n");
846 Try( PrimitivePOWEROFF_Viper650() );
853 "Cannot power off the robot.");
874 UInt32 HIPowerStatus;
875 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
879 if (HIPowerStatus == 1) {
887 "Cannot get the power status.");
947 Try( PrimitiveACQ_POS_J_Viper650(position, ×tamp) );
951 for (
unsigned int i=0; i <
njoint; i++)
984 Try( PrimitiveACQ_POS_Viper650(position, ×tamp) );
988 for (
unsigned int i=0; i <
njoint; i++)
1042 positioningVelocity = velocity;
1053 return positioningVelocity;
1142 "Modification of the robot state");
1154 Try( PrimitiveACQ_POS_Viper650(q.
data, ×tamp) );
1166 for (
unsigned int i=0; i < 3; i++) {
1167 txyz[i] = position[i];
1168 rxyz[i] = position[i+3];
1184 Try( PrimitiveMOVE_J_Viper650(destination.
data, positioningVelocity) );
1185 Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1195 destination = position;
1200 Try( PrimitiveMOVE_J_Viper650(destination.
data, positioningVelocity) );
1201 Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1207 vpRxyzVector rxyz(position[3],position[4],position[5]);
1211 for (
unsigned int i=0; i <3; i++) {
1212 destination[i] = position[i];
1215 int configuration = 0;
1218 Try( PrimitiveMOVE_C_Viper650(destination.
data, configuration,
1219 positioningVelocity) );
1220 Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1226 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1228 "Positionning error: "
1229 "Mixt frame not implemented.");
1235 if (TryStt == InvalidPosition || TryStt == -1023)
1236 std::cout <<
" : Position out of range.\n";
1238 else if (TryStt == -3019) {
1240 std::cout <<
" : Joint position out of range.\n";
1242 std::cout <<
" : Cartesian position leads to a joint position out of range.\n";
1244 else if (TryStt < 0)
1245 std::cout <<
" : Unknown error (see Fabien).\n";
1246 else if (error == -1)
1247 std::cout <<
"Position out of range.\n";
1249 if (TryStt < 0 || error < 0) {
1252 "Position out of range.");
1333 position[0] = pos1 ;
1334 position[1] = pos2 ;
1335 position[2] = pos3 ;
1336 position[3] = pos4 ;
1337 position[4] = pos5 ;
1338 position[5] = pos6 ;
1398 "Bad position in filename.");
1487 Try( PrimitiveACQ_POS_J_Viper650(position.
data, ×tamp) );
1494 Try( PrimitiveACQ_POS_C_Viper650(position.
data, ×tamp) );
1498 for (
unsigned int i=3; i <6; i++)
1501 vpRzyzVector rzyz(position[3], position[4], position[5]);
1506 for (
unsigned int i=0; i <3; i++)
1507 position[i+3] = rxyz[i];
1517 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1519 "Cannot get position in mixt frame: "
1529 "Cannot get position.");
1570 for (
unsigned int j=0;j<3;j++)
1571 RxyzVect[j]=posRxyz[j+3];
1576 for (
unsigned int j=0;j<3;j++)
1578 position[j]=posRxyz[j];
1579 position[j+3]=RtuVect[j];
1605 PrimitiveACQ_TIME_Viper650(×tamp);
1687 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1689 "Cannot send a velocity to the robot "
1690 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1703 for (
unsigned int i=0; i<3; i++)
1705 for (
unsigned int i=3; i<6; i++)
1717 for (
unsigned int i=0; i<6; i++)
1721 for (
unsigned int i=0; i<5; i++)
1737 Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPCAM_VIPER650) );
1745 Try( PrimitiveMOVESPEED_Viper650(vel_sat.
data) );
1750 std::cout <<
"Vitesse ref appliquee: " << vel_sat.
t();
1751 Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPFIX_VIPER650) );
1760 "Case not taken in account.");
1767 if (TryStt == VelStopOnJoint) {
1768 UInt32 axisInJoint[
njoint];
1769 PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1770 for (
unsigned int i=0; i <
njoint; i ++) {
1772 std::cout <<
"\nWarning: Velocity control stopped: axis "
1773 << i+1 <<
" on joint limit!" <<std::endl;
1777 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1778 if (TryString != NULL) {
1780 printf(
" Error sentence %s\n", TryString);
1871 Try( PrimitiveACQ_POS_J_Viper650(q_cur.
data, ×tamp) );
1872 time_cur = timestamp;
1878 if ( ! first_time_getvel ) {
1883 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1892 velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1898 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1913 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1921 for (
unsigned int i=0; i < 3; i++) {
1923 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1925 velocity[i+3] = thetaU[i];
1929 velocity /= (time_cur - time_prev_getvel);
1935 first_time_getvel =
false;
1939 fMc_prev_getvel = fMc_cur;
1942 q_prev_getvel = q_cur;
1945 time_prev_getvel = time_cur;
1952 "Cannot get velocity.");
2115 fd = fopen(filename,
"r") ;
2119 char line[FILENAME_MAX];
2120 char dummy[FILENAME_MAX];
2122 bool sortie =
false;
2126 if (fgets (line, FILENAME_MAX, fd) != NULL) {
2127 if ( strncmp (line,
"#", 1) != 0) {
2129 if ( strncmp (line, head,
sizeof(head)-1) == 0) {
2141 while ( sortie !=
true );
2145 sscanf(line,
"%s %lf %lf %lf %lf %lf %lf",
2147 &q[0], &q[1], &q[2],
2148 &q[3], &q[4], &q[5]);
2185 fd = fopen(filename,
"w") ;
2190 #Viper650 - Position - Version 1.00\n\
2193 # Joint position in degrees\n\
2198 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2250 vpRobotViper650::getCameraDisplacement(
vpColVector &displacement)
2266 vpRobotViper650::getArticularDisplacement(
vpColVector &displacement)
2305 Try( PrimitiveACQ_POS_Viper650(q, ×tamp) );
2306 for (
unsigned int i=0; i <
njoint; i ++) {
2310 if ( ! first_time_getdis ) {
2313 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2319 displacement = q_cur - q_prev_getdis;
2324 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2330 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2337 first_time_getdis =
false;
2341 q_prev_getdis = q_cur;
2347 "Cannot get velocity.");
2369 Try( PrimitiveTFS_BIAS_Viper650() );
2378 "Cannot bias the force/torque sensor.");
2428 Try( PrimitiveTFS_ACQ_Viper650(H.
data) );
2434 "Cannot get force/torque measures.");
2446 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
2447 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2452 "Cannot enable joint limits on axis 6.");
2468 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1) );
2469 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2474 "Cannot disable joint limits on axis 6.");
2516 maxRotationVelocity_joint6 = w6_max;
2529 return maxRotationVelocity_joint6;
2532 #elif !defined(VISP_BUILD_SHARED_LIBS)
2534 void dummy_vpRobotViper650() {};
static const double defaultPositioningVelocity
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.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
virtual ~vpRobotViper650(void)
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 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
Type * data
Address of the first element of the data array.
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
void move(const char *filename)
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.
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.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpCameraParametersProjType
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.
Implementation of a velocity twist matrix and operations on such kind of matrices.
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
Implementation of column vector and the associated operations.
static bool readPosFile(const char *filename, vpColVector &q)
Implementation of a pose vector and operations on poses.
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
void disableJoint6Limits() const
double getMaxRotationVelocityJoint6() const
Implementation of a rotation vector as Euler angle minimal representation.
void setMaxRotationVelocity(double w_max)
Implementation of a rotation vector as Euler angle minimal representation.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_cMe(vpHomogeneousMatrix &cMe) const
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void getForceTorque(vpColVector &H) const
static const unsigned int njoint
Number of joint.
void get_eJe(vpMatrix &eJe)
bool getPowerState() const
void set_eMc(const vpHomogeneousMatrix &eMc_)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void resize(const unsigned int i, const bool flagNullify=true)