39 #include <visp3/core/vpConfig.h> 41 #ifdef VISP_HAVE_FRANKA 43 #include <visp3/robot/vpRobotException.h> 44 #include <visp3/robot/vpRobotFranka.h> 45 #include <visp3/core/vpIoTools.h> 47 #include "vpJointPosTrajGenerator_impl.h" 48 #include "vpJointVelTrajGenerator_impl.h" 49 #include "vpForceTorqueGenerator_impl.h" 57 :
vpRobot(), m_handler(NULL), m_gripper(NULL), m_model(NULL), m_positionningVelocity(20.),
58 m_velControlThread(), m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false),
59 m_dq_des(), m_v_cart_des(),
60 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false),
61 m_tau_J_des(), m_ft_cart_des(),
62 m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(),
63 m_mutex(), m_eMc(), m_log_folder(), m_franka_address()
75 :
vpRobot(), m_handler(NULL), m_gripper(NULL), m_model(NULL), m_positionningVelocity(20.),
76 m_velControlThread(), m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false),
77 m_dq_des(), m_v_cart_des(),
78 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false),
79 m_tau_J_des(), m_ft_cart_des(),
80 m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(),
81 m_mutex(), m_eMc(),m_log_folder(), m_franka_address()
84 connect(franka_address, realtime_config);
90 void vpRobotFranka::init()
94 m_q_min = std::array<double, 7> {-2.8973, -1.7628, -2.8973, -3.0718, -2.8973, -0.0175, -2.8973};
95 m_q_max = std::array<double, 7> {2.8973, 1.7628, 2.8973, -0.0698, 2.8973, 3.7525, 2.8973};
96 m_dq_max = std::array<double, 7> {2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100};
97 m_ddq_max = std::array<double, 7> {15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0};
113 std::cout <<
"Grasped object, will release it now." << std::endl;
132 if(franka_address.empty()) {
138 m_franka_address = franka_address;
139 m_handler =
new franka::Robot(franka_address, realtime_config);
141 std::array<double, 7> lower_torque_thresholds_nominal{
142 {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.}};
143 std::array<double, 7> upper_torque_thresholds_nominal{
144 {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0}};
145 std::array<double, 7> lower_torque_thresholds_acceleration{
146 {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.0}};
147 std::array<double, 7> upper_torque_thresholds_acceleration{
148 {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0}};
149 std::array<double, 6> lower_force_thresholds_nominal{{30.0, 30.0, 30.0, 25.0, 25.0, 25.0}};
150 std::array<double, 6> upper_force_thresholds_nominal{{40.0, 40.0, 40.0, 35.0, 35.0, 35.0}};
151 std::array<double, 6> lower_force_thresholds_acceleration{{30.0, 30.0, 30.0, 25.0, 25.0, 25.0}};
152 std::array<double, 6> upper_force_thresholds_acceleration{{40.0, 40.0, 40.0, 35.0, 35.0, 35.0}};
153 m_handler->setCollisionBehavior(
154 lower_torque_thresholds_acceleration, upper_torque_thresholds_acceleration,
155 lower_torque_thresholds_nominal, upper_torque_thresholds_nominal,
156 lower_force_thresholds_acceleration, upper_force_thresholds_acceleration,
157 lower_force_thresholds_nominal, upper_force_thresholds_nominal);
159 m_handler->setJointImpedance({{3000, 3000, 3000, 2500, 2500, 2000, 2000}});
160 m_handler->setCartesianImpedance({{3000, 3000, 3000, 300, 300, 300}});
161 #if (VISP_HAVE_FRANKA_VERSION < 0x000500) 163 m_handler->setFilters(10, 10, 10, 10, 10);
170 m_model =
new franka::Model(m_handler->loadModel());
195 for (
int i=0; i < 7; i++) {
196 q[i] = robot_state.q[i];
208 for (
size_t i=0; i < 6; i++) {
209 position[i] = fPe[i];
217 for (
size_t i=0; i < 6; i++) {
218 position[i] = fPc[i];
252 for (
int i=0; i < 7; i++)
253 force[i] = robot_state.tau_J[i];
259 for (
int i=0; i < 6; i++)
260 force[i] = robot_state.K_F_ext_hat_K[i];
266 for (
int i=0; i < 6; i++)
267 eFe[i] = robot_state.K_F_ext_hat_K[i];
307 for (
int i=0; i < 7; i++) {
308 d_position[i]=robot_state.dq[i];
330 std::array<double, 7> coriolis_;
334 coriolis_ = m_model->coriolis(robot_state);
337 for (
int i=0; i < 7; i++) {
338 coriolis[i] = coriolis_[i];
352 std::array<double, 7> gravity_;
356 gravity_ = m_model->gravity(robot_state);
359 for (
int i=0; i < 7; i++) {
360 gravity[i] = gravity_[i];
374 std::array<double, 49> mass_;
378 mass_ = m_model->mass(robot_state);
381 for (
size_t i = 0; i < 7; i ++) {
382 for (
size_t j = 0; j < 7; j ++) {
383 mass[i][j] = mass_[j*7 + i];
404 std::array< double, 7 > q_array;
405 for (
size_t i = 0; i < 7; i++)
410 std::array<double, 16> pose_array = m_model->pose(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K);
412 for (
unsigned int i=0; i< 4; i++) {
413 for (
unsigned int j=0; j< 4; j++) {
414 fMe[i][j] = pose_array[j*4 + i];
438 return (fMe * m_eMc);
459 std::array<double, 16> pose_array = robot_state.O_T_EE;
461 for (
unsigned int i=0; i< 4; i++) {
462 for (
unsigned int j=0; j< 4; j++) {
463 fMe[i][j] = pose_array[j*4 + i];
495 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, robot_state);
497 for (
size_t i = 0; i < 6; i ++) {
498 for (
size_t j = 0; j < 7; j ++) {
499 eJe_[i][j] = jacobian[j*6 + i];
519 std::array< double, 7 > q_array;
520 for (
size_t i = 0; i < 7; i++)
523 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K);
525 for (
size_t i = 0; i < 6; i ++) {
526 for (
size_t j = 0; j < 7; j ++) {
527 eJe_[i][j] = jacobian[j*6 + i];
547 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, robot_state);
549 for (
size_t i = 0; i < 6; i ++) {
550 for (
size_t j = 0; j < 7; j ++) {
551 fJe_[i][j] = jacobian[j*6 + i];
574 std::array< double, 7 > q_array;
575 for (
size_t i = 0; i < 7; i++)
578 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K);
580 for (
size_t i = 0; i < 6; i ++) {
581 for (
size_t j = 0; j < 7; j ++) {
582 fJe_[i][j] = jacobian[j*6 + i];
599 if (!folder.empty()) {
603 m_log_folder = folder;
607 error =
"Unable to create Franka log folder: " + folder;
612 m_log_folder = folder;
628 std::cout <<
"Robot was not in position-based control. " 629 "Modification of the robot state" << std::endl;
634 double speed_factor = m_positionningVelocity / 100.;
636 std::array<double, 7> q_goal;
637 for (
size_t i = 0; i < 7; i++) {
638 q_goal[i] = position[i];
641 vpJointPosTrajGenerator joint_pos_traj_generator(speed_factor, q_goal);
644 for (
int attempt = 1; attempt <= nbAttempts; attempt++) {
646 m_handler->control(joint_pos_traj_generator);
648 }
catch (
const franka::ControlException &e) {
649 std::cerr <<
"Warning: communication error: " << e.what() <<
"\nRetry attempt: " << attempt << std::endl;
650 m_handler->automaticErrorRecovery();
651 if (attempt == nbAttempts)
658 "Cannot move the robot to a cartesian position. Only joint positionning is implemented"));
672 m_positionningVelocity = velocity;
688 m_velControlThreadStopAsked =
true;
689 if(m_velControlThread.joinable()) {
690 m_velControlThread.join();
691 m_velControlThreadStopAsked =
false;
692 m_velControlThreadIsRunning =
false;
697 m_ftControlThreadStopAsked =
true;
698 if(m_ftControlThread.joinable()) {
699 m_ftControlThread.join();
700 m_ftControlThreadStopAsked =
false;
701 m_ftControlThreadIsRunning =
false;
708 std::cout <<
"Change the control mode from velocity to position control.\n";
710 m_velControlThreadStopAsked =
true;
711 if(m_velControlThread.joinable()) {
712 m_velControlThread.join();
713 m_velControlThreadStopAsked =
false;
714 m_velControlThreadIsRunning =
false;
718 std::cout <<
"Change the control mode from force/torque to position control.\n";
720 m_ftControlThreadStopAsked =
true;
721 if(m_ftControlThread.joinable()) {
722 m_ftControlThread.join();
723 m_ftControlThreadStopAsked =
false;
724 m_ftControlThreadIsRunning =
false;
731 std::cout <<
"Change the control mode from stop to velocity control.\n";
734 std::cout <<
"Change the control mode from position to velocity control.\n";
737 std::cout <<
"Change the control mode from force/torque to velocity control.\n";
739 m_ftControlThreadStopAsked =
true;
740 if(m_ftControlThread.joinable()) {
741 m_ftControlThread.join();
742 m_ftControlThreadStopAsked =
false;
743 m_ftControlThreadIsRunning =
false;
750 std::cout <<
"Change the control mode from stop to force/torque control.\n";
753 std::cout <<
"Change the control mode from position to force/torque control.\n";
756 std::cout <<
"Change the control mode from velocity to force/torque control.\n";
758 m_velControlThreadStopAsked =
true;
759 if(m_velControlThread.joinable()) {
760 m_velControlThread.join();
761 m_velControlThreadStopAsked =
false;
762 m_velControlThreadIsRunning =
false;
832 "Cannot send a velocity to the robot. " 833 "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first.");
839 if (vel.
size() != 7) {
841 "Joint velocity vector (%d) is not of size 7", vel.
size());
848 for (
size_t i = 0; i < m_dq_des.size(); i++) {
849 m_dq_des[i] = vel_sat[i];
859 if (vel.
size() != 6) {
861 "Cartesian velocity vector (%d) is not of size 6", vel.
size());
865 for (
unsigned int i = 0; i < 3; i++)
867 for (
unsigned int i = 3; i < 6; i++)
877 "Velocity controller not supported");
881 if(! m_velControlThreadIsRunning) {
882 m_velControlThreadIsRunning =
true;
883 m_velControlThread = std::thread(&vpJointVelTrajGenerator::control_thread, vpJointVelTrajGenerator(),
884 std::ref(m_handler), std::ref(m_velControlThreadStopAsked), m_log_folder,
885 frame, m_eMc, std::ref(m_v_cart_des), std::ref(m_dq_des),
886 std::cref(m_q_min), std::cref(m_q_max), std::cref(m_dq_max), std::cref(m_ddq_max),
887 std::ref(m_robot_state), std::ref(m_mutex));
904 const double &filter_gain,
const bool &activate_pi_controller)
909 if (ft.
size() != 7) {
911 "Joint torques vector (%d) is not of size 7", ft.
size());
914 for (
size_t i = 0; i < m_tau_J_des.size(); i++) {
915 m_tau_J_des[i] = ft[i];
926 if (ft.
size() != 6) {
928 "Cartesian force/torque vector (%d) is not of size 6", ft.
size());
939 "Velocity controller not supported");
943 if(! m_ftControlThreadIsRunning) {
945 m_ftControlThreadIsRunning =
true;
946 m_ftControlThread = std::thread(&vpForceTorqueGenerator::control_thread, vpForceTorqueGenerator(),
947 std::ref(m_handler), std::ref(m_ftControlThreadStopAsked), m_log_folder,
948 frame, std::ref(m_tau_J_des), std::ref(m_ft_cart_des), std::ref(m_robot_state),
949 std::ref(m_mutex), filter_gain, activate_pi_controller);
958 franka::RobotState robot_state;
960 if (! m_velControlThreadIsRunning && ! m_ftControlThreadIsRunning) {
961 robot_state = m_handler->readOnce();
963 std::lock_guard<std::mutex> lock(m_mutex);
964 m_robot_state = robot_state;
967 std::lock_guard<std::mutex> lock(m_mutex);
968 robot_state = m_robot_state;
982 for (
size_t i = 0; i < m_q_min.size(); i ++)
983 q_min[i] = m_q_min[i];
995 for (
size_t i = 0; i < m_q_max.size(); i ++)
996 q_max[i] = m_q_max[i];
1098 std::ifstream fd(filename.c_str(), std::ios::in);
1100 if (!fd.is_open()) {
1105 std::string key(
"R:");
1106 std::string id(
"#PANDA - Joint position file");
1107 bool pos_found =
false;
1113 while (std::getline(fd, line)) {
1116 if (!(line.compare(0,
id.size(), id) == 0)) {
1117 std::cout <<
"Error: this position file " << filename <<
" is not for Afma6 robot" << std::endl;
1121 if ((line.compare(0, 1,
"#") == 0)) {
1124 if ((line.compare(0, key.size(), key) == 0)) {
1127 if (chain.size() < njoints + 1)
1129 if (chain.size() < njoints + 1)
1132 std::istringstream ss(line);
1135 for (
unsigned int i = 0; i < njoints; i++)
1143 for (
unsigned int i = 0; i < njoints; i++) {
1150 std::cout <<
"Error: unable to find a position for Panda robot in " << filename << std::endl;
1183 fd = fopen(filename.c_str(),
"w");
1188 "#PANDA - Joint position file\n" 1190 "# R: q1 q2 q3 q4 q5 q6 q7\n" 1191 "# with joint positions q1 to q7 expressed in degrees\n" 1226 if (m_franka_address.empty()) {
1229 if (m_gripper == NULL)
1230 m_gripper =
new franka::Gripper(m_franka_address);
1232 m_gripper->homing();
1246 if (m_franka_address.empty()) {
1249 if (m_gripper == NULL)
1250 m_gripper =
new franka::Gripper(m_franka_address);
1253 franka::GripperState gripper_state = m_gripper->readOnce();
1255 if (gripper_state.max_width < width) {
1256 std::cout <<
"Finger width request is too large for the current fingers on the gripper." 1257 <<
"Maximum possible width is " << gripper_state.max_width << std::endl;
1258 return EXIT_FAILURE;
1261 m_gripper->move(width, 0.1);
1262 return EXIT_SUCCESS;
1288 if (m_franka_address.empty()) {
1291 if (m_gripper == NULL)
1292 m_gripper =
new franka::Gripper(m_franka_address);
1295 franka::GripperState gripper_state = m_gripper->readOnce();
1297 m_gripper->move(gripper_state.max_width, 0.1);
1298 return EXIT_SUCCESS;
1309 if (m_franka_address.empty()) {
1312 if (m_gripper == NULL)
1313 m_gripper =
new franka::Gripper(m_franka_address);
1334 if (m_gripper == NULL)
1335 m_gripper =
new franka::Gripper(m_franka_address);
1338 franka::GripperState gripper_state = m_gripper->readOnce();
1339 std::cout <<
"Gripper max witdh: " << gripper_state.max_width << std::endl;
1340 if (gripper_state.max_width < grasping_width) {
1341 std::cout <<
"Object is too large for the current fingers on the gripper." 1342 <<
"Maximum possible width is " << gripper_state.max_width << std::endl;
1343 return EXIT_FAILURE;
1347 if (!m_gripper->grasp(grasping_width, 0.1, force)) {
1348 std::cout <<
"Failed to grasp object." << std::endl;
1349 return EXIT_FAILURE;
1352 return EXIT_SUCCESS;
1355 #elif !defined(VISP_BUILD_SHARED_LIBS) 1358 void dummy_vpRobotFranka(){};
int gripperMove(double width)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Implementation of a matrix and operations on matrices.
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Error that can be emited by the vpRobot class and its derivates.
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void getCoriolis(vpColVector &coriolis)
Implementation of an homogeneous matrix and operations on such kind of matrices.
bool savePosFile(const std::string &filename, const vpColVector &q)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position)
double getMaxTranslationVelocity(void) const
vpHomogeneousMatrix get_fMe(const vpColVector &q)
void getGravity(vpColVector &gravity)
Initialize the position controller.
error that can be emited by ViSP classes.
void setPositioningVelocity(double velocity)
vpHomogeneousMatrix inverse() const
franka::RobotState getRobotInternalState()
Class that defines a generic virtual robot.
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
vpHomogeneousMatrix get_eMc() const
unsigned int size() const
Return the number of elements of the 2D array.
void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
double getMaxRotationVelocity(void) const
void setLogFolder(const std::string &folder)
int gripperGrasp(double grasping_width, double force=60.)
void getMass(vpMatrix &mass)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
void set_eMc(const vpHomogeneousMatrix &eMc)
Initialize the velocity controller.
virtual vpRobotStateType getRobotState(void) const
bool readPosFile(const std::string &filename, vpColVector &q)
vpPoseVector buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz)
void get_eJe(vpMatrix &eJe)
static double rad(double deg)
Stops robot motion especially in velocity and acceleration control.
void get_fJe(vpMatrix &fJe)
int nDof
number of degrees of freedom
void resize(unsigned int i, bool flagNullify=true)
static double deg(double rad)
Implementation of column vector and the associated operations.
Implementation of a pose vector and operations on poses.
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
vpHomogeneousMatrix get_fMc(const vpColVector &q)
void move(const std::string &filename, double velocity_percentage=10.)
Initialize the force/torque controller.
void connect(const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &ft, const double &filter_gain=0.1, const bool &activate_pi_controller=false)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Function not implemented.
vpColVector getJointMax() const
vpColVector getJointMin() const