Visual Servoing Platform  version 3.6.1 under development (2024-11-14)
vpRobotFranka.h
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the Franka robot.
32  */
33 
34 #ifndef _vpRobotFranka_h_
35 #define _vpRobotFranka_h_
36 
37 #include <visp3/core/vpConfig.h>
38 
39 #if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS)
40 
41 #include <atomic>
42 #include <iostream>
43 #include <thread>
44 #include <vector>
45 
46 #include <stdio.h>
47 
48 #include <franka/exception.h>
49 #include <franka/gripper.h>
50 #include <franka/model.h>
51 #include <franka/robot.h>
52 
53 #include <visp3/core/vpColVector.h>
54 #include <visp3/core/vpException.h>
55 #include <visp3/robot/vpRobot.h>
56 
57 BEGIN_VISP_NAMESPACE
222 class VISP_EXPORT vpRobotFranka : public vpRobot
223 {
224 private:
228  vpRobotFranka(const vpRobotFranka &robot);
232  void getDisplacement(const vpRobot::vpControlFrameType, vpColVector &) VP_OVERRIDE { };
233 
234  void init();
235 
236  franka::Robot *m_handler;
237  franka::Gripper *m_gripper;
238  franka::Model *m_model;
239  double m_positioningVelocity;
240 
241  // Velocity controller
242  std::thread m_velControlThread;
243  std::atomic_bool m_velControlThreadIsRunning;
244  std::atomic_bool m_velControlThreadStopAsked;
245  std::array<double, 7> m_dq_des; // Desired joint velocity
246  vpColVector m_v_cart_des; // Desired cartesian velocity either in reference, end-effector, camera, or tool frame
247 
248  // Force/torque controller
249  std::thread m_ftControlThread;
250  std::atomic_bool m_ftControlThreadIsRunning;
251  std::atomic_bool m_ftControlThreadStopAsked;
252  std::array<double, 7> m_tau_J_des; // Desired joint torques
253  vpColVector m_ft_cart_des; // Desired cartesian force/torque either in reference, end-effector, camera, or tool frame
254 
255  std::array<double, 7> m_q_min; // Joint min position
256  std::array<double, 7> m_q_max; // Joint max position
257  std::array<double, 7> m_dq_max; // Joint max velocity
258  std::array<double, 7> m_ddq_max; // Joint max acceleration
259 
260  franka::RobotState m_robot_state; // Robot state protected by mutex
261  std::mutex m_mutex; // Mutex to protect m_robot_state
262 
263  vpHomogeneousMatrix m_eMc;
264  std::string m_log_folder;
265  std::string m_franka_address;
266 
267 public:
268  vpRobotFranka();
269 
270  vpRobotFranka(const std::string &franka_address,
271  franka::RealtimeConfig realtime_config = franka::RealtimeConfig::kEnforce);
272 
273  virtual ~vpRobotFranka();
274 
275  void connect(const std::string &franka_address,
276  franka::RealtimeConfig realtime_config = franka::RealtimeConfig::kEnforce);
277 
278  vpHomogeneousMatrix get_fMe(const vpColVector &q);
279  vpHomogeneousMatrix get_fMc(const vpColVector &q);
280  vpHomogeneousMatrix get_eMc() const;
281 
282  void get_eJe(vpMatrix &eJe) VP_OVERRIDE;
283  void get_eJe(const vpColVector &q, vpMatrix &eJe);
284  void get_fJe(vpMatrix &fJe) VP_OVERRIDE;
285  void get_fJe(const vpColVector &q, vpMatrix &fJe);
286 
287  void getCoriolis(vpColVector &coriolis);
288  void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force);
289 
290  void getGravity(vpColVector &gravity);
291 
292  franka::RobotState getRobotInternalState();
293 
299  franka::Gripper *getGripperHandler()
300  {
301  if (!m_gripper) {
302  throw(vpException(vpException::fatalError, "Cannot get Franka gripper handler: gripper is not connected"));
303  }
304 
305  return m_gripper;
306  }
307 
313  franka::Robot *getHandler()
314  {
315  if (!m_handler) {
316  throw(vpException(vpException::fatalError, "Cannot get Franka robot handler: robot is not connected"));
317  }
318 
319  return m_handler;
320  }
321 
322  vpColVector getJointMin() const;
323  vpColVector getJointMax() const;
324 
325  void getMass(vpMatrix &mass);
326 
327  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE;
328  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &pose);
329 
330  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position);
331 
332  int gripperClose();
333  int gripperGrasp(double grasping_width, double force = 60.);
334  int gripperGrasp(double grasping_width, double speed, double force);
335  void gripperHoming();
336  int gripperMove(double width);
337  int gripperOpen();
338  void gripperRelease();
339 
340  void move(const std::string &filename, double velocity_percentage = 10.);
341 
342  bool readPosFile(const std::string &filename, vpColVector &q);
343  bool savePosFile(const std::string &filename, const vpColVector &q);
344 
345  void set_eMc(const vpHomogeneousMatrix &eMc);
346  void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &ft, const double &filter_gain = 0.1,
347  const bool &activate_pi_controller = false);
348  void setLogFolder(const std::string &folder);
349  void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE;
350  void setPositioningVelocity(double velocity);
351 
353  void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE;
354 
355  void stopMotion();
356 };
357 END_VISP_NAMESPACE
358 #endif
359 #endif // #ifndef __vpRobotFranka_h_
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ fatalError
Fatal error.
Definition: vpException.h:72
Implementation of an homogeneous matrix and operations on such kind of matrices.
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
franka::Robot * getHandler()
franka::Gripper * getGripperHandler()
Class that defines a generic virtual robot.
Definition: vpRobot.h:59
vpControlFrameType
Definition: vpRobot.h:77
virtual void get_eJe(vpMatrix &_eJe)=0
Get the robot Jacobian expressed in the end-effector frame.
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)=0
Get the robot position (frame has to be specified).
vpRobotStateType
Definition: vpRobot.h:65
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
virtual void init()=0
virtual void get_fJe(vpMatrix &_fJe)=0
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.