Visual Servoing Platform  version 3.6.1 under development (2024-12-06)
vpRobotFranka.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for the Franka robot.
33  *
34 *****************************************************************************/
35 
36 #include <visp3/core/vpConfig.h>
37 
38 #if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS)
39 
40 #include <visp3/core/vpIoTools.h>
41 #include <visp3/robot/vpRobotException.h>
42 #include <visp3/robot/vpRobotFranka.h>
43 
44 #include "vpForceTorqueGenerator_impl.h"
45 #include "vpJointPosTrajGenerator_impl.h"
46 #include "vpJointVelTrajGenerator_impl.h"
47 
48 BEGIN_VISP_NAMESPACE
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(),
59  m_franka_address()
60 {
61  init();
62 }
63 
70 vpRobotFranka::vpRobotFranka(const std::string &franka_address, franka::RealtimeConfig realtime_config)
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(),
75  m_franka_address()
76 {
77  init();
78  connect(franka_address, realtime_config);
79 }
80 
84 void vpRobotFranka::init()
85 {
86  nDof = 7;
87 
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};
92 }
93 
100 {
102 
103  if (m_handler)
104  delete m_handler;
105 
106  if (m_gripper) {
107  delete m_gripper;
108  }
109 
110  if (m_model) {
111  delete m_model;
112  }
113 }
114 
121 void vpRobotFranka::connect(const std::string &franka_address, franka::RealtimeConfig realtime_config)
122 {
123  init();
124  if (franka_address.empty()) {
125  throw(vpException(vpException::fatalError, "Cannot connect Franka robot: IP/hostname is not set"));
126  }
127  if (m_handler)
128  delete m_handler;
129 
130  m_franka_address = franka_address;
131  m_handler = new franka::Robot(franka_address, realtime_config);
132 
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);
145 
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)
149  // m_handler->setFilters(100, 100, 100, 100, 100);
150  m_handler->setFilters(10, 10, 10, 10, 10);
151 #else
152  // use franka::lowpassFilter() instead throw Franka::robot::control() with cutoff_frequency parameter
153 #endif
154  if (m_model) {
155  delete m_model;
156  }
157  m_model = new franka::Model(m_handler->loadModel());
158 }
159 
175 {
176  if (!m_handler) {
177  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
178  }
179 
180  franka::RobotState robot_state = getRobotInternalState();
181  vpColVector q(7);
182  for (int i = 0; i < 7; i++) {
183  q[i] = robot_state.q[i];
184  }
185 
186  switch (frame) {
187  case JOINT_STATE: {
188  position = q;
189  break;
190  }
191  case END_EFFECTOR_FRAME: {
192  position.resize(6);
193  vpHomogeneousMatrix fMe = get_fMe(q);
194  vpPoseVector fPe(fMe);
195  for (size_t i = 0; i < 6; i++) {
196  position[i] = fPe[i];
197  }
198  break;
199  }
200  case TOOL_FRAME: { // same a CAMERA_FRAME
201  position.resize(6);
202  vpHomogeneousMatrix fMc = get_fMc(q);
203  vpPoseVector fPc(fMc);
204  for (size_t i = 0; i < 6; i++) {
205  position[i] = fPc[i];
206  }
207  break;
208  }
209  default: {
210  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: wrong method"));
211  }
212  }
213 }
214 
226 {
227  if (!m_handler) {
228  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
229  }
230 
231  franka::RobotState robot_state = getRobotInternalState();
232 
233  switch (frame) {
234  case JOINT_STATE: {
235  force.resize(7);
236  for (int i = 0; i < 7; i++)
237  force[i] = robot_state.tau_J[i];
238 
239  break;
240  }
241  case END_EFFECTOR_FRAME: {
242  force.resize(6);
243  for (int i = 0; i < 6; i++)
244  force[i] = robot_state.K_F_ext_hat_K[i];
245  break;
246  }
247  case TOOL_FRAME: {
248  // end-effector frame
249  vpColVector eFe(6);
250  for (int i = 0; i < 6; i++)
251  eFe[i] = robot_state.K_F_ext_hat_K[i];
252 
253  // Transform in tool frame
255  vpForceTwistMatrix cWe(cMe);
256  force = cWe * eFe;
257  break;
258  }
259  default: {
260  throw(vpException(vpException::fatalError, "Cannot get Franka force/torque: frame not supported"));
261  }
262  }
263 }
264 
280 {
281  if (!m_handler) {
282  throw(vpException(vpException::fatalError, "Cannot get Franka robot velocity: robot is not connected"));
283  }
284 
285  franka::RobotState robot_state = getRobotInternalState();
286 
287  switch (frame) {
288 
289  case JOINT_STATE: {
290  d_position.resize(7);
291  for (int i = 0; i < 7; i++) {
292  d_position[i] = robot_state.dq[i];
293  }
294  break;
295  }
296 
297  default: {
298  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian velocity: not implemented"));
299  }
300  }
301 }
302 
309 {
310  if (!m_handler) {
311  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
312  }
313 
314  std::array<double, 7> coriolis_;
315 
316  franka::RobotState robot_state = getRobotInternalState();
317 
318  coriolis_ = m_model->coriolis(robot_state);
319 
320  coriolis.resize(7);
321  for (int i = 0; i < 7; i++) {
322  coriolis[i] = coriolis_[i];
323  }
324 }
325 
331 {
332  if (!m_handler) {
333  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
334  }
335 
336  std::array<double, 7> gravity_;
337 
338  franka::RobotState robot_state = getRobotInternalState();
339 
340  gravity_ = m_model->gravity(robot_state);
341 
342  gravity.resize(7);
343  for (int i = 0; i < 7; i++) {
344  gravity[i] = gravity_[i];
345  }
346 }
347 
353 {
354  if (!m_handler) {
355  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
356  }
357 
358  std::array<double, 49> mass_;
359 
360  franka::RobotState robot_state = getRobotInternalState();
361 
362  mass_ = m_model->mass(robot_state); // column-major
363 
364  mass.resize(7, 7); // row-major
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];
368  }
369  }
370 }
371 
380 {
381  if (!m_handler) {
382  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
383  }
384  if (q.size() != 7) {
385  throw(vpException(vpException::fatalError, "Joint position vector [%u] is not a 7-dim vector", q.size()));
386  }
387 
388  std::array<double, 7> q_array;
389  for (size_t i = 0; i < 7; i++)
390  q_array[i] = q[i];
391 
392  franka::RobotState robot_state = getRobotInternalState();
393 
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];
400  }
401  }
402 
403  return fMe;
404 }
405 
421 {
422  vpHomogeneousMatrix fMe = get_fMe(q);
423  return (fMe * m_eMc);
424 }
425 
436 {
437  if (!m_handler) {
438  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
439  }
440  if (frame == JOINT_STATE) {
441  throw(vpException(vpException::fatalError, "Cannot get Franka joint position as a pose vector"));
442  }
443 
444  franka::RobotState robot_state = getRobotInternalState();
445 
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];
451  }
452  }
453 
454  switch (frame) {
455  case END_EFFECTOR_FRAME: {
456  pose.buildFrom(fMe);
457  break;
458  }
459  case TOOL_FRAME: {
460  pose.buildFrom(fMe * m_eMc);
461  break;
462  }
463  default: {
464  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: not implemented"));
465  }
466  }
467 }
468 
475 {
476  if (!m_handler) {
477  throw(vpException(vpException::fatalError, "Cannot get Franka robot eJe jacobian: robot is not connected"));
478  }
479 
480  franka::RobotState robot_state = getRobotInternalState();
481 
482  std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, robot_state); // column-major
483  eJe_.resize(6, 7); // row-major
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];
487  }
488  }
489  // TODO check from vpRobot fJe and fJeAvailable
490 }
491 
498 {
499  if (!m_handler) {
500  throw(vpException(vpException::fatalError, "Cannot get Franka robot eJe jacobian: robot is not connected"));
501  }
502 
503  franka::RobotState robot_state = getRobotInternalState();
504 
505  std::array<double, 7> q_array;
506  for (size_t i = 0; i < 7; i++)
507  q_array[i] = q[i];
508 
509  std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
510  robot_state.EE_T_K); // column-major
511  eJe_.resize(6, 7); // row-major
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];
515  }
516  }
517  // TODO check from vpRobot fJe and fJeAvailable
518 }
519 
526 {
527  if (!m_handler) {
528  throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian: robot is not connected"));
529  }
530 
531  franka::RobotState robot_state = getRobotInternalState();
532 
533  std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, robot_state); // column-major
534  fJe_.resize(6, 7); // row-major
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];
538  }
539  }
540  // TODO check from vpRobot fJe and fJeAvailable
541 }
542 
549 {
550  if (!m_handler) {
551  throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian: robot is not connected"));
552  }
553  if (q.size() != 7) {
554  throw(vpException(
556  "Cannot get Franka robot fJe jacobian with an input joint position vector [%u] that is not a 7-dim vector",
557  q.size()));
558  }
559 
560  franka::RobotState robot_state = getRobotInternalState();
561 
562  std::array<double, 7> q_array;
563  for (size_t i = 0; i < 7; i++)
564  q_array[i] = q[i];
565 
566  std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
567  robot_state.EE_T_K); // column-major
568  fJe_.resize(6, 7); // row-major
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];
572  }
573  }
574  // TODO check from vpRobot fJe and fJeAvailable
575 }
576 
586 void vpRobotFranka::setLogFolder(const std::string &folder)
587 {
588  if (!folder.empty()) {
589  if (vpIoTools::checkDirectory(folder) == false) {
590  try {
591  vpIoTools::makeDirectory(folder);
592  m_log_folder = folder;
593  }
594  catch (const vpException &e) {
595  std::string error;
596  error = "Unable to create Franka log folder: " + folder;
597  throw(vpException(vpException::fatalError, error));
598  }
599  }
600  else {
601  m_log_folder = folder;
602  }
603  }
604 }
605 
612 {
613  if (!m_handler) {
614  throw(vpException(vpException::fatalError, "Cannot set Franka robot position: robot is not connected"));
615  }
617  std::cout << "Robot was not in position-based control. "
618  "Modification of the robot state"
619  << std::endl;
621  }
622 
623  if (frame == vpRobot::JOINT_STATE) {
624  double speed_factor = m_positioningVelocity / 100.;
625 
626  std::array<double, 7> q_goal;
627  for (size_t i = 0; i < 7; i++) {
628  q_goal[i] = position[i];
629  }
630 
631  vpJointPosTrajGenerator joint_pos_traj_generator(speed_factor, q_goal);
632 
633  int nbAttempts = 10;
634  for (int attempt = 1; attempt <= nbAttempts; attempt++) {
635  try {
636  m_handler->control(joint_pos_traj_generator);
637  break;
638  }
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)
643  throw;
644  }
645  }
646  }
647  else {
649  "Cannot move the robot to a cartesian position. Only joint positioning is implemented"));
650  }
651 }
652 
661 void vpRobotFranka::setPositioningVelocity(double velocity) { m_positioningVelocity = velocity; }
662 
670 {
671  switch (newState) {
672  case vpRobot::STATE_STOP: {
673  // Start primitive STOP only if the current state is velocity or force/torque
675  // Stop the robot
676  m_velControlThreadStopAsked = true;
677  if (m_velControlThread.joinable()) {
678  m_velControlThread.join();
679  m_velControlThreadStopAsked = false;
680  m_velControlThreadIsRunning = false;
681  }
682  }
684  // Stop the robot
685  m_ftControlThreadStopAsked = true;
686  if (m_ftControlThread.joinable()) {
687  m_ftControlThread.join();
688  m_ftControlThreadStopAsked = false;
689  m_ftControlThreadIsRunning = false;
690  }
691  }
692  break;
693  }
696  std::cout << "Change the control mode from velocity to position control.\n";
697  // Stop the robot
698  m_velControlThreadStopAsked = true;
699  if (m_velControlThread.joinable()) {
700  m_velControlThread.join();
701  m_velControlThreadStopAsked = false;
702  m_velControlThreadIsRunning = false;
703  }
704  }
706  std::cout << "Change the control mode from force/torque to position control.\n";
707  // Stop the robot
708  m_ftControlThreadStopAsked = true;
709  if (m_ftControlThread.joinable()) {
710  m_ftControlThread.join();
711  m_ftControlThreadStopAsked = false;
712  m_ftControlThreadIsRunning = false;
713  }
714  }
715  break;
716  }
719  std::cout << "Change the control mode from stop to velocity control.\n";
720  }
722  std::cout << "Change the control mode from position to velocity control.\n";
723  }
725  std::cout << "Change the control mode from force/torque to velocity control.\n";
726  // Stop the robot
727  m_ftControlThreadStopAsked = true;
728  if (m_ftControlThread.joinable()) {
729  m_ftControlThread.join();
730  m_ftControlThreadStopAsked = false;
731  m_ftControlThreadIsRunning = false;
732  }
733  }
734  break;
735  }
738  std::cout << "Change the control mode from stop to force/torque control.\n";
739  }
741  std::cout << "Change the control mode from position to force/torque control.\n";
742  }
744  std::cout << "Change the control mode from velocity to force/torque control.\n";
745  // Stop the robot
746  m_velControlThreadStopAsked = true;
747  if (m_velControlThread.joinable()) {
748  m_velControlThread.join();
749  m_velControlThreadStopAsked = false;
750  m_velControlThreadIsRunning = false;
751  }
752  }
753  break;
754  }
755 
756  default:
757  break;
758  }
759 
760  return vpRobot::setRobotState(newState);
761 }
762 
817 {
820  "Cannot send a velocity to the robot. "
821  "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first.");
822  }
823 
824  switch (frame) {
825  // Saturation in joint space
826  case JOINT_STATE: {
827  if (vel.size() != 7) {
828  throw vpRobotException(vpRobotException::wrongStateError, "Joint velocity vector (%d) is not of size 7",
829  vel.size());
830  }
831 
832  vpColVector vel_max(7, getMaxRotationVelocity());
833 
834  vpColVector vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
835 
836  for (size_t i = 0; i < m_dq_des.size(); i++) { // TODO create a function to convert
837  m_dq_des[i] = vel_sat[i];
838  }
839 
840  break;
841  }
842 
843  // Saturation in cartesian space
844  case vpRobot::TOOL_FRAME:
847  if (vel.size() != 6) {
848  throw vpRobotException(vpRobotException::wrongStateError, "Cartesian velocity vector (%d) is not of size 6",
849  vel.size());
850  }
851  vpColVector vel_max(6);
852 
853  for (unsigned int i = 0; i < 3; i++)
854  vel_max[i] = getMaxTranslationVelocity();
855  for (unsigned int i = 3; i < 6; i++)
856  vel_max[i] = getMaxRotationVelocity();
857 
858  m_v_cart_des = vpRobot::saturateVelocities(vel, vel_max, true);
859 
860  break;
861  }
862 
863  case vpRobot::MIXT_FRAME: {
864  throw vpRobotException(vpRobotException::wrongStateError, "Velocity controller not supported");
865  }
866  }
867 
868  if (!m_velControlThreadIsRunning) {
869  m_velControlThreadIsRunning = true;
870  m_velControlThread =
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));
875  }
876 }
877 
878 /*
879  Apply a force/torque to the robot.
880 
881  \param[in] frame : Control frame in which the force/torque is applied.
882 
883  \param[in] ft : Force/torque vector. The size of this vector
884  is always 6 for a cartesian force/torque skew, and 7 for joint torques.
885 
886  \param[in] filter_gain : Value in range [0:1] to filter the force/torque vector \e ft.
887  To diable the filter set filter_gain to 1.
888  \param[in] activate_pi_controller : Activate proportional and integral low level controller.
889  */
891  const double &filter_gain, const bool &activate_pi_controller)
892 {
893  switch (frame) {
894  // Saturation in joint space
895  case JOINT_STATE: {
896  if (ft.size() != 7) {
897  throw vpRobotException(vpRobotException::wrongStateError, "Joint torques vector (%d) is not of size 7",
898  ft.size());
899  }
900 
901  for (size_t i = 0; i < m_tau_J_des.size(); i++) { // TODO create a function to convert
902  m_tau_J_des[i] = ft[i];
903  }
904  // TODO: Introduce force/torque saturation
905 
906  break;
907  }
908 
909  // Saturation in cartesian space
910  case vpRobot::TOOL_FRAME:
913  if (ft.size() != 6) {
914  throw vpRobotException(vpRobotException::wrongStateError, "Cartesian force/torque vector (%d) is not of size 6",
915  ft.size());
916  }
917 
918  m_ft_cart_des = ft;
919  // TODO: Introduce force/torque saturation
920 
921  break;
922  }
923 
924  case vpRobot::MIXT_FRAME: {
925  throw vpRobotException(vpRobotException::wrongStateError, "Velocity controller not supported");
926  }
927  }
928 
929  if (!m_ftControlThreadIsRunning) {
930  getRobotInternalState(); // Update m_robot_state internally
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);
936  }
937 }
938 
940 {
941  if (!m_handler) {
942  throw(vpException(vpException::fatalError, "Cannot get Franka robot state: robot is not connected"));
943  }
944  franka::RobotState robot_state;
945 
946  if (!m_velControlThreadIsRunning && !m_ftControlThreadIsRunning) {
947  robot_state = m_handler->readOnce();
948 
949  std::lock_guard<std::mutex> lock(m_mutex);
950  m_robot_state = robot_state;
951  }
952  else { // robot_state is updated in the velocity control thread
953  std::lock_guard<std::mutex> lock(m_mutex);
954  robot_state = m_robot_state;
955  }
956 
957  return robot_state;
958 }
959 
966 {
967  vpColVector q_min(m_q_min.size());
968  for (size_t i = 0; i < m_q_min.size(); i++)
969  q_min[i] = m_q_min[i];
970 
971  return q_min;
972 }
979 {
980  vpColVector q_max(m_q_max.size());
981  for (size_t i = 0; i < m_q_max.size(); i++)
982  q_max[i] = m_q_max[i];
983 
984  return q_max;
985 }
986 
998 
1011 void vpRobotFranka::set_eMc(const vpHomogeneousMatrix &eMc) { m_eMc = eMc; }
1012 
1022 void vpRobotFranka::move(const std::string &filename, double velocity_percentage)
1023 {
1024  vpColVector q;
1025 
1026  this->readPosFile(filename, q);
1028  this->setPositioningVelocity(velocity_percentage);
1030 }
1031 
1076 bool vpRobotFranka::readPosFile(const std::string &filename, vpColVector &q)
1077 {
1078  std::ifstream fd(filename.c_str(), std::ios::in);
1079 
1080  if (!fd.is_open()) {
1081  return false;
1082  }
1083 
1084  std::string line;
1085  std::string key("R:");
1086  std::string id("#PANDA - Joint position file");
1087  bool pos_found = false;
1088  int lineNum = 0;
1089  size_t njoints = 7;
1090 
1091  q.resize(njoints);
1092 
1093  while (std::getline(fd, line)) {
1094  lineNum++;
1095  if (lineNum == 1) {
1096  if (!(line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
1097  std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
1098  return false;
1099  }
1100  }
1101  if ((line.compare(0, 1, "#") == 0)) { // skip comment
1102  continue;
1103  }
1104  if ((line.compare(0, key.size(), key) == 0)) { // decode position
1105  // check if there are at least njoint values in the line
1106  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1107  if (chain.size() < njoints + 1) // try to split with tab separator
1108  chain = vpIoTools::splitChain(line, std::string("\t"));
1109  if (chain.size() < njoints + 1)
1110  continue;
1111 
1112  std::istringstream ss(line);
1113  std::string key_;
1114  ss >> key_;
1115  for (unsigned int i = 0; i < njoints; i++)
1116  ss >> q[i];
1117  pos_found = true;
1118  break;
1119  }
1120  }
1121 
1122  // converts rotations from degrees into radians
1123  for (unsigned int i = 0; i < njoints; i++) {
1124  q[i] = vpMath::rad(q[i]);
1125  }
1126 
1127  fd.close();
1128 
1129  if (!pos_found) {
1130  std::cout << "Error: unable to find a position for Panda robot in " << filename << std::endl;
1131  return false;
1132  }
1133 
1134  return true;
1135 }
1136 
1159 bool vpRobotFranka::savePosFile(const std::string &filename, const vpColVector &q)
1160 {
1161 
1162  FILE *fd;
1163  fd = fopen(filename.c_str(), "w");
1164  if (fd == nullptr)
1165  return false;
1166 
1167  fprintf(fd, "#PANDA - Joint position file\n"
1168  "#\n"
1169  "# R: q1 q2 q3 q4 q5 q6 q7\n"
1170  "# with joint positions q1 to q7 expressed in degrees\n"
1171  "#\n");
1172 
1173  // Save positions in mm and deg
1174  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
1175  vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]), vpMath::deg(q[6]));
1176 
1177  fclose(fd);
1178  return (true);
1179 }
1180 
1189 {
1191  vpColVector q(7, 0);
1193  }
1195 }
1196 
1204 {
1205  if (m_franka_address.empty()) {
1206  throw(vpException(vpException::fatalError, "Cannot perform franka gripper homing without ip address"));
1207  }
1208  if (m_gripper == nullptr)
1209  m_gripper = new franka::Gripper(m_franka_address);
1210 
1211  m_gripper->homing();
1212 }
1213 
1224 {
1225  if (m_franka_address.empty()) {
1226  throw(vpException(vpException::fatalError, "Cannot open franka gripper without ip address"));
1227  }
1228  if (m_gripper == nullptr)
1229  m_gripper = new franka::Gripper(m_franka_address);
1230 
1231  // Check for the maximum grasping width.
1232  franka::GripperState gripper_state = m_gripper->readOnce();
1233 
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;
1238  }
1239 
1240  m_gripper->move(width, 0.1);
1241  return EXIT_SUCCESS;
1242 }
1243 
1253 
1263 {
1264  if (m_franka_address.empty()) {
1265  throw(vpException(vpException::fatalError, "Cannot open franka gripper without ip address"));
1266  }
1267  if (m_gripper == nullptr)
1268  m_gripper = new franka::Gripper(m_franka_address);
1269 
1270  // Check for the maximum grasping width.
1271  franka::GripperState gripper_state = m_gripper->readOnce();
1272 
1273  m_gripper->move(gripper_state.max_width, 0.1);
1274  return EXIT_SUCCESS;
1275 }
1276 
1284 {
1285  if (m_franka_address.empty()) {
1286  throw(vpException(vpException::fatalError, "Cannot release franka gripper without ip address"));
1287  }
1288  if (m_gripper == nullptr)
1289  m_gripper = new franka::Gripper(m_franka_address);
1290 
1291  m_gripper->stop();
1292 }
1293 
1308 int vpRobotFranka::gripperGrasp(double grasping_width, double force)
1309 {
1310  return gripperGrasp(grasping_width, 0.1, force);
1311 }
1312 
1328 int vpRobotFranka::gripperGrasp(double grasping_width, double speed, double force)
1329 {
1330  if (m_gripper == nullptr)
1331  m_gripper = new franka::Gripper(m_franka_address);
1332 
1333  // Check for the maximum grasping width.
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;
1340  }
1341 
1342  // Grasp the object.
1343  if (!m_gripper->grasp(grasping_width, speed, force)) {
1344  std::cout << "Failed to grasp object." << std::endl;
1345  return EXIT_FAILURE;
1346  }
1347 
1348  return EXIT_SUCCESS;
1349 }
1350 END_VISP_NAMESPACE
1351 #elif !defined(VISP_BUILD_SHARED_LIBS)
1352 // Work around to avoid warning: libvisp_robot.a(vpRobotFranka.cpp.o) has
1353 // no symbols
1354 void dummy_vpRobotFranka() { };
1355 #endif
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition: vpArray2D.h:362
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:349
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ functionNotImplementedError
Function not implemented.
Definition: vpException.h:66
@ fatalError
Fatal error.
Definition: vpException.h:72
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1661
static bool checkDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:396
static void makeDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:550
static double rad(double deg)
Definition: vpMath.h:129
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
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
virtual ~vpRobotFranka()
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.
Definition: vpRobot.h:59
int nDof
number of degrees of freedom
Definition: vpRobot.h:104
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:155
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164
vpControlFrameType
Definition: vpRobot.h:77
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ JOINT_STATE
Definition: vpRobot.h:82
@ TOOL_FRAME
Definition: vpRobot.h:86
@ MIXT_FRAME
Definition: vpRobot.h:88
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:83
vpRobotStateType
Definition: vpRobot.h:65
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
@ STATE_FORCE_TORQUE_CONTROL
Initialize the force/torque controller.
Definition: vpRobot.h:70
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:274
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:252