36 #include <visp3/core/vpConfig.h>
38 #ifdef VISP_HAVE_VIPER650
42 #include <sys/types.h>
45 #include <visp3/core/vpDebug.h>
46 #include <visp3/core/vpExponentialMap.h>
47 #include <visp3/core/vpIoTools.h>
48 #include <visp3/core/vpThetaUVector.h>
49 #include <visp3/core/vpVelocityTwistMatrix.h>
50 #include <visp3/robot/vpRobot.h>
51 #include <visp3/robot/vpRobotException.h>
52 #include <visp3/robot/vpRobotViper650.h>
59 bool vpRobotViper650::m_robotAlreadyCreated =
false;
81 void emergencyStopViper650(
int signo)
83 std::cout <<
"Stop the Viper650 application by signal (" << signo <<
"): " << (char)7;
86 std::cout <<
"SIGINT (stop by ^C) " << std::endl;
89 std::cout <<
"SIGBUS (stop due to a bus error) " << std::endl;
92 std::cout <<
"SIGSEGV (stop due to a segmentation fault) " << std::endl;
95 std::cout <<
"SIGKILL (stop by CTRL \\) " << std::endl;
98 std::cout <<
"SIGQUIT " << std::endl;
101 std::cout << signo << std::endl;
105 PrimitiveSTOP_Viper650();
106 std::cout <<
"Robot was stopped\n";
111 fprintf(stdout,
"Application ");
113 kill(getpid(), SIGKILL);
201 signal(SIGINT, emergencyStopViper650);
202 signal(SIGBUS, emergencyStopViper650);
203 signal(SIGSEGV, emergencyStopViper650);
204 signal(SIGKILL, emergencyStopViper650);
205 signal(SIGQUIT, emergencyStopViper650);
209 std::cout <<
"Open communication with MotionBlox.\n";
222 vpRobotViper650::m_robotAlreadyCreated =
true;
258 m_q_prev_getvel.
resize(6);
260 m_time_prev_getvel = 0;
261 m_first_time_getvel =
true;
264 m_q_prev_getdis.
resize(6);
266 m_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(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
290 std::cout <<
"Robot status: ";
291 switch (EStopStatus) {
293 m_controlMode =
AUTO;
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:
308 m_controlMode =
ESTOP;
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;
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 "
338 else if (TryStt == -675)
339 printf(
" Timeout enabling power...\n");
343 PrimitivePOWEROFF_Viper650();
345 ShutDownConnection();
347 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
435 for (
unsigned int i = 0; i < 3; i++) {
436 eMc_pose[i] =
etc[i];
437 eMc_pose[i + 3] =
erc[i];
440 Try(PrimitiveCONST_Viper650(eMc_pose));
519 for (
unsigned int i = 0; i < 3; i++) {
520 eMc_pose[i] =
etc[i];
521 eMc_pose[i + 3] =
erc[i];
524 Try(PrimitiveCONST_Viper650(eMc_pose));
589 for (
unsigned int i = 0; i < 3; i++) {
590 eMc_pose[i] =
etc[i];
591 eMc_pose[i + 3] =
erc[i];
594 Try(PrimitiveCONST_Viper650(eMc_pose));
619 for (
unsigned int i = 0; i < 3; i++) {
620 eMc_pose[i] =
etc[i];
621 eMc_pose[i + 3] =
erc[i];
624 Try(PrimitiveCONST_Viper650(eMc_pose));
651 for (
unsigned int i = 0; i < 3; i++) {
652 eMc_pose[i] =
etc[i];
653 eMc_pose[i + 3] =
erc[i];
656 Try(PrimitiveCONST_Viper650(eMc_pose));
680 UInt32 HIPowerStatus;
681 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
692 ShutDownConnection();
694 vpRobotViper650::m_robotAlreadyCreated =
false;
714 Try(PrimitiveSTOP_Viper650());
721 std::cout <<
"Change the control mode from velocity to position control.\n";
722 Try(PrimitiveSTOP_Viper650());
733 std::cout <<
"Change the control mode from stop to velocity control.\n";
764 Try(PrimitiveSTOP_Viper650());
769 vpERROR_TRACE(
"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(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
795 if (EStopStatus == ESTOP_AUTO) {
796 m_controlMode =
AUTO;
799 else if (EStopStatus == ESTOP_MANUAL) {
803 else if (EStopStatus == ESTOP_ACTIVATED) {
804 m_controlMode =
ESTOP;
806 std::cout <<
"Emergency stop is activated! \n"
807 <<
"Check the emergency stop button and push the yellow "
808 "button before continuing."
812 fprintf(stdout,
"Remaining time %us \r", nitermax - i);
817 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
818 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
820 ShutDownConnection();
825 if (EStopStatus == ESTOP_ACTIVATED)
826 std::cout << std::endl;
828 if (EStopStatus == ESTOP_ACTIVATED) {
829 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
833 if (HIPowerStatus == 0) {
834 fprintf(stdout,
"Power ON the Viper650 robot\n");
837 Try(PrimitivePOWERON_Viper650());
842 vpERROR_TRACE(
"Cannot power on the robot");
861 UInt32 HIPowerStatus;
862 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
865 if (HIPowerStatus == 1) {
866 fprintf(stdout,
"Power OFF the Viper650 robot\n");
869 Try(PrimitivePOWEROFF_Viper650());
874 vpERROR_TRACE(
"Cannot power off the robot");
895 UInt32 HIPowerStatus;
896 Try(PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
899 if (HIPowerStatus == 1) {
905 vpERROR_TRACE(
"Cannot get the power status");
959 Try(PrimitiveACQ_POS_J_Viper650(position, ×tamp));
963 for (
unsigned int i = 0; i <
njoint; i++)
970 vpERROR_TRACE(
"catch exception ");
993 Try(PrimitiveACQ_POS_Viper650(position, ×tamp));
997 for (
unsigned int i = 0; i <
njoint; i++)
1004 vpERROR_TRACE(
"Error caught");
1142 vpERROR_TRACE(
"Robot was not in position-based control\n"
1143 "Modification of the robot state");
1155 Try(PrimitiveACQ_POS_Viper650(q.
data, ×tamp));
1167 for (
unsigned int i = 0; i < 3; i++) {
1168 txyz[i] = position[i];
1169 rxyz[i] = position[i + 3];
1185 Try(PrimitiveMOVE_J_Viper650(destination.
data, m_positioningVelocity));
1186 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1196 destination = position;
1202 Try(PrimitiveMOVE_J_Viper650(destination.
data, m_positioningVelocity));
1203 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1208 vpRxyzVector rxyz(position[3], position[4], position[5]);
1212 for (
unsigned int i = 0; i < 3; i++) {
1213 destination[i] = position[i];
1216 int configuration = 0;
1220 Try(PrimitiveMOVE_C_Viper650(destination.
data, configuration, m_positioningVelocity));
1221 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1227 "Mixt frame not implemented.");
1231 "Mixt frame not implemented.");
1236 if (TryStt == InvalidPosition || TryStt == -1023)
1237 std::cout <<
" : Position out of range.\n";
1239 else if (TryStt == -3019) {
1241 std::cout <<
" : Joint position out of range.\n";
1243 std::cout <<
" : Cartesian position leads to a joint position out of "
1246 else if (TryStt < 0)
1247 std::cout <<
" : Unknown error (see Fabien).\n";
1248 else if (error == -1)
1249 std::cout <<
"Position out of range.\n";
1251 if (TryStt < 0 || error < 0) {
1252 vpERROR_TRACE(
"Positioning error.");
1328 double pos4,
double pos5,
double pos6)
1342 vpERROR_TRACE(
"Error caught");
1397 vpERROR_TRACE(
"Bad position in \"%s\"", filename.c_str());
1488 Try(PrimitiveACQ_POS_J_Viper650(position.
data, ×tamp));
1496 Try(PrimitiveACQ_POS_J_Viper650(q.
data, ×tamp));
1507 for (
unsigned int i = 0; i < 3; i++) {
1508 position[i] = fMc[i][3];
1509 position[i + 3] = rxyz[i];
1526 vpERROR_TRACE(
"Cannot get position.");
1568 for (
unsigned int j = 0; j < 3; j++)
1569 RxyzVect[j] = posRxyz[j + 3];
1574 for (
unsigned int j = 0; j < 3; j++) {
1575 position[j] = posRxyz[j];
1576 position[j + 3] = RtuVect[j];
1603 PrimitiveACQ_TIME_Viper650(×tamp);
1691 vpERROR_TRACE(
"Cannot send a velocity to the robot "
1692 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1694 "Cannot send a velocity to the robot "
1695 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1709 for (
unsigned int i = 0; i < 3; i++)
1711 for (
unsigned int i = 3; i < 6; i++)
1724 for (
unsigned int i = 0; i < 6; i++)
1728 for (
unsigned int i = 0; i < 5; i++)
1743 Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPCAM_VIPER650));
1753 Try(PrimitiveMOVESPEED_CART_Viper650(v_c.
data, REPCAM_VIPER650));
1761 Try(PrimitiveMOVESPEED_Viper650(vel_sat.
data));
1767 Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.
data, REPFIX_VIPER650));
1775 vpERROR_TRACE(
"Error in spec of vpRobot. "
1776 "Case not taken in account.");
1783 if (TryStt == VelStopOnJoint) {
1784 UInt32 axisInJoint[
njoint];
1785 PrimitiveSTATUS_Viper650(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, axisInJoint,
nullptr);
1786 for (
unsigned int i = 0; i <
njoint; i++) {
1788 std::cout <<
"\nWarning: Velocity control stopped: axis " << i + 1 <<
" on joint limit!" << std::endl;
1792 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1793 if (TryString !=
nullptr) {
1795 printf(
" Error sentence %s\n", TryString);
1883 Try(PrimitiveACQ_POS_J_Viper650(q_cur.
data, ×tamp));
1884 time_cur = timestamp;
1892 if (!m_first_time_getvel) {
1897 eMe = m_fMe_prev_getvel.
inverse() * fMe_cur;
1907 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1916 velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1922 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1937 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1945 for (
unsigned int i = 0; i < 3; i++) {
1947 velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1949 velocity[i + 3] = thetaU[i];
1953 velocity /= (time_cur - m_time_prev_getvel);
1958 "vpRobotViper650::getVelocity() not implemented in end-effector"));
1963 m_first_time_getvel =
false;
1967 m_fMe_prev_getvel = fMe_cur;
1969 m_fMc_prev_getvel = fMc_cur;
1972 m_q_prev_getvel = q_cur;
1975 m_time_prev_getvel = time_cur;
1979 vpERROR_TRACE(
"Cannot get velocity.");
2147 std::ifstream fd(filename.c_str(), std::ios::in);
2149 if (!fd.is_open()) {
2154 std::string key(
"R:");
2155 std::string id(
"#Viper650 - Position");
2156 bool pos_found =
false;
2161 while (std::getline(fd, line)) {
2164 if (!(line.compare(0,
id.size(),
id) == 0)) {
2165 std::cout <<
"Error: this position file " << filename <<
" is not for Viper650 robot" << std::endl;
2169 if ((line.compare(0, 1,
"#") == 0)) {
2172 if ((line.compare(0, key.size(), key) == 0)) {
2175 if (chain.size() <
njoint + 1)
2177 if (chain.size() <
njoint + 1)
2180 std::istringstream ss(line);
2183 for (
unsigned int i = 0; i <
njoint; i++)
2196 std::cout <<
"Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2230 fd = fopen(filename.c_str(),
"w");
2235 #Viper650 - Position - Version 1.00\n\
2238 # Joint position in degrees\n\
2305 Try(PrimitiveACQ_POS_Viper650(q, ×tamp));
2306 for (
unsigned int i = 0; i <
njoint; i++) {
2310 if (!m_first_time_getdis) {
2313 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2318 displacement = q_cur - m_q_prev_getdis;
2323 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2328 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2332 std::cout <<
"getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2338 m_first_time_getdis =
false;
2342 m_q_prev_getdis = q_cur;
2346 vpERROR_TRACE(
"Cannot get velocity.");
2368 Try(PrimitiveTFS_BIAS_Viper650());
2375 vpERROR_TRACE(
"Cannot bias the force/torque sensor.");
2428 Try(PrimitiveTFS_ACQ_Viper650(H.
data));
2432 vpERROR_TRACE(
"Cannot get the force/torque measures.");
2483 Try(PrimitiveTFS_ACQ_Viper650(H.
data));
2489 vpERROR_TRACE(
"Cannot get the force/torque measures.");
2503 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
2504 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2507 vpERROR_TRACE(
"Cannot enable joint limits on axis 6");
2525 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1));
2526 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2529 vpERROR_TRACE(
"Cannot disable joint limits on axis 6");
2571 m_maxRotationVelocity_joint6 = w6_max;
2593 Try(PrimitivePneumaticGripper_Viper650(1));
2594 std::cout <<
"Open the pneumatic gripper..." << std::endl;
2611 Try(PrimitivePneumaticGripper_Viper650(0));
2612 std::cout <<
"Close the pneumatic gripper..." << std::endl;
2619 #elif !defined(VISP_BUILD_SHARED_LIBS)
2622 void 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)
Class that defines a generic virtual robot.
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)
Modelization of the ADEPT Viper 650 robot.
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)