Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
vpRobotFranka.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #ifdef VISP_HAVE_FRANKA
42 
43 #include <visp3/robot/vpRobotException.h>
44 #include <visp3/robot/vpRobotFranka.h>
45 #include <visp3/core/vpIoTools.h>
46 
47 #include "vpJointPosTrajGenerator_impl.h"
48 #include "vpJointVelTrajGenerator_impl.h"
49 #include "vpForceTorqueGenerator_impl.h"
50 
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()
64 {
65  init();
66 }
67 
74 vpRobotFranka::vpRobotFranka(const std::string &franka_address, franka::RealtimeConfig realtime_config)
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()
82 {
83  init();
84  connect(franka_address, realtime_config);
85 }
86 
90 void vpRobotFranka::init()
91 {
92  nDof = 7;
93 
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};
98 }
99 
106 {
108 
109  if (m_handler)
110  delete m_handler;
111 
112  if (m_gripper) {
113  std::cout << "Grasped object, will release it now." << std::endl;
114  m_gripper->stop();
115  delete m_gripper;
116  }
117 
118  if (m_model) {
119  delete m_model;
120  }
121 }
122 
129 void vpRobotFranka::connect(const std::string &franka_address, franka::RealtimeConfig realtime_config)
130 {
131  init();
132  if(franka_address.empty()) {
133  throw(vpException(vpException::fatalError, "Cannot connect Franka robot: IP/hostname is not set"));
134  }
135  if (m_handler)
136  delete m_handler;
137 
138  m_franka_address = franka_address;
139  m_handler = new franka::Robot(franka_address, realtime_config);
140 
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);
158 
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)
162  // m_handler->setFilters(100, 100, 100, 100, 100);
163  m_handler->setFilters(10, 10, 10, 10, 10);
164 #else
165  // use franka::lowpassFilter() instead throw Franka::robot::control() with cutoff_frequency parameter
166 #endif
167  if (m_model) {
168  delete m_model;
169  }
170  m_model = new franka::Model(m_handler->loadModel());
171 }
172 
188 {
189  if (!m_handler) {
190  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
191  }
192 
193  franka::RobotState robot_state = getRobotInternalState();
194  vpColVector q(7);
195  for (int i=0; i < 7; i++) {
196  q[i] = robot_state.q[i];
197  }
198 
199  switch(frame) {
200  case JOINT_STATE: {
201  position = q;
202  break;
203  }
204  case END_EFFECTOR_FRAME: {
205  position.resize(6);
206  vpHomogeneousMatrix fMe = get_fMe(q);
207  vpPoseVector fPe(fMe);
208  for (size_t i=0; i < 6; i++) {
209  position[i] = fPe[i];
210  }
211  break;
212  }
213  case TOOL_FRAME: { // same a CAMERA_FRAME
214  position.resize(6);
215  vpHomogeneousMatrix fMc = get_fMc(q);
216  vpPoseVector fPc(fMc);
217  for (size_t i=0; i < 6; i++) {
218  position[i] = fPc[i];
219  }
220  break;
221  }
222  default: {
223  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: wrong method"));
224  }
225  }
226 }
227 
242 {
243  if (!m_handler) {
244  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
245  }
246 
247  franka::RobotState robot_state = getRobotInternalState();
248 
249  switch(frame) {
250  case JOINT_STATE: {
251  force.resize(7);
252  for (int i=0; i < 7; i++)
253  force[i] = robot_state.tau_J[i];
254 
255  break;
256  }
257  case END_EFFECTOR_FRAME: {
258  force.resize(6);
259  for (int i=0; i < 6; i++)
260  force[i] = robot_state.K_F_ext_hat_K[i];
261  break;
262  }
263  case TOOL_FRAME: {
264  // end-effector frame
265  vpColVector eFe(6);
266  for (int i=0; i < 6; i++)
267  eFe[i] = robot_state.K_F_ext_hat_K[i];
268 
269  // Transform in tool frame
271  vpForceTwistMatrix cWe( cMe );
272  force = cWe * eFe;
273  break;
274  }
275  default: {
276  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: wrong method"));
277  }
278  }
279 }
280 
296 {
297  if (!m_handler) {
298  throw(vpException(vpException::fatalError, "Cannot get Franka robot velocity: robot is not connected"));
299  }
300 
301  franka::RobotState robot_state = getRobotInternalState();
302 
303  switch(frame) {
304 
305  case JOINT_STATE: {
306  d_position.resize(7);
307  for (int i=0; i < 7; i++) {
308  d_position[i]=robot_state.dq[i];
309  }
310  break;
311  }
312 
313  default: {
314  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian velocity: not implemented"));
315  }
316  }
317 }
318 
325 {
326  if (!m_handler) {
327  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
328  }
329 
330  std::array<double, 7> coriolis_;
331 
332  franka::RobotState robot_state = getRobotInternalState();
333 
334  coriolis_ = m_model->coriolis(robot_state);
335 
336  coriolis.resize(7);
337  for (int i=0; i < 7; i++) {
338  coriolis[i] = coriolis_[i];
339  }
340 }
341 
347 {
348  if (!m_handler) {
349  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
350  }
351 
352  std::array<double, 7> gravity_;
353 
354  franka::RobotState robot_state = getRobotInternalState();
355 
356  gravity_ = m_model->gravity(robot_state);
357 
358  gravity.resize(7);
359  for (int i=0; i < 7; i++) {
360  gravity[i] = gravity_[i];
361  }
362 }
363 
369 {
370  if (!m_handler) {
371  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
372  }
373 
374  std::array<double, 49> mass_;
375 
376  franka::RobotState robot_state = getRobotInternalState();
377 
378  mass_ = m_model->mass(robot_state); // column-major
379 
380  mass.resize(7, 7); // row-major
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];
384  }
385  }
386 }
387 
396 {
397  if (!m_handler) {
398  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
399  }
400  if (q.size() != 7) {
401  throw(vpException(vpException::fatalError, "Joint position vector [%u] is not a 7-dim vector", q.size()));
402  }
403 
404  std::array< double, 7 > q_array;
405  for (size_t i = 0; i < 7; i++)
406  q_array[i] = q[i];
407 
408  franka::RobotState robot_state = getRobotInternalState();
409 
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];
415  }
416  }
417 
418  return fMe;
419 }
420 
436 {
437  vpHomogeneousMatrix fMe = get_fMe(q);
438  return (fMe * m_eMc);
439 }
440 
452 {
453  if (!m_handler) {
454  throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
455  }
456 
457  franka::RobotState robot_state = getRobotInternalState();
458 
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];
464  }
465  }
466 
467  switch(frame) {
468  case END_EFFECTOR_FRAME: {
469  pose.buildFrom(fMe);
470  break;
471  }
472  case TOOL_FRAME: {
473  pose.buildFrom(fMe * m_eMc);
474  break;
475  }
476  default: {
477  throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: not implemented"));
478  }
479  }
480 }
481 
488 {
489  if (!m_handler) {
490  throw(vpException(vpException::fatalError, "Cannot get Franka robot eJe jacobian: robot is not connected"));
491  }
492 
493  franka::RobotState robot_state = getRobotInternalState();
494 
495  std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, robot_state); // column-major
496  eJe_.resize(6, 7); // row-major
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];
500  }
501  }
502  // TODO check from vpRobot fJe and fJeAvailable
503 }
504 
512 {
513  if (!m_handler) {
514  throw(vpException(vpException::fatalError, "Cannot get Franka robot eJe jacobian: robot is not connected"));
515  }
516 
517  franka::RobotState robot_state = getRobotInternalState();
518 
519  std::array< double, 7 > q_array;
520  for (size_t i = 0; i < 7; i++)
521  q_array[i] = q[i];
522 
523  std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K); // column-major
524  eJe_.resize(6, 7); // row-major
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];
528  }
529  }
530  // TODO check from vpRobot fJe and fJeAvailable
531 
532 }
533 
540 {
541  if (!m_handler) {
542  throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian: robot is not connected"));
543  }
544 
545  franka::RobotState robot_state = getRobotInternalState();
546 
547  std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, robot_state); // column-major
548  fJe_.resize(6, 7); // row-major
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];
552  }
553  }
554  // TODO check from vpRobot fJe and fJeAvailable
555 }
556 
564 {
565  if (!m_handler) {
566  throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian: robot is not connected"));
567  }
568  if (q.size() != 7) {
569  throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian with an input joint position vector [%u] that is not a 7-dim vector", q.size()));
570  }
571 
572  franka::RobotState robot_state = getRobotInternalState();
573 
574  std::array< double, 7 > q_array;
575  for (size_t i = 0; i < 7; i++)
576  q_array[i] = q[i];
577 
578  std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K); // column-major
579  fJe_.resize(6, 7); // row-major
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];
583  }
584  }
585  // TODO check from vpRobot fJe and fJeAvailable
586 }
587 
597 void vpRobotFranka::setLogFolder(const std::string &folder)
598 {
599  if (!folder.empty()) {
600  if (vpIoTools::checkDirectory(folder) == false) {
601  try {
602  vpIoTools::makeDirectory(folder);
603  m_log_folder = folder;
604  }
605  catch(const vpException &e) {
606  std::string error;
607  error = "Unable to create Franka log folder: " + folder;
608  throw(vpException(vpException::fatalError, error));
609  }
610  }
611  else {
612  m_log_folder = folder;
613  }
614  }
615 }
616 
623 {
624  if (!m_handler) {
625  throw(vpException(vpException::fatalError, "Cannot set Franka robot position: robot is not connected"));
626  }
628  std::cout << "Robot was not in position-based control. "
629  "Modification of the robot state" << std::endl;
631  }
632 
633  if (frame == vpRobot::JOINT_STATE) {
634  double speed_factor = m_positionningVelocity / 100.;
635 
636  std::array<double, 7> q_goal;
637  for (size_t i = 0; i < 7; i++) {
638  q_goal[i] = position[i];
639  }
640 
641  vpJointPosTrajGenerator joint_pos_traj_generator(speed_factor, q_goal);
642 
643  int nbAttempts = 10;
644  for (int attempt = 1; attempt <= nbAttempts; attempt++) {
645  try {
646  m_handler->control(joint_pos_traj_generator);
647  break;
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)
652  throw;
653  }
654  }
655  }
656  else {
658  "Cannot move the robot to a cartesian position. Only joint positionning is implemented"));
659  }
660 }
661 
671 {
672  m_positionningVelocity = velocity;
673 }
674 
682 {
683  switch (newState) {
684  case vpRobot::STATE_STOP: {
685  // Start primitive STOP only if the current state is velocity or force/torque
687  // Stop the robot
688  m_velControlThreadStopAsked = true;
689  if(m_velControlThread.joinable()) {
690  m_velControlThread.join();
691  m_velControlThreadStopAsked = false;
692  m_velControlThreadIsRunning = false;
693  }
694  }
696  // Stop the robot
697  m_ftControlThreadStopAsked = true;
698  if(m_ftControlThread.joinable()) {
699  m_ftControlThread.join();
700  m_ftControlThreadStopAsked = false;
701  m_ftControlThreadIsRunning = false;
702  }
703  }
704  break;
705  }
708  std::cout << "Change the control mode from velocity to position control.\n";
709  // Stop the robot
710  m_velControlThreadStopAsked = true;
711  if(m_velControlThread.joinable()) {
712  m_velControlThread.join();
713  m_velControlThreadStopAsked = false;
714  m_velControlThreadIsRunning = false;
715  }
716  }
718  std::cout << "Change the control mode from force/torque to position control.\n";
719  // Stop the robot
720  m_ftControlThreadStopAsked = true;
721  if(m_ftControlThread.joinable()) {
722  m_ftControlThread.join();
723  m_ftControlThreadStopAsked = false;
724  m_ftControlThreadIsRunning = false;
725  }
726  }
727  break;
728  }
731  std::cout << "Change the control mode from stop to velocity control.\n";
732  }
734  std::cout << "Change the control mode from position to velocity control.\n";
735  }
737  std::cout << "Change the control mode from force/torque to velocity control.\n";
738  // Stop the robot
739  m_ftControlThreadStopAsked = true;
740  if(m_ftControlThread.joinable()) {
741  m_ftControlThread.join();
742  m_ftControlThreadStopAsked = false;
743  m_ftControlThreadIsRunning = false;
744  }
745  }
746  break;
747  }
750  std::cout << "Change the control mode from stop to force/torque control.\n";
751  }
753  std::cout << "Change the control mode from position to force/torque control.\n";
754  }
756  std::cout << "Change the control mode from velocity to force/torque control.\n";
757  // Stop the robot
758  m_velControlThreadStopAsked = true;
759  if(m_velControlThread.joinable()) {
760  m_velControlThread.join();
761  m_velControlThreadStopAsked = false;
762  m_velControlThreadIsRunning = false;
763  }
764  }
765  break;
766  }
767 
768  default:
769  break;
770  }
771 
772  return vpRobot::setRobotState(newState);
773 }
774 
829 {
832  "Cannot send a velocity to the robot. "
833  "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first.");
834  }
835 
836  switch (frame) {
837  // Saturation in joint space
838  case JOINT_STATE: {
839  if (vel.size() != 7) {
841  "Joint velocity vector (%d) is not of size 7", vel.size());
842  }
843 
844  vpColVector vel_max(7, getMaxRotationVelocity());
845 
846  vpColVector vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
847 
848  for (size_t i = 0; i < m_dq_des.size(); i++) { // TODO create a function to convert
849  m_dq_des[i] = vel_sat[i];
850  }
851 
852  break;
853  }
854 
855  // Saturation in cartesian space
856  case vpRobot::TOOL_FRAME:
859  if (vel.size() != 6) {
861  "Cartesian velocity vector (%d) is not of size 6", vel.size());
862  }
863  vpColVector vel_max(6);
864 
865  for (unsigned int i = 0; i < 3; i++)
866  vel_max[i] = getMaxTranslationVelocity();
867  for (unsigned int i = 3; i < 6; i++)
868  vel_max[i] = getMaxRotationVelocity();
869 
870  m_v_cart_des = vpRobot::saturateVelocities(vel, vel_max, true);
871 
872  break;
873  }
874 
875  case vpRobot::MIXT_FRAME: {
877  "Velocity controller not supported");
878  }
879  }
880 
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));
888  }
889 }
890 
891 /*
892  Apply a force/torque to the robot.
893 
894  \param[in] frame : Control frame in which the force/torque is applied.
895 
896  \param[in] ft : Force/torque vector. The size of this vector
897  is always 6 for a cartesian force/torque skew, and 7 for joint torques.
898 
899  \param[in] filter_gain : Value in range [0:1] to filter the force/torque vector \e ft.
900  To diable the filter set filter_gain to 1.
901  \param[in] activate_pi_controller : Activate proportional and integral low level controller.
902  */
904  const double &filter_gain, const bool &activate_pi_controller)
905 {
906  switch (frame) {
907  // Saturation in joint space
908  case JOINT_STATE: {
909  if (ft.size() != 7) {
911  "Joint torques vector (%d) is not of size 7", ft.size());
912  }
913 
914  for (size_t i = 0; i < m_tau_J_des.size(); i++) { // TODO create a function to convert
915  m_tau_J_des[i] = ft[i];
916  }
917  // TODO: Introduce force/torque saturation
918 
919  break;
920  }
921 
922  // Saturation in cartesian space
923  case vpRobot::TOOL_FRAME:
926  if (ft.size() != 6) {
928  "Cartesian force/torque vector (%d) is not of size 6", ft.size());
929  }
930 
931  m_ft_cart_des = ft;
932  // TODO: Introduce force/torque saturation
933 
934  break;
935  }
936 
937  case vpRobot::MIXT_FRAME: {
939  "Velocity controller not supported");
940  }
941  }
942 
943  if(! m_ftControlThreadIsRunning) {
944  getRobotInternalState(); // Update m_robot_state internally
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);
950  }
951 }
952 
954 {
955  if (!m_handler) {
956  throw(vpException(vpException::fatalError, "Cannot get Franka robot state: robot is not connected"));
957  }
958  franka::RobotState robot_state;
959 
960  if (! m_velControlThreadIsRunning && ! m_ftControlThreadIsRunning) {
961  robot_state = m_handler->readOnce();
962 
963  std::lock_guard<std::mutex> lock(m_mutex);
964  m_robot_state = robot_state;
965  }
966  else { // robot_state is updated in the velocity control thread
967  std::lock_guard<std::mutex> lock(m_mutex);
968  robot_state = m_robot_state;
969  }
970 
971  return robot_state;
972 }
973 
980 {
981  vpColVector q_min(m_q_min.size());
982  for (size_t i = 0; i < m_q_min.size(); i ++)
983  q_min[i] = m_q_min[i];
984 
985  return q_min;
986 }
993 {
994  vpColVector q_max(m_q_max.size());
995  for (size_t i = 0; i < m_q_max.size(); i ++)
996  q_max[i] = m_q_max[i];
997 
998  return q_max;
999 }
1000 
1012 {
1013  return m_eMc;
1014 }
1015 
1029 {
1030  m_eMc = eMc;
1031 }
1032 
1042 void vpRobotFranka::move(const std::string &filename, double velocity_percentage)
1043 {
1044  vpColVector q;
1045 
1046  this->readPosFile(filename, q);
1048  this->setPositioningVelocity(velocity_percentage);
1050 }
1051 
1096 bool vpRobotFranka::readPosFile(const std::string &filename, vpColVector &q)
1097 {
1098  std::ifstream fd(filename.c_str(), std::ios::in);
1099 
1100  if (!fd.is_open()) {
1101  return false;
1102  }
1103 
1104  std::string line;
1105  std::string key("R:");
1106  std::string id("#PANDA - Joint position file");
1107  bool pos_found = false;
1108  int lineNum = 0;
1109  size_t njoints = 7;
1110 
1111  q.resize(njoints);
1112 
1113  while (std::getline(fd, line)) {
1114  lineNum++;
1115  if (lineNum == 1) {
1116  if (!(line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
1117  std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
1118  return false;
1119  }
1120  }
1121  if ((line.compare(0, 1, "#") == 0)) { // skip comment
1122  continue;
1123  }
1124  if ((line.compare(0, key.size(), key) == 0)) { // decode position
1125  // check if there are at least njoint values in the line
1126  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1127  if (chain.size() < njoints + 1) // try to split with tab separator
1128  chain = vpIoTools::splitChain(line, std::string("\t"));
1129  if (chain.size() < njoints + 1)
1130  continue;
1131 
1132  std::istringstream ss(line);
1133  std::string key_;
1134  ss >> key_;
1135  for (unsigned int i = 0; i < njoints; i++)
1136  ss >> q[i];
1137  pos_found = true;
1138  break;
1139  }
1140  }
1141 
1142  // converts rotations from degrees into radians
1143  for (unsigned int i = 0; i < njoints; i++) {
1144  q[i] = vpMath::rad(q[i]);
1145  }
1146 
1147  fd.close();
1148 
1149  if (!pos_found) {
1150  std::cout << "Error: unable to find a position for Panda robot in " << filename << std::endl;
1151  return false;
1152  }
1153 
1154  return true;
1155 }
1156 
1179 bool vpRobotFranka::savePosFile(const std::string &filename, const vpColVector &q)
1180 {
1181 
1182  FILE *fd;
1183  fd = fopen(filename.c_str(), "w");
1184  if (fd == NULL)
1185  return false;
1186 
1187  fprintf(fd,
1188  "#PANDA - Joint position file\n"
1189  "#\n"
1190  "# R: q1 q2 q3 q4 q5 q6 q7\n"
1191  "# with joint positions q1 to q7 expressed in degrees\n"
1192  "#\n");
1193 
1194  // Save positions in mm and deg
1195  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
1196  vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]), vpMath::deg(q[6]));
1197 
1198  fclose(fd);
1199  return (true);
1200 }
1201 
1210 {
1212  vpColVector q(7, 0);
1214  }
1216 }
1217 
1225 {
1226  if (m_franka_address.empty()) {
1227  throw (vpException(vpException::fatalError, "Cannot perform franka gripper homing without ip address"));
1228  }
1229  if (m_gripper == NULL)
1230  m_gripper = new franka::Gripper(m_franka_address);
1231 
1232  m_gripper->homing();
1233 }
1234 
1245 {
1246  if (m_franka_address.empty()) {
1247  throw (vpException(vpException::fatalError, "Cannot open franka gripper without ip address"));
1248  }
1249  if (m_gripper == NULL)
1250  m_gripper = new franka::Gripper(m_franka_address);
1251 
1252  // Check for the maximum grasping width.
1253  franka::GripperState gripper_state = m_gripper->readOnce();
1254 
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;
1259  }
1260 
1261  m_gripper->move(width, 0.1);
1262  return EXIT_SUCCESS;
1263 }
1264 
1274 {
1275  return gripperMove(0);
1276 }
1277 
1287 {
1288  if (m_franka_address.empty()) {
1289  throw (vpException(vpException::fatalError, "Cannot open franka gripper without ip address"));
1290  }
1291  if (m_gripper == NULL)
1292  m_gripper = new franka::Gripper(m_franka_address);
1293 
1294  // Check for the maximum grasping width.
1295  franka::GripperState gripper_state = m_gripper->readOnce();
1296 
1297  m_gripper->move(gripper_state.max_width, 0.1);
1298  return EXIT_SUCCESS;
1299 }
1300 
1308 {
1309  if (m_franka_address.empty()) {
1310  throw (vpException(vpException::fatalError, "Cannot release franka gripper without ip address"));
1311  }
1312  if (m_gripper == NULL)
1313  m_gripper = new franka::Gripper(m_franka_address);
1314 
1315  m_gripper->stop();
1316 }
1317 
1332 int vpRobotFranka::gripperGrasp(double grasping_width, double force)
1333 {
1334  if (m_gripper == NULL)
1335  m_gripper = new franka::Gripper(m_franka_address);
1336 
1337  // Check for the maximum grasping width.
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;
1344  }
1345 
1346  // Grasp the object.
1347  if (!m_gripper->grasp(grasping_width, 0.1, force)) {
1348  std::cout << "Failed to grasp object." << std::endl;
1349  return EXIT_FAILURE;
1350  }
1351 
1352  return EXIT_SUCCESS;
1353 }
1354 
1355 #elif !defined(VISP_BUILD_SHARED_LIBS)
1356 // Work arround to avoid warning: libvisp_robot.a(vpRobotFranka.cpp.o) has
1357 // no symbols
1358 void dummy_vpRobotFranka(){};
1359 #endif
1360 
int gripperMove(double width)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:164
static void makeDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:572
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition: vpArray2D.h:305
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)
virtual ~vpRobotFranka()
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:251
vpHomogeneousMatrix get_fMe(const vpColVector &q)
void getGravity(vpColVector &gravity)
Initialize the position controller.
Definition: vpRobot.h:67
error that can be emited by ViSP classes.
Definition: vpException.h:71
void setPositioningVelocity(double velocity)
vpHomogeneousMatrix inverse() const
franka::RobotState getRobotInternalState()
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
vpControlFrameType
Definition: vpRobot.h:75
vpHomogeneousMatrix get_eMc() const
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:291
void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:273
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)
Definition: vpRobot.cpp:201
static bool checkDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:422
void set_eMc(const vpHomogeneousMatrix &eMc)
Initialize the velocity controller.
Definition: vpRobot.h:66
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:144
vpRobotStateType
Definition: vpRobot.h:64
bool readPosFile(const std::string &filename, vpColVector &q)
vpPoseVector buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz)
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1767
void get_eJe(vpMatrix &eJe)
static double rad(double deg)
Definition: vpMath.h:108
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:65
void get_fJe(vpMatrix &fJe)
int nDof
number of degrees of freedom
Definition: vpRobot.h:102
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:310
static double deg(double rad)
Definition: vpMath.h:101
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:151
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.
Definition: vpRobot.h:69
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.
Definition: vpException.h:90
vpColVector getJointMax() const
vpColVector getJointMin() const