34#include <visp3/core/vpConfig.h>
36#ifdef VISP_HAVE_VIPER850
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/vpRobotViper850.h>
57bool vpRobotViper850::m_robotAlreadyCreated =
false;
79void emergencyStopViper850(
int signo)
81 std::cout <<
"Stop the Viper850 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_Viper850();
104 std::cout <<
"Robot was stopped\n";
109 fprintf(stdout,
"Application ");
111 kill(getpid(), SIGKILL);
198 signal(SIGINT, emergencyStopViper850);
199 signal(SIGBUS, emergencyStopViper850);
200 signal(SIGSEGV, emergencyStopViper850);
201 signal(SIGKILL, emergencyStopViper850);
202 signal(SIGQUIT, emergencyStopViper850);
206 std::cout <<
"Open communication with MotionBlox.\n";
219 vpRobotViper850::m_robotAlreadyCreated =
true;
257 m_q_prev_getvel.resize(6);
259 m_time_prev_getvel = 0;
260 m_first_time_getvel =
true;
263 m_q_prev_getdis.resize(6);
265 m_first_time_getdis =
true;
267#if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
268 std::string calibfile;
269#ifdef VISP_HAVE_VIPER850_DATA
270 calibfile = std::string(VISP_VIPER850_DATA_PATH) + std::string(
"/ati/FT17824.cal");
275 "data to retrieve ATI F/T calib "
278 m_ati.setCalibrationFile(calibfile);
283 Try(InitializeConnection(
verbose_));
286 Try(InitializeNode_Viper850());
288 Try(PrimitiveRESET_Viper850());
291 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
297 UInt32 HIPowerStatus;
299 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
304 std::cout <<
"Robot status: ";
305 switch (EStopStatus) {
307 m_controlMode =
AUTO;
308 if (HIPowerStatus == 0)
309 std::cout <<
"Power is OFF" << std::endl;
311 std::cout <<
"Power is ON" << std::endl;
316 if (HIPowerStatus == 0)
317 std::cout <<
"Power is OFF" << std::endl;
319 std::cout <<
"Power is ON" << std::endl;
321 case ESTOP_ACTIVATED:
322 m_controlMode =
ESTOP;
323 std::cout <<
"Emergency stop is activated" << std::endl;
326 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
327 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
330 std::cout << std::endl;
348 if (TryStt == -20001)
349 printf(
"No connection detected. Check if the robot is powered on \n"
350 "and if the firewire link exist between the MotionBlox and this "
352 else if (TryStt == -675)
353 printf(
" Timeout enabling power...\n");
357 PrimitivePOWEROFF_Viper850();
359 ShutDownConnection();
361 std::cout <<
"Cannot open connection with the motionblox..." << std::endl;
449 for (
unsigned int i = 0; i < 3; i++) {
450 eMc_pose[i] =
etc[i];
451 eMc_pose[i + 3] =
erc[i];
454 Try(PrimitiveCONST_Viper850(eMc_pose));
533 for (
unsigned int i = 0; i < 3; i++) {
534 eMc_pose[i] =
etc[i];
535 eMc_pose[i + 3] =
erc[i];
538 Try(PrimitiveCONST_Viper850(eMc_pose));
603 for (
unsigned int i = 0; i < 3; i++) {
604 eMc_pose[i] =
etc[i];
605 eMc_pose[i + 3] =
erc[i];
608 Try(PrimitiveCONST_Viper850(eMc_pose));
633 for (
unsigned int i = 0; i < 3; i++) {
634 eMc_pose[i] =
etc[i];
635 eMc_pose[i + 3] =
erc[i];
638 Try(PrimitiveCONST_Viper850(eMc_pose));
665 for (
unsigned int i = 0; i < 3; i++) {
666 eMc_pose[i] =
etc[i];
667 eMc_pose[i + 3] =
erc[i];
670 Try(PrimitiveCONST_Viper850(eMc_pose));
689#if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
698 UInt32 HIPowerStatus;
699 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
710 ShutDownConnection();
712 vpRobotViper850::m_robotAlreadyCreated =
false;
732 Try(PrimitiveSTOP_Viper850());
739 std::cout <<
"Change the control mode from velocity to position control.\n";
740 Try(PrimitiveSTOP_Viper850());
751 std::cout <<
"Change the control mode from stop to velocity control.\n";
782 Try(PrimitiveSTOP_Viper850());
806 UInt32 HIPowerStatus;
808 bool firsttime =
true;
809 unsigned int nitermax = 10;
811 for (
unsigned int i = 0; i < nitermax; i++) {
812 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr, &EStopStatus,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
813 if (EStopStatus == ESTOP_AUTO) {
814 m_controlMode =
AUTO;
817 else if (EStopStatus == ESTOP_MANUAL) {
821 else if (EStopStatus == ESTOP_ACTIVATED) {
822 m_controlMode =
ESTOP;
824 std::cout <<
"Emergency stop is activated! \n"
825 <<
"Check the emergency stop button and push the yellow "
826 "button before continuing."
830 fprintf(stdout,
"Remaining time %us \r", nitermax - i);
835 std::cout <<
"Sorry there is an error on the emergency chain." << std::endl;
836 std::cout <<
"You have to call Adept for maintenance..." << std::endl;
838 ShutDownConnection();
843 if (EStopStatus == ESTOP_ACTIVATED)
844 std::cout << std::endl;
846 if (EStopStatus == ESTOP_ACTIVATED) {
847 std::cout <<
"Sorry, cannot power on the robot." << std::endl;
851 if (HIPowerStatus == 0) {
852 fprintf(stdout,
"Power ON the Viper850 robot\n");
855 Try(PrimitivePOWERON_Viper850());
879 UInt32 HIPowerStatus;
880 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
883 if (HIPowerStatus == 1) {
884 fprintf(stdout,
"Power OFF the Viper850 robot\n");
887 Try(PrimitivePOWEROFF_Viper850());
913 UInt32 HIPowerStatus;
914 Try(PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, &HIPowerStatus));
917 if (HIPowerStatus == 1) {
977 Try(PrimitiveACQ_POS_J_Viper850(position, ×tamp));
981 for (
unsigned int i = 0; i <
njoint; i++)
1011 Try(PrimitiveACQ_POS_Viper850(position, ×tamp));
1015 for (
unsigned int i = 0; i <
njoint; i++)
1161 "Modification of the robot state");
1173 Try(PrimitiveACQ_POS_Viper850(q.
data, ×tamp));
1185 for (
unsigned int i = 0; i < 3; i++) {
1186 txyz[i] = position[i];
1187 rxyz[i] = position[i + 3];
1203 Try(PrimitiveMOVE_J_Viper850(destination.
data, m_positioningVelocity));
1204 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1214 destination = position;
1220 Try(PrimitiveMOVE_J_Viper850(destination.
data, m_positioningVelocity));
1221 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1226 vpRxyzVector rxyz(position[3], position[4], position[5]);
1230 for (
unsigned int i = 0; i < 3; i++) {
1231 destination[i] = position[i];
1234 int configuration = 0;
1238 Try(PrimitiveMOVE_C_Viper850(destination.
data, configuration, m_positioningVelocity));
1239 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1245 "Mixt frame not implemented.");
1249 "End-effector frame not implemented.");
1254 if (TryStt == InvalidPosition || TryStt == -1023)
1255 std::cout <<
" : Position out of range.\n";
1256 else if (TryStt == -3019) {
1258 std::cout <<
" : Joint position out of range.\n";
1260 std::cout <<
" : Cartesian position leads to a joint position out of "
1263 else if (TryStt < 0)
1264 std::cout <<
" : Unknown error (see Fabien).\n";
1265 else if (error == -1)
1266 std::cout <<
"Position out of range.\n";
1268 if (TryStt < 0 || error < 0) {
1345 double pos4,
double pos5,
double pos6)
1505 Try(PrimitiveACQ_POS_J_Viper850(position.
data, ×tamp));
1513 Try(PrimitiveACQ_POS_J_Viper850(q.
data, ×tamp));
1524 for (
unsigned int i = 0; i < 3; i++) {
1525 position[i] = fMc[i][3];
1526 position[i + 3] = rxyz[i];
1557 PrimitiveACQ_TIME_Viper850(×tamp);
1594 for (
unsigned int j = 0; j < 3; j++)
1595 RxyzVect[j] = posRxyz[j + 3];
1600 for (
unsigned int j = 0; j < 3; j++) {
1601 position[j] = posRxyz[j];
1602 position[j + 3] = RtuVect[j];
1623 for (
unsigned int j = 0; j < 3; j++)
1624 RxyzVect[j] = posRxyz[j + 3];
1629 for (
unsigned int j = 0; j < 3; j++) {
1630 position[j] = posRxyz[j];
1631 position[j + 3] = RtuVect[j];
1720 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1722 "Cannot send a velocity to the robot "
1723 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1737 for (
unsigned int i = 0; i < 3; i++)
1739 for (
unsigned int i = 3; i < 6; i++)
1753 for (
unsigned int i = 0; i < 6; i++)
1757 for (
unsigned int i = 0; i < 5; i++)
1772 Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPCAM_VIPER850));
1782 Try(PrimitiveMOVESPEED_CART_Viper850(v_c.
data, REPCAM_VIPER850));
1790 Try(PrimitiveMOVESPEED_Viper850(vel_sat.
data));
1796 Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.
data, REPFIX_VIPER850));
1805 "Case not taken in account.");
1812 if (TryStt == VelStopOnJoint) {
1813 UInt32 axisInJoint[
njoint];
1814 PrimitiveSTATUS_Viper850(
nullptr,
nullptr,
nullptr,
nullptr,
nullptr, axisInJoint,
nullptr);
1815 for (
unsigned int i = 0; i <
njoint; i++) {
1817 std::cout <<
"\nWarning: Velocity control stopped: axis " << i + 1 <<
" on joint limit!" << std::endl;
1821 printf(
"\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1822 if (TryString !=
nullptr) {
1824 printf(
" Error sentence %s\n", TryString);
1912 Try(PrimitiveACQ_POS_J_Viper850(q_cur.
data, ×tamp));
1913 time_cur = timestamp;
1921 if (!m_first_time_getvel) {
1926 eMe = m_fMe_prev_getvel.
inverse() * fMe_cur;
1936 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1945 velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1951 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1966 cMc = m_fMc_prev_getvel.
inverse() * fMc_cur;
1974 for (
unsigned int i = 0; i < 3; i++) {
1976 velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1978 velocity[i + 3] = thetaU[i];
1982 velocity /= (time_cur - m_time_prev_getvel);
1987 "vpRobotViper850::getVelocity() not implemented in end-effector"));
1992 m_first_time_getvel =
false;
1996 m_fMe_prev_getvel = fMe_cur;
1998 m_fMc_prev_getvel = fMc_cur;
2001 m_q_prev_getvel = q_cur;
2004 m_time_prev_getvel = time_cur;
2176 std::ifstream fd(filename.c_str(), std::ios::in);
2178 if (!fd.is_open()) {
2183 std::string key(
"R:");
2184 std::string id(
"#Viper850 - Position");
2185 bool pos_found =
false;
2190 while (std::getline(fd, line)) {
2193 if (!(line.compare(0,
id.size(),
id) == 0)) {
2194 std::cout <<
"Error: this position file " << filename <<
" is not for Viper850 robot" << std::endl;
2198 if ((line.compare(0, 1,
"#") == 0)) {
2201 if ((line.compare(0, key.size(), key) == 0)) {
2204 if (chain.size() <
njoint + 1)
2206 if (chain.size() <
njoint + 1)
2209 std::istringstream ss(line);
2212 for (
unsigned int i = 0; i <
njoint; i++)
2225 std::cout <<
"Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2259 fd = fopen(filename.c_str(),
"w");
2264#Viper850 - Position - Version 1.00\n\
2267# Joint position in degrees\n\
2334 Try(PrimitiveACQ_POS_Viper850(q, ×tamp));
2335 for (
unsigned int i = 0; i <
njoint; i++) {
2339 if (!m_first_time_getdis) {
2342 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
2347 displacement = q_cur - m_q_prev_getdis;
2352 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
2357 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
2361 std::cout <<
"getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2367 m_first_time_getdis =
false;
2371 m_q_prev_getdis = q_cur;
2389#if defined(USE_ATI_DAQ)
2390#if defined(VISP_HAVE_COMEDI)
2394 "apt-get install libcomedi-dev"));
2399 Try(PrimitiveTFS_BIAS_Viper850());
2421#if defined(USE_ATI_DAQ)
2422#if defined(VISP_HAVE_COMEDI)
2426 "apt-get install libcomedi-dev"));
2478#if defined(USE_ATI_DAQ)
2479#if defined(VISP_HAVE_COMEDI)
2480 H = m_ati.getForceTorque();
2484 "apt-get install libcomedi-dev"));
2491 Try(PrimitiveTFS_ACQ_Viper850(H.
data));
2544#if defined(USE_ATI_DAQ)
2545#if defined(VISP_HAVE_COMEDI)
2550 "apt-get install libcomedi-dev"));
2557 Try(PrimitiveTFS_ACQ_Viper850(H.
data));
2578 Try(PrimitivePneumaticGripper_Viper850(1));
2579 std::cout <<
"Open the pneumatic gripper..." << std::endl;
2596 Try(PrimitivePneumaticGripper_Viper850(0));
2597 std::cout <<
"Close the pneumatic gripper..." << std::endl;
2612 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
2613 std::cout <<
"Enable joint limits on axis 6..." << std::endl;
2634 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1));
2635 std::cout <<
"Warning: Disable joint limits on axis 6..." << std::endl;
2681 maxRotationVelocity_joint6 = w6_max;
2694#elif !defined(VISP_BUILD_SHARED_LIBS)
2697void dummy_vpRobotViper850() { }
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.
vpColVector getForceTorque() const
void get_cVe(vpVelocityTwistMatrix &cVe) const
virtual ~vpRobotViper850(void)
static const double m_defaultPositioningVelocity
bool getPowerState() const
void set_eMc(const vpHomogeneousMatrix &eMc_)
void setMaxRotationVelocity(double w_max)
void closeGripper() const
void setMaxRotationVelocityJoint6(double w6_max)
void biasForceTorqueSensor()
void unbiasForceTorqueSensor()
void disableJoint6Limits() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
void enableJoint6Limits() const
@ AUTO
Automatic control mode (default).
@ ESTOP
Emergency stop activated.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
double getPositioningVelocity(void) const
static bool readPosFile(const std::string &filename, vpColVector &q)
void setPositioningVelocity(double velocity)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
void get_cMe(vpHomogeneousMatrix &cMe) const
void move(const std::string &filename)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
double getMaxRotationVelocityJoint6() const
static bool savePosFile(const std::string &filename, const vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
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)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
vpCameraParameters::vpCameraParametersProjType projModel
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)