34#include <visp3/core/vpConfig.h>
36#if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS)
38#include <visp3/core/vpIoTools.h>
39#include <visp3/robot/vpRobotException.h>
40#include <visp3/robot/vpRobotFranka.h>
42#include "vpForceTorqueGenerator_impl.h"
43#include "vpJointPosTrajGenerator_impl.h"
44#include "vpJointVelTrajGenerator_impl.h"
53 :
vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
54 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
55 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
56 m_ft_cart_des(), m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(), m_mutex(), m_eMc(), m_log_folder(),
69 :
vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
70 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
71 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
72 m_ft_cart_des(), m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(), m_mutex(), m_eMc(), m_log_folder(),
76 connect(franka_address, realtime_config);
86 :
vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
87 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
88 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
89 m_ft_cart_des(), m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(), m_mutex(), m_eMc(), m_log_folder(),
93 connect(franka_address, realtime_config);
103 m_q_min = std::array<double, 7>{-2.8973, -1.7628, -2.8973, -3.0718, -2.8973, -0.0175, -2.8973};
104 m_q_max = std::array<double, 7>{2.8973, 1.7628, 2.8973, -0.0698, 2.8973, 3.7525, 2.8973};
105 m_dq_max = std::array<double, 7>{2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100};
106 m_ddq_max = std::array<double, 7>{15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0};
139 if (franka_address.empty()) {
145 m_franka_address = franka_address;
146 m_handler =
new franka::Robot(franka_address, realtime_config);
148 std::array<double, 7> lower_torque_thresholds_nominal { {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.} };
149 std::array<double, 7> upper_torque_thresholds_nominal { {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0} };
150 std::array<double, 7> lower_torque_thresholds_acceleration { {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.0} };
151 std::array<double, 7> upper_torque_thresholds_acceleration { {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0} };
152 std::array<double, 6> lower_force_thresholds_nominal { {30.0, 30.0, 30.0, 25.0, 25.0, 25.0} };
153 std::array<double, 6> upper_force_thresholds_nominal { {40.0, 40.0, 40.0, 35.0, 35.0, 35.0} };
154 std::array<double, 6> lower_force_thresholds_acceleration { {30.0, 30.0, 30.0, 25.0, 25.0, 25.0} };
155 std::array<double, 6> upper_force_thresholds_acceleration { {40.0, 40.0, 40.0, 35.0, 35.0, 35.0} };
156 m_handler->setCollisionBehavior(lower_torque_thresholds_acceleration, upper_torque_thresholds_acceleration,
157 lower_torque_thresholds_nominal, upper_torque_thresholds_nominal,
158 lower_force_thresholds_acceleration, upper_force_thresholds_acceleration,
159 lower_force_thresholds_nominal, upper_force_thresholds_nominal);
161 m_handler->setJointImpedance({ {3000, 3000, 3000, 2500, 2500, 2000, 2000} });
162 m_handler->setCartesianImpedance({ {3000, 3000, 3000, 300, 300, 300} });
163#if (VISP_HAVE_FRANKA_VERSION < 0x000500)
165 m_handler->setFilters(10, 10, 10, 10, 10);
172 m_model =
new franka::Model(m_handler->loadModel());
183 switch (realtime_config) {
185 connect(franka_address, franka::RealtimeConfig::kEnforce);
188 connect(franka_address, franka::RealtimeConfig::kIgnore);
215 for (
int i = 0; i < 7; i++) {
216 q[i] = robot_state.q[i];
228 for (
size_t i = 0; i < 6; i++) {
229 position[i] = fPe[i];
237 for (
size_t i = 0; i < 6; i++) {
238 position[i] = fPc[i];
269 for (
int i = 0; i < 7; i++)
270 force[i] = robot_state.tau_J[i];
276 for (
int i = 0; i < 6; i++)
277 force[i] = robot_state.K_F_ext_hat_K[i];
283 for (
int i = 0; i < 6; i++)
284 eFe[i] = robot_state.K_F_ext_hat_K[i];
324 for (
int i = 0; i < 7; i++) {
325 d_position[i] = robot_state.dq[i];
347 std::array<double, 7> coriolis_;
351 coriolis_ = m_model->coriolis(robot_state);
354 for (
int i = 0; i < 7; i++) {
355 coriolis[i] = coriolis_[i];
369 std::array<double, 7> gravity_;
373 gravity_ = m_model->gravity(robot_state);
376 for (
int i = 0; i < 7; i++) {
377 gravity[i] = gravity_[i];
391 std::array<double, 49> mass_;
395 mass_ = m_model->mass(robot_state);
398 for (
size_t i = 0; i < 7; i++) {
399 for (
size_t j = 0; j < 7; j++) {
400 mass[i][j] = mass_[j * 7 + i];
421 std::array<double, 7> q_array;
422 for (
size_t i = 0; i < 7; i++)
427 std::array<double, 16> pose_array =
428 m_model->pose(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K);
430 for (
unsigned int i = 0; i < 4; i++) {
431 for (
unsigned int j = 0; j < 4; j++) {
432 fMe[i][j] = pose_array[j * 4 + i];
456 return (fMe * m_eMc);
479 std::array<double, 16> pose_array = robot_state.O_T_EE;
481 for (
unsigned int i = 0; i < 4; i++) {
482 for (
unsigned int j = 0; j < 4; j++) {
483 fMe[i][j] = pose_array[j * 4 + i];
515 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, robot_state);
517 for (
size_t i = 0; i < 6; i++) {
518 for (
size_t j = 0; j < 7; j++) {
519 eJe_[i][j] = jacobian[j * 6 + i];
538 std::array<double, 7> q_array;
539 for (
size_t i = 0; i < 7; i++)
542 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
545 for (
size_t i = 0; i < 6; i++) {
546 for (
size_t j = 0; j < 7; j++) {
547 eJe_[i][j] = jacobian[j * 6 + i];
566 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, robot_state);
568 for (
size_t i = 0; i < 6; i++) {
569 for (
size_t j = 0; j < 7; j++) {
570 fJe_[i][j] = jacobian[j * 6 + i];
589 "Cannot get Franka robot fJe jacobian with an input joint position vector [%u] that is not a 7-dim vector",
595 std::array<double, 7> q_array;
596 for (
size_t i = 0; i < 7; i++)
599 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
602 for (
size_t i = 0; i < 6; i++) {
603 for (
size_t j = 0; j < 7; j++) {
604 fJe_[i][j] = jacobian[j * 6 + i];
621 if (!folder.empty()) {
625 m_log_folder = folder;
629 error =
"Unable to create Franka log folder: " + folder;
634 m_log_folder = folder;
650 std::cout <<
"Robot was not in position-based control. "
651 "Modification of the robot state"
657 double speed_factor = m_positioningVelocity / 100.;
659 std::array<double, 7> q_goal;
660 for (
size_t i = 0; i < 7; i++) {
661 q_goal[i] = position[i];
664 vpJointPosTrajGenerator joint_pos_traj_generator(speed_factor, q_goal);
667 for (
int attempt = 1; attempt <= nbAttempts; attempt++) {
669 m_handler->control(joint_pos_traj_generator);
672 catch (
const franka::ControlException &e) {
673 std::cerr <<
"Warning: communication error: " << e.what() <<
"\nRetry attempt: " << attempt << std::endl;
674 m_handler->automaticErrorRecovery();
675 if (attempt == nbAttempts)
682 "Cannot move the robot to a cartesian position. Only joint positioning is implemented"));
709 m_velControlThreadStopAsked =
true;
710 if (m_velControlThread.joinable()) {
711 m_velControlThread.join();
712 m_velControlThreadStopAsked =
false;
713 m_velControlThreadIsRunning =
false;
718 m_ftControlThreadStopAsked =
true;
719 if (m_ftControlThread.joinable()) {
720 m_ftControlThread.join();
721 m_ftControlThreadStopAsked =
false;
722 m_ftControlThreadIsRunning =
false;
729 std::cout <<
"Change the control mode from velocity to position control.\n";
731 m_velControlThreadStopAsked =
true;
732 if (m_velControlThread.joinable()) {
733 m_velControlThread.join();
734 m_velControlThreadStopAsked =
false;
735 m_velControlThreadIsRunning =
false;
739 std::cout <<
"Change the control mode from force/torque to position control.\n";
741 m_ftControlThreadStopAsked =
true;
742 if (m_ftControlThread.joinable()) {
743 m_ftControlThread.join();
744 m_ftControlThreadStopAsked =
false;
745 m_ftControlThreadIsRunning =
false;
752 std::cout <<
"Change the control mode from stop to velocity control.\n";
755 std::cout <<
"Change the control mode from position to velocity control.\n";
758 std::cout <<
"Change the control mode from force/torque to velocity control.\n";
760 m_ftControlThreadStopAsked =
true;
761 if (m_ftControlThread.joinable()) {
762 m_ftControlThread.join();
763 m_ftControlThreadStopAsked =
false;
764 m_ftControlThreadIsRunning =
false;
771 std::cout <<
"Change the control mode from stop to force/torque control.\n";
774 std::cout <<
"Change the control mode from position to force/torque control.\n";
777 std::cout <<
"Change the control mode from velocity to force/torque control.\n";
779 m_velControlThreadStopAsked =
true;
780 if (m_velControlThread.joinable()) {
781 m_velControlThread.join();
782 m_velControlThreadStopAsked =
false;
783 m_velControlThreadIsRunning =
false;
853 "Cannot send a velocity to the robot. "
854 "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first.");
860 if (vel.
size() != 7) {
869 for (
size_t i = 0; i < m_dq_des.size(); i++) {
870 m_dq_des[i] = vel_sat[i];
880 if (vel.
size() != 6) {
886 for (
unsigned int i = 0; i < 3; i++)
888 for (
unsigned int i = 3; i < 6; i++)
901 if (!m_velControlThreadIsRunning) {
902 m_velControlThreadIsRunning =
true;
904 std::thread(&vpJointVelTrajGenerator::control_thread, vpJointVelTrajGenerator(), std::ref(m_handler),
905 std::ref(m_velControlThreadStopAsked), m_log_folder, frame, m_eMc, std::ref(m_v_cart_des),
906 std::ref(m_dq_des), std::cref(m_q_min), std::cref(m_q_max), std::cref(m_dq_max),
907 std::cref(m_ddq_max), std::ref(m_robot_state), std::ref(m_mutex));
924 const double &filter_gain,
const bool &activate_pi_controller)
929 if (ft.
size() != 7) {
934 for (
size_t i = 0; i < m_tau_J_des.size(); i++) {
935 m_tau_J_des[i] = ft[i];
946 if (ft.
size() != 6) {
962 if (!m_ftControlThreadIsRunning) {
964 m_ftControlThreadIsRunning =
true;
965 m_ftControlThread = std::thread(&vpForceTorqueGenerator::control_thread, vpForceTorqueGenerator(),
966 std::ref(m_handler), std::ref(m_ftControlThreadStopAsked), m_log_folder, frame,
967 std::ref(m_tau_J_des), std::ref(m_ft_cart_des), std::ref(m_robot_state),
968 std::ref(m_mutex), filter_gain, activate_pi_controller);
977 franka::RobotState robot_state;
979 if (!m_velControlThreadIsRunning && !m_ftControlThreadIsRunning) {
980 robot_state = m_handler->readOnce();
982 std::lock_guard<std::mutex> lock(m_mutex);
983 m_robot_state = robot_state;
986 std::lock_guard<std::mutex> lock(m_mutex);
987 robot_state = m_robot_state;
1001 for (
size_t i = 0; i < m_q_min.size(); i++)
1002 q_min[i] = m_q_min[i];
1014 for (
size_t i = 0; i < m_q_max.size(); i++)
1015 q_max[i] = m_q_max[i];
1111 std::ifstream fd(filename.c_str(), std::ios::in);
1113 if (!fd.is_open()) {
1118 std::string key(
"R:");
1119 std::string id(
"#PANDA - Joint position file");
1120 bool pos_found =
false;
1126 while (std::getline(fd, line)) {
1129 if (!(line.compare(0,
id.size(),
id) == 0)) {
1130 std::cout <<
"Error: this position file " << filename <<
" is not for Afma6 robot" << std::endl;
1134 if ((line.compare(0, 1,
"#") == 0)) {
1137 if ((line.compare(0, key.size(), key) == 0)) {
1140 if (chain.size() < njoints + 1)
1142 if (chain.size() < njoints + 1)
1145 std::istringstream ss(line);
1148 for (
unsigned int i = 0; i < njoints; i++)
1156 for (
unsigned int i = 0; i < njoints; i++) {
1163 std::cout <<
"Error: unable to find a position for Panda robot in " << filename << std::endl;
1196 fd = fopen(filename.c_str(),
"w");
1200 fprintf(fd,
"#PANDA - Joint position file\n"
1202 "# R: q1 q2 q3 q4 q5 q6 q7\n"
1203 "# with joint positions q1 to q7 expressed in degrees\n"
1238 if (m_franka_address.empty()) {
1241 if (m_gripper ==
nullptr)
1242 m_gripper =
new franka::Gripper(m_franka_address);
1244 m_gripper->homing();
1258 if (m_franka_address.empty()) {
1261 if (m_gripper ==
nullptr)
1262 m_gripper =
new franka::Gripper(m_franka_address);
1265 franka::GripperState gripper_state = m_gripper->readOnce();
1267 if (gripper_state.max_width < width) {
1268 std::cout <<
"Finger width request is too large for the current fingers on the gripper."
1269 <<
"Maximum possible width is " << gripper_state.max_width << std::endl;
1270 return EXIT_FAILURE;
1273 m_gripper->move(width, 0.1);
1274 return EXIT_SUCCESS;
1297 if (m_franka_address.empty()) {
1300 if (m_gripper ==
nullptr)
1301 m_gripper =
new franka::Gripper(m_franka_address);
1304 franka::GripperState gripper_state = m_gripper->readOnce();
1306 m_gripper->move(gripper_state.max_width, 0.1);
1307 return EXIT_SUCCESS;
1318 if (m_franka_address.empty()) {
1321 if (m_gripper ==
nullptr)
1322 m_gripper =
new franka::Gripper(m_franka_address);
1363 if (m_gripper ==
nullptr)
1364 m_gripper =
new franka::Gripper(m_franka_address);
1367 franka::GripperState gripper_state = m_gripper->readOnce();
1368 std::cout <<
"Gripper max witdh: " << gripper_state.max_width << std::endl;
1369 if (gripper_state.max_width < grasping_width) {
1370 std::cout <<
"Object is too large for the current fingers on the gripper."
1371 <<
"Maximum possible width is " << gripper_state.max_width << std::endl;
1372 return EXIT_FAILURE;
1376 if (!m_gripper->grasp(grasping_width, speed, force)) {
1377 std::cout <<
"Failed to grasp object." << std::endl;
1378 return EXIT_FAILURE;
1381 return EXIT_SUCCESS;
1384#elif !defined(VISP_BUILD_SHARED_LIBS)
1387void dummy_vpRobotFranka() { }
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
unsigned int size() const
Return the number of elements of the 2D array.
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.
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() 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.
vpPoseVector & buildFrom(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz)
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
franka::RobotState getRobotInternalState()
void move(const std::string &filename, double velocity_percentage=10.)
bool savePosFile(const std::string &filename, const vpColVector &q)
void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
vpHomogeneousMatrix get_eMc() const
int gripperGrasp(double grasping_width, double force=60.)
vpColVector getJointMin() const
void setLogFolder(const std::string &folder)
void getGravity(vpColVector &gravity)
int gripperMove(double width)
void getMass(vpMatrix &mass)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &ft, const double &filter_gain=0.1, const bool &activate_pi_controller=false)
vpColVector getJointMax() const
void getCoriolis(vpColVector &coriolis)
void setPositioningVelocity(double velocity)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
void set_eMc(const vpHomogeneousMatrix &eMc)
bool readPosFile(const std::string &filename, vpColVector &q)
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position)
void connect(const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
vpHomogeneousMatrix get_fMe(const vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
vpHomogeneousMatrix get_fMc(const vpColVector &q)
int nDof
number of degrees of freedom
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.
@ STATE_FORCE_TORQUE_CONTROL
Initialize the force/torque controller.
double getMaxRotationVelocity(void) const
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
double getMaxTranslationVelocity(void) const