36 #include <visp3/core/vpConfig.h>
38 #if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS)
40 #include <visp3/core/vpIoTools.h>
41 #include <visp3/robot/vpRobotException.h>
42 #include <visp3/robot/vpRobotFranka.h>
44 #include "vpForceTorqueGenerator_impl.h"
45 #include "vpJointPosTrajGenerator_impl.h"
46 #include "vpJointVelTrajGenerator_impl.h"
55 :
vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
56 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
57 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
58 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(),
71 :
vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
72 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
73 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
74 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(),
78 connect(franka_address, realtime_config);
84 void vpRobotFranka::init()
88 m_q_min = std::array<double, 7>{-2.8973, -1.7628, -2.8973, -3.0718, -2.8973, -0.0175, -2.8973};
89 m_q_max = std::array<double, 7>{2.8973, 1.7628, 2.8973, -0.0698, 2.8973, 3.7525, 2.8973};
90 m_dq_max = std::array<double, 7>{2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100};
91 m_ddq_max = std::array<double, 7>{15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0};
124 if (franka_address.empty()) {
130 m_franka_address = franka_address;
131 m_handler =
new franka::Robot(franka_address, realtime_config);
133 std::array<double, 7> lower_torque_thresholds_nominal { {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.} };
134 std::array<double, 7> upper_torque_thresholds_nominal { {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0} };
135 std::array<double, 7> lower_torque_thresholds_acceleration { {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.0} };
136 std::array<double, 7> upper_torque_thresholds_acceleration { {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0} };
137 std::array<double, 6> lower_force_thresholds_nominal { {30.0, 30.0, 30.0, 25.0, 25.0, 25.0} };
138 std::array<double, 6> upper_force_thresholds_nominal { {40.0, 40.0, 40.0, 35.0, 35.0, 35.0} };
139 std::array<double, 6> lower_force_thresholds_acceleration { {30.0, 30.0, 30.0, 25.0, 25.0, 25.0} };
140 std::array<double, 6> upper_force_thresholds_acceleration { {40.0, 40.0, 40.0, 35.0, 35.0, 35.0} };
141 m_handler->setCollisionBehavior(lower_torque_thresholds_acceleration, upper_torque_thresholds_acceleration,
142 lower_torque_thresholds_nominal, upper_torque_thresholds_nominal,
143 lower_force_thresholds_acceleration, upper_force_thresholds_acceleration,
144 lower_force_thresholds_nominal, upper_force_thresholds_nominal);
146 m_handler->setJointImpedance({ {3000, 3000, 3000, 2500, 2500, 2000, 2000} });
147 m_handler->setCartesianImpedance({ {3000, 3000, 3000, 300, 300, 300} });
148 #if (VISP_HAVE_FRANKA_VERSION < 0x000500)
150 m_handler->setFilters(10, 10, 10, 10, 10);
157 m_model =
new franka::Model(m_handler->loadModel());
182 for (
int i = 0; i < 7; i++) {
183 q[i] = robot_state.q[i];
195 for (
size_t i = 0; i < 6; i++) {
196 position[i] = fPe[i];
204 for (
size_t i = 0; i < 6; i++) {
205 position[i] = fPc[i];
236 for (
int i = 0; i < 7; i++)
237 force[i] = robot_state.tau_J[i];
243 for (
int i = 0; i < 6; i++)
244 force[i] = robot_state.K_F_ext_hat_K[i];
250 for (
int i = 0; i < 6; i++)
251 eFe[i] = robot_state.K_F_ext_hat_K[i];
291 for (
int i = 0; i < 7; i++) {
292 d_position[i] = robot_state.dq[i];
314 std::array<double, 7> coriolis_;
318 coriolis_ = m_model->coriolis(robot_state);
321 for (
int i = 0; i < 7; i++) {
322 coriolis[i] = coriolis_[i];
336 std::array<double, 7> gravity_;
340 gravity_ = m_model->gravity(robot_state);
343 for (
int i = 0; i < 7; i++) {
344 gravity[i] = gravity_[i];
358 std::array<double, 49> mass_;
362 mass_ = m_model->mass(robot_state);
365 for (
size_t i = 0; i < 7; i++) {
366 for (
size_t j = 0; j < 7; j++) {
367 mass[i][j] = mass_[j * 7 + i];
388 std::array<double, 7> q_array;
389 for (
size_t i = 0; i < 7; i++)
394 std::array<double, 16> pose_array =
395 m_model->pose(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K);
397 for (
unsigned int i = 0; i < 4; i++) {
398 for (
unsigned int j = 0; j < 4; j++) {
399 fMe[i][j] = pose_array[j * 4 + i];
423 return (fMe * m_eMc);
446 std::array<double, 16> pose_array = robot_state.O_T_EE;
448 for (
unsigned int i = 0; i < 4; i++) {
449 for (
unsigned int j = 0; j < 4; j++) {
450 fMe[i][j] = pose_array[j * 4 + i];
482 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, robot_state);
484 for (
size_t i = 0; i < 6; i++) {
485 for (
size_t j = 0; j < 7; j++) {
486 eJe_[i][j] = jacobian[j * 6 + i];
505 std::array<double, 7> q_array;
506 for (
size_t i = 0; i < 7; i++)
509 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
512 for (
size_t i = 0; i < 6; i++) {
513 for (
size_t j = 0; j < 7; j++) {
514 eJe_[i][j] = jacobian[j * 6 + i];
533 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, robot_state);
535 for (
size_t i = 0; i < 6; i++) {
536 for (
size_t j = 0; j < 7; j++) {
537 fJe_[i][j] = jacobian[j * 6 + i];
556 "Cannot get Franka robot fJe jacobian with an input joint position vector [%u] that is not a 7-dim vector",
562 std::array<double, 7> q_array;
563 for (
size_t i = 0; i < 7; i++)
566 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
569 for (
size_t i = 0; i < 6; i++) {
570 for (
size_t j = 0; j < 7; j++) {
571 fJe_[i][j] = jacobian[j * 6 + i];
588 if (!folder.empty()) {
592 m_log_folder = folder;
596 error =
"Unable to create Franka log folder: " + folder;
601 m_log_folder = folder;
617 std::cout <<
"Robot was not in position-based control. "
618 "Modification of the robot state"
624 double speed_factor = m_positioningVelocity / 100.;
626 std::array<double, 7> q_goal;
627 for (
size_t i = 0; i < 7; i++) {
628 q_goal[i] = position[i];
631 vpJointPosTrajGenerator joint_pos_traj_generator(speed_factor, q_goal);
634 for (
int attempt = 1; attempt <= nbAttempts; attempt++) {
636 m_handler->control(joint_pos_traj_generator);
639 catch (
const franka::ControlException &e) {
640 std::cerr <<
"Warning: communication error: " << e.what() <<
"\nRetry attempt: " << attempt << std::endl;
641 m_handler->automaticErrorRecovery();
642 if (attempt == nbAttempts)
649 "Cannot move the robot to a cartesian position. Only joint positioning is implemented"));
676 m_velControlThreadStopAsked =
true;
677 if (m_velControlThread.joinable()) {
678 m_velControlThread.join();
679 m_velControlThreadStopAsked =
false;
680 m_velControlThreadIsRunning =
false;
685 m_ftControlThreadStopAsked =
true;
686 if (m_ftControlThread.joinable()) {
687 m_ftControlThread.join();
688 m_ftControlThreadStopAsked =
false;
689 m_ftControlThreadIsRunning =
false;
696 std::cout <<
"Change the control mode from velocity to position control.\n";
698 m_velControlThreadStopAsked =
true;
699 if (m_velControlThread.joinable()) {
700 m_velControlThread.join();
701 m_velControlThreadStopAsked =
false;
702 m_velControlThreadIsRunning =
false;
706 std::cout <<
"Change the control mode from force/torque to position control.\n";
708 m_ftControlThreadStopAsked =
true;
709 if (m_ftControlThread.joinable()) {
710 m_ftControlThread.join();
711 m_ftControlThreadStopAsked =
false;
712 m_ftControlThreadIsRunning =
false;
719 std::cout <<
"Change the control mode from stop to velocity control.\n";
722 std::cout <<
"Change the control mode from position to velocity control.\n";
725 std::cout <<
"Change the control mode from force/torque to velocity control.\n";
727 m_ftControlThreadStopAsked =
true;
728 if (m_ftControlThread.joinable()) {
729 m_ftControlThread.join();
730 m_ftControlThreadStopAsked =
false;
731 m_ftControlThreadIsRunning =
false;
738 std::cout <<
"Change the control mode from stop to force/torque control.\n";
741 std::cout <<
"Change the control mode from position to force/torque control.\n";
744 std::cout <<
"Change the control mode from velocity to force/torque control.\n";
746 m_velControlThreadStopAsked =
true;
747 if (m_velControlThread.joinable()) {
748 m_velControlThread.join();
749 m_velControlThreadStopAsked =
false;
750 m_velControlThreadIsRunning =
false;
820 "Cannot send a velocity to the robot. "
821 "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first.");
827 if (vel.
size() != 7) {
836 for (
size_t i = 0; i < m_dq_des.size(); i++) {
837 m_dq_des[i] = vel_sat[i];
847 if (vel.
size() != 6) {
853 for (
unsigned int i = 0; i < 3; i++)
855 for (
unsigned int i = 3; i < 6; i++)
868 if (!m_velControlThreadIsRunning) {
869 m_velControlThreadIsRunning =
true;
871 std::thread(&vpJointVelTrajGenerator::control_thread, vpJointVelTrajGenerator(), std::ref(m_handler),
872 std::ref(m_velControlThreadStopAsked), m_log_folder, frame, m_eMc, std::ref(m_v_cart_des),
873 std::ref(m_dq_des), std::cref(m_q_min), std::cref(m_q_max), std::cref(m_dq_max),
874 std::cref(m_ddq_max), std::ref(m_robot_state), std::ref(m_mutex));
891 const double &filter_gain,
const bool &activate_pi_controller)
896 if (ft.
size() != 7) {
901 for (
size_t i = 0; i < m_tau_J_des.size(); i++) {
902 m_tau_J_des[i] = ft[i];
913 if (ft.
size() != 6) {
929 if (!m_ftControlThreadIsRunning) {
931 m_ftControlThreadIsRunning =
true;
932 m_ftControlThread = std::thread(&vpForceTorqueGenerator::control_thread, vpForceTorqueGenerator(),
933 std::ref(m_handler), std::ref(m_ftControlThreadStopAsked), m_log_folder, frame,
934 std::ref(m_tau_J_des), std::ref(m_ft_cart_des), std::ref(m_robot_state),
935 std::ref(m_mutex), filter_gain, activate_pi_controller);
944 franka::RobotState robot_state;
946 if (!m_velControlThreadIsRunning && !m_ftControlThreadIsRunning) {
947 robot_state = m_handler->readOnce();
949 std::lock_guard<std::mutex> lock(m_mutex);
950 m_robot_state = robot_state;
953 std::lock_guard<std::mutex> lock(m_mutex);
954 robot_state = m_robot_state;
968 for (
size_t i = 0; i < m_q_min.size(); i++)
969 q_min[i] = m_q_min[i];
981 for (
size_t i = 0; i < m_q_max.size(); i++)
982 q_max[i] = m_q_max[i];
1078 std::ifstream fd(filename.c_str(), std::ios::in);
1080 if (!fd.is_open()) {
1085 std::string key(
"R:");
1086 std::string id(
"#PANDA - Joint position file");
1087 bool pos_found =
false;
1093 while (std::getline(fd, line)) {
1096 if (!(line.compare(0,
id.size(),
id) == 0)) {
1097 std::cout <<
"Error: this position file " << filename <<
" is not for Afma6 robot" << std::endl;
1101 if ((line.compare(0, 1,
"#") == 0)) {
1104 if ((line.compare(0, key.size(), key) == 0)) {
1107 if (chain.size() < njoints + 1)
1109 if (chain.size() < njoints + 1)
1112 std::istringstream ss(line);
1115 for (
unsigned int i = 0; i < njoints; i++)
1123 for (
unsigned int i = 0; i < njoints; i++) {
1130 std::cout <<
"Error: unable to find a position for Panda robot in " << filename << std::endl;
1163 fd = fopen(filename.c_str(),
"w");
1167 fprintf(fd,
"#PANDA - Joint position file\n"
1169 "# R: q1 q2 q3 q4 q5 q6 q7\n"
1170 "# with joint positions q1 to q7 expressed in degrees\n"
1205 if (m_franka_address.empty()) {
1208 if (m_gripper ==
nullptr)
1209 m_gripper =
new franka::Gripper(m_franka_address);
1211 m_gripper->homing();
1225 if (m_franka_address.empty()) {
1228 if (m_gripper ==
nullptr)
1229 m_gripper =
new franka::Gripper(m_franka_address);
1232 franka::GripperState gripper_state = m_gripper->readOnce();
1234 if (gripper_state.max_width < width) {
1235 std::cout <<
"Finger width request is too large for the current fingers on the gripper."
1236 <<
"Maximum possible width is " << gripper_state.max_width << std::endl;
1237 return EXIT_FAILURE;
1240 m_gripper->move(width, 0.1);
1241 return EXIT_SUCCESS;
1264 if (m_franka_address.empty()) {
1267 if (m_gripper ==
nullptr)
1268 m_gripper =
new franka::Gripper(m_franka_address);
1271 franka::GripperState gripper_state = m_gripper->readOnce();
1273 m_gripper->move(gripper_state.max_width, 0.1);
1274 return EXIT_SUCCESS;
1285 if (m_franka_address.empty()) {
1288 if (m_gripper ==
nullptr)
1289 m_gripper =
new franka::Gripper(m_franka_address);
1330 if (m_gripper ==
nullptr)
1331 m_gripper =
new franka::Gripper(m_franka_address);
1334 franka::GripperState gripper_state = m_gripper->readOnce();
1335 std::cout <<
"Gripper max witdh: " << gripper_state.max_width << std::endl;
1336 if (gripper_state.max_width < grasping_width) {
1337 std::cout <<
"Object is too large for the current fingers on the gripper."
1338 <<
"Maximum possible width is " << gripper_state.max_width << std::endl;
1339 return EXIT_FAILURE;
1343 if (!m_gripper->grasp(grasping_width, speed, force)) {
1344 std::cout <<
"Failed to grasp object." << std::endl;
1345 return EXIT_FAILURE;
1348 return EXIT_SUCCESS;
1351 #elif !defined(VISP_BUILD_SHARED_LIBS)
1354 void 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)
Class that defines a generic virtual robot.
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