34#include <visp3/core/vpConfig.h>
36#ifdef VISP_HAVE_VIPER650
43#include <visp3/core/vpDebug.h>
44#include <visp3/core/vpExponentialMap.h>
45#include <visp3/core/vpIoTools.h>
46#include <visp3/core/vpThetaUVector.h>
47#include <visp3/core/vpVelocityTwistMatrix.h>
48#include <visp3/robot/vpRobot.h>
49#include <visp3/robot/vpRobotException.h>
50#include <visp3/robot/vpRobotViper650.h>
57bool vpRobotViper650::m_robotAlreadyCreated =
false;
79void emergencyStopViper650(
int signo)
81 std::cout <<
"Stop the Viper650 application by signal (" << signo <<
"): " <<
static_cast<char>(7);
84 std::cout <<
"SIGINT (stop by ^C) " << std::endl;
87 std::cout <<
"SIGBUS (stop due to a bus error) " << std::endl;
90 std::cout <<
"SIGSEGV (stop due to a segmentation fault) " << std::endl;
93 std::cout <<
"SIGKILL (stop by CTRL \\) " << std::endl;
96 std::cout <<
"SIGQUIT " << std::endl;
99 std::cout << signo << std::endl;
103 PrimitiveSTOP_Viper650();
104 std::cout <<
"Robot was stopped\n";
109 fprintf(stdout,
"Application ");
111 kill(getpid(), SIGKILL);
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::m_robotAlreadyCreated =
true;
256 m_q_prev_getvel.resize(6);
258 m_time_prev_getvel = 0;
259 m_first_time_getvel =
true;
262 m_q_prev_getdis.resize(6);
264 m_first_time_getdis =
true;
267 Try(InitializeConnection(
verbose_));
270 Try(InitializeNode_Viper650());
272 Try(PrimitiveRESET_Viper650());
275 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
281 UInt32 HIPowerStatus;
283 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
288 std::cout <<
"Robot status: ";
289 switch (EStopStatus) {
291 m_controlMode =
AUTO;
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:
306 m_controlMode =
ESTOP;
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;
332 if (TryStt == -20001)
333 printf(
"No connection detected. Check if the robot is powered on \n"
334 "and if the firewire link exist between the MotionBlox and this "
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;
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));
517 for (
unsigned int i = 0; i < 3; i++) {
518 eMc_pose[i] =
etc[i];
519 eMc_pose[i + 3] =
erc[i];
522 Try(PrimitiveCONST_Viper650(eMc_pose));
587 for (
unsigned int i = 0; i < 3; i++) {
588 eMc_pose[i] =
etc[i];
589 eMc_pose[i + 3] =
erc[i];
592 Try(PrimitiveCONST_Viper650(eMc_pose));
617 for (
unsigned int i = 0; i < 3; i++) {
618 eMc_pose[i] =
etc[i];
619 eMc_pose[i + 3] =
erc[i];
622 Try(PrimitiveCONST_Viper650(eMc_pose));
649 for (
unsigned int i = 0; i < 3; i++) {
650 eMc_pose[i] =
etc[i];
651 eMc_pose[i + 3] =
erc[i];
654 Try(PrimitiveCONST_Viper650(eMc_pose));
678 UInt32 HIPowerStatus;
679 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
690 ShutDownConnection();
692 vpRobotViper650::m_robotAlreadyCreated =
false;
712 Try(PrimitiveSTOP_Viper650());
719 std::cout <<
"Change the control mode from velocity to position control.\n";
720 Try(PrimitiveSTOP_Viper650());
731 std::cout <<
"Change the control mode from stop to velocity control.\n";
762 Try(PrimitiveSTOP_Viper650());
786 UInt32 HIPowerStatus;
788 bool firsttime =
true;
789 unsigned int nitermax = 10;
791 for (
unsigned int i = 0; i < nitermax; i++) {
792 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
793 if (EStopStatus == ESTOP_AUTO) {
794 m_controlMode =
AUTO;
797 else if (EStopStatus == ESTOP_MANUAL) {
801 else if (EStopStatus == ESTOP_ACTIVATED) {
802 m_controlMode =
ESTOP;
804 std::cout <<
"Emergency stop is activated! \n"
805 <<
"Check the emergency stop button and push the yellow "
806 "button before continuing."
810 fprintf(stdout,
"Remaining time %us \r", nitermax - i);
815 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
816 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
818 ShutDownConnection();
823 if (EStopStatus == ESTOP_ACTIVATED)
824 std::cout << std::endl;
826 if (EStopStatus == ESTOP_ACTIVATED) {
827 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
831 if (HIPowerStatus == 0) {
832 fprintf(stdout,
"Power ON the Viper650 robot\n");
835 Try(PrimitivePOWERON_Viper650());
859 UInt32 HIPowerStatus;
860 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
863 if (HIPowerStatus == 1) {
864 fprintf(stdout,
"Power OFF the Viper650 robot\n");
867 Try(PrimitivePOWEROFF_Viper650());
893 UInt32 HIPowerStatus;
894 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
897 if (HIPowerStatus == 1) {
957 Try(PrimitiveACQ_POS_J_Viper650(position, ×tamp));
961 for (
unsigned int i = 0; i <
njoint; i++)
991 Try(PrimitiveACQ_POS_Viper650(position, ×tamp));
995 for (
unsigned int i = 0; i <
njoint; i++)
1141 "Modification of the robot state");
1153 Try(PrimitiveACQ_POS_Viper650(q.
data, ×tamp));
1165 for (
unsigned int i = 0; i < 3; i++) {
1166 txyz[i] = position[i];
1167 rxyz[i] = position[i + 3];
1183 Try(PrimitiveMOVE_J_Viper650(destination.
data, m_positioningVelocity));
1184 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1194 destination = position;
1200 Try(PrimitiveMOVE_J_Viper650(destination.
data, m_positioningVelocity));
1201 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1206 vpRxyzVector rxyz(position[3], position[4], position[5]);
1210 for (
unsigned int i = 0; i < 3; i++) {
1211 destination[i] = position[i];
1214 int configuration = 0;
1218 Try(PrimitiveMOVE_C_Viper650(destination.
data, configuration, m_positioningVelocity));
1219 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1225 "Mixt frame not implemented.");
1229 "Mixt frame not implemented.");
1234 if (TryStt == InvalidPosition || TryStt == -1023)
1235 std::cout <<
" : Position out of range.\n";
1237 else if (TryStt == -3019) {
1239 std::cout <<
" : Joint position out of range.\n";
1241 std::cout <<
" : Cartesian position leads to a joint position out of "
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) {
1326 double pos4,
double pos5,
double pos6)
1486 Try(PrimitiveACQ_POS_J_Viper650(position.
data, ×tamp));
1494 Try(PrimitiveACQ_POS_J_Viper650(q.
data, ×tamp));
1505 for (
unsigned int i = 0; i < 3; i++) {
1506 position[i] = fMc[i][3];
1507 position[i + 3] = rxyz[i];
1566 for (
unsigned int j = 0; j < 3; j++)
1567 RxyzVect[j] = posRxyz[j + 3];
1572 for (
unsigned int j = 0; j < 3; j++) {
1573 position[j] = posRxyz[j];
1574 position[j + 3] = RtuVect[j];
1601 PrimitiveACQ_TIME_Viper650(×tamp);
1690 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1692 "Cannot send a velocity to the robot "
1693 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1707 for (
unsigned int i = 0; i < 3; i++)
1709 for (
unsigned int i = 3; i < 6; i++)
1722 for (
unsigned int i = 0; i < 6; i++)
1726 for (
unsigned int i = 0; i < 5; i++)
1741 Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPCAM_VIPER650));
1751 Try(PrimitiveMOVESPEED_CART_Viper650(v_c.
data, REPCAM_VIPER650));
1759 Try(PrimitiveMOVESPEED_Viper650(vel_sat.
data));
1765 Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPFIX_VIPER650));
1774 "Case not taken in account.");
1781 if (TryStt == VelStopOnJoint) {
1782 UInt32 axisInJoint[
njoint];
1783 PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, axisInJoint,
nullptr);
1784 for (
unsigned int i = 0; i <
njoint; i++) {
1786 std::cout <<
"\nWarning: Velocity control stopped: axis " << i + 1 <<
" on joint limit!" << std::endl;
1790 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1791 if (TryString !=
nullptr) {
1793 printf(
" Error sentence %s\n", TryString);
1881 Try(PrimitiveACQ_POS_J_Viper650(q_cur.
data, ×tamp));
1882 time_cur = timestamp;
1890 if (!m_first_time_getvel) {
1895 eMe = m_fMe_prev_getvel.
inverse() * fMe_cur;
1905 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1914 velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1920 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1935 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1943 for (
unsigned int i = 0; i < 3; i++) {
1945 velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1947 velocity[i + 3] = thetaU[i];
1951 velocity /= (time_cur - m_time_prev_getvel);
1956 "vpRobotViper650::getVelocity() not implemented in end-effector"));
1961 m_first_time_getvel =
false;
1965 m_fMe_prev_getvel = fMe_cur;
1967 m_fMc_prev_getvel = fMc_cur;
1970 m_q_prev_getvel = q_cur;
1973 m_time_prev_getvel = time_cur;
2145 std::ifstream fd(filename.c_str(), std::ios::in);
2147 if (!fd.is_open()) {
2152 std::string key(
"R:");
2153 std::string id(
"#Viper650 - Position");
2154 bool pos_found =
false;
2159 while (std::getline(fd, line)) {
2162 if (!(line.compare(0,
id.size(),
id) == 0)) {
2163 std::cout <<
"Error: this position file " << filename <<
" is not for Viper650 robot" << std::endl;
2167 if ((line.compare(0, 1,
"#") == 0)) {
2170 if ((line.compare(0, key.size(), key) == 0)) {
2173 if (chain.size() <
njoint + 1)
2175 if (chain.size() <
njoint + 1)
2178 std::istringstream ss(line);
2181 for (
unsigned int i = 0; i <
njoint; i++)
2194 std::cout <<
"Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2228 fd = fopen(filename.c_str(),
"w");
2233#Viper650 - Position - Version 1.00\n\
2236# Joint position in degrees\n\
2303 Try(PrimitiveACQ_POS_Viper650(q, ×tamp));
2304 for (
unsigned int i = 0; i <
njoint; i++) {
2308 if (!m_first_time_getdis) {
2311 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2316 displacement = q_cur - m_q_prev_getdis;
2321 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2326 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2330 std::cout <<
"getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2336 m_first_time_getdis =
false;
2340 m_q_prev_getdis = q_cur;
2366 Try(PrimitiveTFS_BIAS_Viper650());
2426 Try(PrimitiveTFS_ACQ_Viper650(H.
data));
2481 Try(PrimitiveTFS_ACQ_Viper650(H.
data));
2501 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
2502 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2523 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1));
2524 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2569 m_maxRotationVelocity_joint6 = w6_max;
2591 Try(PrimitivePneumaticGripper_Viper650(1));
2592 std::cout <<
"Open the pneumatic gripper..." << std::endl;
2609 Try(PrimitivePneumaticGripper_Viper650(0));
2610 std::cout <<
"Close the pneumatic gripper..." << std::endl;
2617#elif !defined(VISP_BUILD_SHARED_LIBS)
2620void dummy_vpRobotViper650() { }
Type * data
Address of the first element of the data array.
vpCameraParametersProjType
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
error that can be emitted by ViSP classes.
@ functionNotImplementedError
Function not implemented.
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
static double rad(double deg)
static double deg(double rad)
Implementation of a matrix and operations on matrices.
Implementation of a pose vector and operations on poses.
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ constructionError
Error from constructor.
@ positionOutOfRangeError
Position is out of range.
@ lowLevelError
Error thrown by the low level sdk.
void move(const std::string &filename)
void set_eMc(const vpHomogeneousMatrix &eMc_)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
static const double m_defaultPositioningVelocity
virtual ~vpRobotViper650(void)
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void setPositioningVelocity(double velocity)
void enableJoint6Limits() const
void get_cVe(vpVelocityTwistMatrix &cVe) const
vpColVector getForceTorque() const
bool getPowerState() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocityJoint6(double w6_max)
void disableJoint6Limits() const
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
void biasForceTorqueSensor() const
void get_cMe(vpHomogeneousMatrix &cMe) const
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
@ AUTO
Automatic control mode (default).
@ ESTOP
Emergency stop activated.
double getMaxRotationVelocityJoint6() const
void setMaxRotationVelocity(double w_max)
static bool readPosFile(const std::string &filename, vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
double getPositioningVelocity(void) const
void closeGripper() const
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
void setVerbose(bool verbose)
virtual vpRobotStateType getRobotState(void) const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
@ STATE_POSITION_CONTROL
Initialize the position controller.
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
double getMaxRotationVelocity(void) const
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
double getMaxTranslationVelocity(void) const
double maxRotationVelocity
void setMaxRotationVelocity(double maxVr)
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
vpRxyzVector & buildFrom(const vpRotationMatrix &R)
Implementation of a rotation vector as Euler angle minimal representation.
Implementation of a rotation vector as axis-angle minimal representation.
vpThetaUVector & buildFrom(const vpHomogeneousMatrix &M)
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpCameraParameters::vpCameraParametersProjType projModel
static const vpToolType defaultTool
Default tool attached to the robot end effector.
vpToolType
List of possible tools that can be attached to the robot end-effector.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
static const unsigned int njoint
Number of joint.
void get_cMe(vpHomogeneousMatrix &cMe) const
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT void sleepMs(double t)