Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotFranka.h
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 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 VP_ROBOT_FRANKA_H
35#define VP_ROBOT_FRANKA_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
226class VISP_EXPORT vpRobotFranka : public vpRobot
227{
228private:
232 vpRobotFranka(const vpRobotFranka &robot);
236 void getDisplacement(const vpRobot::vpControlFrameType, vpColVector &) VP_OVERRIDE { }
237
238 void init();
239
240 franka::Robot *m_handler;
241 franka::Gripper *m_gripper;
242 franka::Model *m_model;
243 double m_positioningVelocity;
244
245 // Velocity controller
246 std::thread m_velControlThread;
247 std::atomic_bool m_velControlThreadIsRunning;
248 std::atomic_bool m_velControlThreadStopAsked;
249 std::array<double, 7> m_dq_des; // Desired joint velocity
250 vpColVector m_v_cart_des; // Desired cartesian velocity either in reference, end-effector, camera, or tool frame
251
252 // Force/torque controller
253 std::thread m_ftControlThread;
254 std::atomic_bool m_ftControlThreadIsRunning;
255 std::atomic_bool m_ftControlThreadStopAsked;
256 std::array<double, 7> m_tau_J_des; // Desired joint torques
257 vpColVector m_ft_cart_des; // Desired cartesian force/torque either in reference, end-effector, camera, or tool frame
258
259 std::array<double, 7> m_q_min; // Joint min position
260 std::array<double, 7> m_q_max; // Joint max position
261 std::array<double, 7> m_dq_max; // Joint max velocity
262 std::array<double, 7> m_ddq_max; // Joint max acceleration
263
264 franka::RobotState m_robot_state; // Robot state protected by mutex
265 std::mutex m_mutex; // Mutex to protect m_robot_state
266
268 std::string m_log_folder;
269 std::string m_franka_address;
270
271public:
277 enum class vpRealtimeConfig { kEnforce, kIgnore };
278
280
281 vpRobotFranka(const std::string &franka_address,
282 franka::RealtimeConfig realtime_config = franka::RealtimeConfig::kEnforce);
283 vpRobotFranka(const std::string &franka_address, vpRealtimeConfig realtime_config);
284
285 virtual ~vpRobotFranka();
286
287 void connect(const std::string &franka_address,
288 franka::RealtimeConfig realtime_config = franka::RealtimeConfig::kEnforce);
289 void connect(const std::string &franka_address, vpRealtimeConfig realtime_config);
290
291 vpHomogeneousMatrix get_fMe(const vpColVector &q);
292 vpHomogeneousMatrix get_fMc(const vpColVector &q);
293 vpHomogeneousMatrix get_eMc() const;
294
295 void get_eJe(vpMatrix &eJe) VP_OVERRIDE;
296 void get_eJe(const vpColVector &q, vpMatrix &eJe);
297 void get_fJe(vpMatrix &fJe) VP_OVERRIDE;
298 void get_fJe(const vpColVector &q, vpMatrix &fJe);
299
300 void getCoriolis(vpColVector &coriolis);
301 void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force);
302
303 void getGravity(vpColVector &gravity);
304
305 franka::RobotState getRobotInternalState();
306
312 franka::Gripper *getGripperHandler()
313 {
314 if (!m_gripper) {
315 throw(vpException(vpException::fatalError, "Cannot get Franka gripper handler: gripper is not connected"));
316 }
317
318 return m_gripper;
319 }
320
326 franka::Robot *getHandler()
327 {
328 if (!m_handler) {
329 throw(vpException(vpException::fatalError, "Cannot get Franka robot handler: robot is not connected"));
330 }
331
332 return m_handler;
333 }
334
335 vpColVector getJointMin() const;
336 vpColVector getJointMax() const;
337
338 void getMass(vpMatrix &mass);
339
340 void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE;
342
343 void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position);
344
345 int gripperClose();
346 int gripperGrasp(double grasping_width, double force = 60.);
347 int gripperGrasp(double grasping_width, double speed, double force);
348 void gripperHoming();
349 int gripperMove(double width);
350 int gripperOpen();
351 void gripperRelease();
352
353 void move(const std::string &filename, double velocity_percentage = 10.);
354
355 bool readPosFile(const std::string &filename, vpColVector &q);
356 bool savePosFile(const std::string &filename, const vpColVector &q);
357
358 void set_eMc(const vpHomogeneousMatrix &eMc);
359 void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &ft, const double &filter_gain = 0.1,
360 const bool &activate_pi_controller = false);
361 void setLogFolder(const std::string &folder);
362 void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE;
363 void setPositioningVelocity(double velocity);
364
366 void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE;
367
368 void stopMotion();
369};
370END_VISP_NAMESPACE
371#endif
372#endif // #ifndef __vpRobotFranka_h_
Implementation of column vector and the associated operations.
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:175
Implementation of a pose vector and operations on poses.
franka::Robot * getHandler()
franka::Gripper * getGripperHandler()
vpControlFrameType
Definition vpRobot.h:74
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:62
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition vpRobot.cpp:200
virtual void init()=0
virtual void get_fJe(vpMatrix &_fJe)=0
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
vpRobot(void)
Definition vpRobot.cpp:49
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.