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/core/vpIoTools.h>
53 #include <visp3/robot/vpRobot.h>
54 #include <visp3/robot/vpRobotViper650.h>
60 bool vpRobotViper650::robotAlreadyCreated =
false;
82 void emergencyStopViper650(
int signo)
84 std::cout <<
"Stop the Viper650 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_Viper650();
104 std::cout <<
"Robot was stopped\n";
109 fprintf(stdout,
"Application ");
111 kill(getpid(), SIGKILL);
174 vpRobotViper650::vpRobotViper650 (
bool verbose)
199 signal(SIGINT, emergencyStopViper650);
200 signal(SIGBUS, emergencyStopViper650) ;
201 signal(SIGSEGV, emergencyStopViper650) ;
202 signal(SIGKILL, emergencyStopViper650);
203 signal(SIGQUIT, emergencyStopViper650);
207 std::cout <<
"Open communication with MotionBlox.\n";
220 vpRobotViper650::robotAlreadyCreated =
true;
259 time_prev_getvel = 0;
260 first_time_getvel =
true;
265 first_time_getdis =
true;
268 Try( InitializeConnection(
verbose_) );
271 Try( InitializeNode_Viper650() );
273 Try( PrimitiveRESET_Viper650() );
276 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
282 UInt32 HIPowerStatus;
284 Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
290 std::cout <<
"Robot status: ";
291 switch(EStopStatus) {
294 if (HIPowerStatus == 0)
295 std::cout <<
"Power is OFF" << std::endl;
297 std::cout <<
"Power is ON" << std::endl;
302 if (HIPowerStatus == 0)
303 std::cout <<
"Power is OFF" << std::endl;
305 std::cout <<
"Power is ON" << std::endl;
307 case ESTOP_ACTIVATED:
309 std::cout <<
"Emergency stop is activated" << std::endl;
312 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
313 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
316 std::cout << std::endl;
333 if (TryStt == -20001)
334 printf(
"No connection detected. Check if the robot is powered on \n"
335 "and if the firewire link exist between the MotionBlox and this computer.\n");
336 else if (TryStt == -675)
337 printf(
" Timeout enabling power...\n");
341 PrimitivePOWEROFF_Viper650();
343 ShutDownConnection();
345 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
347 "Cannot open connection with the motionblox");
433 for (
unsigned int i=0; i < 3; i ++) {
434 eMc_pose[i] =
etc[i];
435 eMc_pose[i+3] =
erc[i];
438 Try( PrimitiveCONST_Viper650(eMc_pose) );
513 for (
unsigned int i=0; i < 3; i ++) {
514 eMc_pose[i] =
etc[i];
515 eMc_pose[i+3] =
erc[i];
518 Try( PrimitiveCONST_Viper650(eMc_pose) );
579 for (
unsigned int i=0; i < 3; i ++) {
580 eMc_pose[i] =
etc[i];
581 eMc_pose[i+3] =
erc[i];
584 Try( PrimitiveCONST_Viper650(eMc_pose) );
610 for (
unsigned int i=0; i < 3; i ++) {
611 eMc_pose[i] =
etc[i];
612 eMc_pose[i+3] =
erc[i];
615 Try( PrimitiveCONST_Viper650(eMc_pose) );
643 for (
unsigned int i=0; i < 3; i ++) {
644 eMc_pose[i] =
etc[i];
645 eMc_pose[i+3] =
erc[i];
648 Try( PrimitiveCONST_Viper650(eMc_pose) );
672 UInt32 HIPowerStatus;
673 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
685 ShutDownConnection();
687 vpRobotViper650::robotAlreadyCreated =
false;
711 Try( PrimitiveSTOP_Viper650() );
718 std::cout <<
"Change the control mode from velocity to position control.\n";
719 Try( PrimitiveSTOP_Viper650() );
729 std::cout <<
"Change the control mode from stop to velocity control.\n";
762 Try( PrimitiveSTOP_Viper650() );
769 "Cannot stop robot motion.");
788 UInt32 HIPowerStatus;
790 bool firsttime =
true;
791 unsigned int nitermax = 10;
793 for (
unsigned int i=0; i<nitermax; i++) {
794 Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
796 if (EStopStatus == ESTOP_AUTO) {
800 else if (EStopStatus == ESTOP_MANUAL) {
804 else if (EStopStatus == ESTOP_ACTIVATED) {
807 std::cout <<
"Emergency stop is activated! \n"
808 <<
"Check the emergency stop button and push the yellow button before continuing." << std::endl;
811 fprintf(stdout,
"Remaining time %us \r", nitermax-i);
816 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
817 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
819 ShutDownConnection();
824 if (EStopStatus == ESTOP_ACTIVATED)
825 std::cout << std::endl;
827 if (EStopStatus == ESTOP_ACTIVATED) {
828 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
830 "Cannot power on the robot.");
833 if (HIPowerStatus == 0) {
834 fprintf(stdout,
"Power ON the Viper650 robot\n");
837 Try( PrimitivePOWERON_Viper650() );
844 "Cannot power off the robot.");
863 UInt32 HIPowerStatus;
864 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
868 if (HIPowerStatus == 1) {
869 fprintf(stdout,
"Power OFF the Viper650 robot\n");
872 Try( PrimitivePOWEROFF_Viper650() );
879 "Cannot power off the robot.");
900 UInt32 HIPowerStatus;
901 Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
905 if (HIPowerStatus == 1) {
913 "Cannot get the power status.");
973 Try( PrimitiveACQ_POS_J_Viper650(position, ×tamp) );
977 for (
unsigned int i=0; i <
njoint; i++)
1010 Try( PrimitiveACQ_POS_Viper650(position, ×tamp) );
1014 for (
unsigned int i=0; i <
njoint; i++)
1068 positioningVelocity = velocity;
1079 return positioningVelocity;
1168 "Modification of the robot state");
1180 Try( PrimitiveACQ_POS_Viper650(q.
data, ×tamp) );
1192 for (
unsigned int i=0; i < 3; i++) {
1193 txyz[i] = position[i];
1194 rxyz[i] = position[i+3];
1210 Try( PrimitiveMOVE_J_Viper650(destination.
data, positioningVelocity) );
1211 Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1221 destination = position;
1226 Try( PrimitiveMOVE_J_Viper650(destination.
data, positioningVelocity) );
1227 Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1233 vpRxyzVector rxyz(position[3],position[4],position[5]);
1237 for (
unsigned int i=0; i <3; i++) {
1238 destination[i] = position[i];
1241 int configuration = 0;
1244 Try( PrimitiveMOVE_C_Viper650(destination.
data, configuration,
1245 positioningVelocity) );
1246 Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1252 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1254 "Positionning error: "
1255 "Mixt frame not implemented.");
1260 if (TryStt == InvalidPosition || TryStt == -1023)
1261 std::cout <<
" : Position out of range.\n";
1263 else if (TryStt == -3019) {
1265 std::cout <<
" : Joint position out of range.\n";
1267 std::cout <<
" : Cartesian position leads to a joint position out of range.\n";
1269 else if (TryStt < 0)
1270 std::cout <<
" : Unknown error (see Fabien).\n";
1271 else if (error == -1)
1272 std::cout <<
"Position out of range.\n";
1274 if (TryStt < 0 || error < 0) {
1277 "Position out of range.");
1358 position[0] = pos1 ;
1359 position[1] = pos2 ;
1360 position[2] = pos3 ;
1361 position[3] = pos4 ;
1362 position[4] = pos5 ;
1363 position[5] = pos6 ;
1423 "Bad position in filename.");
1512 Try( PrimitiveACQ_POS_J_Viper650(position.
data, ×tamp) );
1519 Try( PrimitiveACQ_POS_C_Viper650(position.
data, ×tamp) );
1523 for (
unsigned int i=3; i <6; i++)
1526 vpRzyzVector rzyz(position[3], position[4], position[5]);
1531 for (
unsigned int i=0; i <3; i++)
1532 position[i+3] = rxyz[i];
1542 vpERROR_TRACE (
"Cannot get position in mixt frame: not implemented");
1544 "Cannot get position in mixt frame: "
1553 "Cannot get position.");
1594 for (
unsigned int j=0;j<3;j++)
1595 RxyzVect[j]=posRxyz[j+3];
1600 for (
unsigned int j=0;j<3;j++)
1602 position[j]=posRxyz[j];
1603 position[j+3]=RtuVect[j];
1629 PrimitiveACQ_TIME_Viper650(×tamp);
1711 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1713 "Cannot send a velocity to the robot "
1714 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1727 for (
unsigned int i=0; i<3; i++)
1729 for (
unsigned int i=3; i<6; i++)
1742 for (
unsigned int i=0; i<6; i++)
1746 for (
unsigned int i=0; i<5; i++)
1762 Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPCAM_VIPER650) );
1770 Try( PrimitiveMOVESPEED_Viper650(vel_sat.
data) );
1775 std::cout <<
"Vitesse ref appliquee: " << vel_sat.
t();
1776 Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPFIX_VIPER650) );
1785 "Case not taken in account.");
1792 if (TryStt == VelStopOnJoint) {
1793 UInt32 axisInJoint[
njoint];
1794 PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1795 for (
unsigned int i=0; i <
njoint; i ++) {
1797 std::cout <<
"\nWarning: Velocity control stopped: axis "
1798 << i+1 <<
" on joint limit!" <<std::endl;
1802 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1803 if (TryString != NULL) {
1805 printf(
" Error sentence %s\n", TryString);
1896 Try( PrimitiveACQ_POS_J_Viper650(q_cur.
data, ×tamp) );
1897 time_cur = timestamp;
1903 if ( ! first_time_getvel ) {
1908 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1917 velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1923 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1938 cMc = fMc_prev_getvel.
inverse() * fMc_cur;
1946 for (
unsigned int i=0; i < 3; i++) {
1948 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1950 velocity[i+3] = thetaU[i];
1954 velocity /= (time_cur - time_prev_getvel);
1960 first_time_getvel =
false;
1964 fMc_prev_getvel = fMc_cur;
1967 q_prev_getvel = q_cur;
1970 time_prev_getvel = time_cur;
1977 "Cannot get velocity.");
2138 std::ifstream fd(filename.c_str(), std::ios::in);
2140 if(! fd.is_open()) {
2145 std::string key(
"R:");
2146 std::string id(
"#Viper650 - Position");
2147 bool pos_found =
false;
2152 while(std::getline(fd, line)) {
2155 if(! (line.compare(0,
id.size(), id) == 0)) {
2156 std::cout <<
"Error: this position file " << filename <<
" is not for Viper650 robot" << std::endl;
2160 if((line.compare(0, 1,
"#") == 0)) {
2163 if((line.compare(0, key.size(), key) == 0)) {
2166 if (chain.size() <
njoint+1)
2168 if(chain.size() <
njoint+1)
2171 std::istringstream ss(line);
2174 for (
unsigned int i=0; i<
njoint; i++)
2187 std::cout <<
"Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2222 fd = fopen(filename.c_str(),
"w") ;
2227 #Viper650 - Position - Version 1.00\n\
2230 # Joint position in degrees\n\
2235 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2287 vpRobotViper650::getCameraDisplacement(
vpColVector &displacement)
2303 vpRobotViper650::getArticularDisplacement(
vpColVector &displacement)
2342 Try( PrimitiveACQ_POS_Viper650(q, ×tamp) );
2343 for (
unsigned int i=0; i <
njoint; i ++) {
2347 if ( ! first_time_getdis ) {
2350 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2355 displacement = q_cur - q_prev_getdis;
2360 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2365 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2371 first_time_getdis =
false;
2375 q_prev_getdis = q_cur;
2381 "Cannot get velocity.");
2403 Try( PrimitiveTFS_BIAS_Viper650() );
2412 "Cannot bias the force/torque sensor.");
2461 Try( PrimitiveTFS_ACQ_Viper650(H.
data) );
2467 "Cannot get force/torque measures.");
2514 Try( PrimitiveTFS_ACQ_Viper650(H.
data) );
2522 "Cannot get force/torque measures.");
2535 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
2536 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2541 "Cannot enable joint limits on axis 6.");
2557 Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1) );
2558 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2563 "Cannot disable joint limits on axis 6.");
2605 maxRotationVelocity_joint6 = w6_max;
2618 return maxRotationVelocity_joint6;
2630 Try( PrimitivePneumaticGripper_Viper650(1) );
2631 std::cout <<
"Open the pneumatic gripper..." << std::endl;
2635 "Cannot open the gripper.");
2649 Try( PrimitivePneumaticGripper_Viper650(0) );
2650 std::cout <<
"Close the pneumatic gripper..." << std::endl;
2654 "Cannot close the gripper.");
2658 #elif !defined(VISP_BUILD_SHARED_LIBS)
2660 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)
vpColVector getForceTorque() const
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 closeGripper() const
double getMaxRotationVelocity(void) const
static bool savePosFile(const std::string &filename, const vpColVector &q)
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
VISP_EXPORT void sleepMs(double t)
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
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.
Implementation of a pose vector and operations on poses.
vpHomogeneousMatrix inverse() const
void move(const std::string &filename)
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)
static bool readPosFile(const std::string &filename, vpColVector &q)
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.
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)