Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotFranka.cpp
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#include <visp3/core/vpConfig.h>
35
36#if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS)
37
38#include <visp3/core/vpIoTools.h>
39#include <visp3/robot/vpRobotException.h>
40#include <visp3/robot/vpRobotFranka.h>
41
42#include "vpForceTorqueGenerator_impl.h"
43#include "vpJointPosTrajGenerator_impl.h"
44#include "vpJointVelTrajGenerator_impl.h"
45
53 : vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
54 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
55 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
56 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(),
57 m_franka_address()
58{
59 init();
60}
61
68vpRobotFranka::vpRobotFranka(const std::string &franka_address, franka::RealtimeConfig realtime_config)
69 : vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
70 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
71 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
72 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(),
73 m_franka_address()
74{
75 init();
76 connect(franka_address, realtime_config);
77}
78
85vpRobotFranka::vpRobotFranka(const std::string &franka_address, vpRealtimeConfig realtime_config)
86 : vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(),
87 m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(),
88 m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(),
89 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(),
90 m_franka_address()
91{
92 init();
93 connect(franka_address, realtime_config);
94}
95
100{
101 nDof = 7;
102
103 m_q_min = std::array<double, 7>{-2.8973, -1.7628, -2.8973, -3.0718, -2.8973, -0.0175, -2.8973};
104 m_q_max = std::array<double, 7>{2.8973, 1.7628, 2.8973, -0.0698, 2.8973, 3.7525, 2.8973};
105 m_dq_max = std::array<double, 7>{2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100};
106 m_ddq_max = std::array<double, 7>{15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0};
107}
108
115{
117
118 if (m_handler)
119 delete m_handler;
120
121 if (m_gripper) {
122 delete m_gripper;
123 }
124
125 if (m_model) {
126 delete m_model;
127 }
128}
129
136void vpRobotFranka::connect(const std::string &franka_address, franka::RealtimeConfig realtime_config)
137{
138 init();
139 if (franka_address.empty()) {
140 throw(vpException(vpException::fatalError, "Cannot connect Franka robot: IP/hostname is not set"));
141 }
142 if (m_handler)
143 delete m_handler;
144
145 m_franka_address = franka_address;
146 m_handler = new franka::Robot(franka_address, realtime_config);
147
148 std::array<double, 7> lower_torque_thresholds_nominal { {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.} };
149 std::array<double, 7> upper_torque_thresholds_nominal { {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0} };
150 std::array<double, 7> lower_torque_thresholds_acceleration { {25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.0} };
151 std::array<double, 7> upper_torque_thresholds_acceleration { {35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0} };
152 std::array<double, 6> lower_force_thresholds_nominal { {30.0, 30.0, 30.0, 25.0, 25.0, 25.0} };
153 std::array<double, 6> upper_force_thresholds_nominal { {40.0, 40.0, 40.0, 35.0, 35.0, 35.0} };
154 std::array<double, 6> lower_force_thresholds_acceleration { {30.0, 30.0, 30.0, 25.0, 25.0, 25.0} };
155 std::array<double, 6> upper_force_thresholds_acceleration { {40.0, 40.0, 40.0, 35.0, 35.0, 35.0} };
156 m_handler->setCollisionBehavior(lower_torque_thresholds_acceleration, upper_torque_thresholds_acceleration,
157 lower_torque_thresholds_nominal, upper_torque_thresholds_nominal,
158 lower_force_thresholds_acceleration, upper_force_thresholds_acceleration,
159 lower_force_thresholds_nominal, upper_force_thresholds_nominal);
160
161 m_handler->setJointImpedance({ {3000, 3000, 3000, 2500, 2500, 2000, 2000} });
162 m_handler->setCartesianImpedance({ {3000, 3000, 3000, 300, 300, 300} });
163#if (VISP_HAVE_FRANKA_VERSION < 0x000500)
164 // m_handler->setFilters(100, 100, 100, 100, 100);
165 m_handler->setFilters(10, 10, 10, 10, 10);
166#else
167 // use franka::lowpassFilter() instead throw Franka::robot::control() with cutoff_frequency parameter
168#endif
169 if (m_model) {
170 delete m_model;
171 }
172 m_model = new franka::Model(m_handler->loadModel());
173}
174
181void vpRobotFranka::connect(const std::string &franka_address, vpRealtimeConfig realtime_config)
182{
183 switch (realtime_config) {
185 connect(franka_address, franka::RealtimeConfig::kEnforce);
186 break;
188 connect(franka_address, franka::RealtimeConfig::kIgnore);
189 break;
190 }
191}
192
208{
209 if (!m_handler) {
210 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
211 }
212
213 franka::RobotState robot_state = getRobotInternalState();
214 vpColVector q(7);
215 for (int i = 0; i < 7; i++) {
216 q[i] = robot_state.q[i];
217 }
218
219 switch (frame) {
220 case JOINT_STATE: {
221 position = q;
222 break;
223 }
224 case END_EFFECTOR_FRAME: {
225 position.resize(6);
227 vpPoseVector fPe(fMe);
228 for (size_t i = 0; i < 6; i++) {
229 position[i] = fPe[i];
230 }
231 break;
232 }
233 case TOOL_FRAME: { // same a CAMERA_FRAME
234 position.resize(6);
236 vpPoseVector fPc(fMc);
237 for (size_t i = 0; i < 6; i++) {
238 position[i] = fPc[i];
239 }
240 break;
241 }
242 default: {
243 throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: wrong method"));
244 }
245 }
246}
247
259{
260 if (!m_handler) {
261 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
262 }
263
264 franka::RobotState robot_state = getRobotInternalState();
265
266 switch (frame) {
267 case JOINT_STATE: {
268 force.resize(7);
269 for (int i = 0; i < 7; i++)
270 force[i] = robot_state.tau_J[i];
271
272 break;
273 }
274 case END_EFFECTOR_FRAME: {
275 force.resize(6);
276 for (int i = 0; i < 6; i++)
277 force[i] = robot_state.K_F_ext_hat_K[i];
278 break;
279 }
280 case TOOL_FRAME: {
281 // end-effector frame
282 vpColVector eFe(6);
283 for (int i = 0; i < 6; i++)
284 eFe[i] = robot_state.K_F_ext_hat_K[i];
285
286 // Transform in tool frame
288 vpForceTwistMatrix cWe(cMe);
289 force = cWe * eFe;
290 break;
291 }
292 default: {
293 throw(vpException(vpException::fatalError, "Cannot get Franka force/torque: frame not supported"));
294 }
295 }
296}
297
313{
314 if (!m_handler) {
315 throw(vpException(vpException::fatalError, "Cannot get Franka robot velocity: robot is not connected"));
316 }
317
318 franka::RobotState robot_state = getRobotInternalState();
319
320 switch (frame) {
321
322 case JOINT_STATE: {
323 d_position.resize(7);
324 for (int i = 0; i < 7; i++) {
325 d_position[i] = robot_state.dq[i];
326 }
327 break;
328 }
329
330 default: {
331 throw(vpException(vpException::fatalError, "Cannot get Franka cartesian velocity: not implemented"));
332 }
333 }
334}
335
342{
343 if (!m_handler) {
344 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
345 }
346
347 std::array<double, 7> coriolis_;
348
349 franka::RobotState robot_state = getRobotInternalState();
350
351 coriolis_ = m_model->coriolis(robot_state);
352
353 coriolis.resize(7);
354 for (int i = 0; i < 7; i++) {
355 coriolis[i] = coriolis_[i];
356 }
357}
358
364{
365 if (!m_handler) {
366 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
367 }
368
369 std::array<double, 7> gravity_;
370
371 franka::RobotState robot_state = getRobotInternalState();
372
373 gravity_ = m_model->gravity(robot_state);
374
375 gravity.resize(7);
376 for (int i = 0; i < 7; i++) {
377 gravity[i] = gravity_[i];
378 }
379}
380
386{
387 if (!m_handler) {
388 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
389 }
390
391 std::array<double, 49> mass_;
392
393 franka::RobotState robot_state = getRobotInternalState();
394
395 mass_ = m_model->mass(robot_state); // column-major
396
397 mass.resize(7, 7); // row-major
398 for (size_t i = 0; i < 7; i++) {
399 for (size_t j = 0; j < 7; j++) {
400 mass[i][j] = mass_[j * 7 + i];
401 }
402 }
403}
404
413{
414 if (!m_handler) {
415 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
416 }
417 if (q.size() != 7) {
418 throw(vpException(vpException::fatalError, "Joint position vector [%u] is not a 7-dim vector", q.size()));
419 }
420
421 std::array<double, 7> q_array;
422 for (size_t i = 0; i < 7; i++)
423 q_array[i] = q[i];
424
425 franka::RobotState robot_state = getRobotInternalState();
426
427 std::array<double, 16> pose_array =
428 m_model->pose(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE, robot_state.EE_T_K);
430 for (unsigned int i = 0; i < 4; i++) {
431 for (unsigned int j = 0; j < 4; j++) {
432 fMe[i][j] = pose_array[j * 4 + i];
433 }
434 }
435
436 return fMe;
437}
438
454{
456 return (fMe * m_eMc);
457}
458
469{
470 if (!m_handler) {
471 throw(vpException(vpException::fatalError, "Cannot get Franka robot position: robot is not connected"));
472 }
473 if (frame == JOINT_STATE) {
474 throw(vpException(vpException::fatalError, "Cannot get Franka joint position as a pose vector"));
475 }
476
477 franka::RobotState robot_state = getRobotInternalState();
478
479 std::array<double, 16> pose_array = robot_state.O_T_EE;
481 for (unsigned int i = 0; i < 4; i++) {
482 for (unsigned int j = 0; j < 4; j++) {
483 fMe[i][j] = pose_array[j * 4 + i];
484 }
485 }
486
487 switch (frame) {
488 case END_EFFECTOR_FRAME: {
489 pose.buildFrom(fMe);
490 break;
491 }
492 case TOOL_FRAME: {
493 pose.buildFrom(fMe * m_eMc);
494 break;
495 }
496 default: {
497 throw(vpException(vpException::fatalError, "Cannot get Franka cartesian position: not implemented"));
498 }
499 }
500}
501
508{
509 if (!m_handler) {
510 throw(vpException(vpException::fatalError, "Cannot get Franka robot eJe jacobian: robot is not connected"));
511 }
512
513 franka::RobotState robot_state = getRobotInternalState();
514
515 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, robot_state); // column-major
516 eJe_.resize(6, 7); // row-major
517 for (size_t i = 0; i < 6; i++) {
518 for (size_t j = 0; j < 7; j++) {
519 eJe_[i][j] = jacobian[j * 6 + i];
520 }
521 }
522 // TODO check from vpRobot fJe and fJeAvailable
523}
524
531{
532 if (!m_handler) {
533 throw(vpException(vpException::fatalError, "Cannot get Franka robot eJe jacobian: robot is not connected"));
534 }
535
536 franka::RobotState robot_state = getRobotInternalState();
537
538 std::array<double, 7> q_array;
539 for (size_t i = 0; i < 7; i++)
540 q_array[i] = q[i];
541
542 std::array<double, 42> jacobian = m_model->bodyJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
543 robot_state.EE_T_K); // column-major
544 eJe_.resize(6, 7); // row-major
545 for (size_t i = 0; i < 6; i++) {
546 for (size_t j = 0; j < 7; j++) {
547 eJe_[i][j] = jacobian[j * 6 + i];
548 }
549 }
550 // TODO check from vpRobot fJe and fJeAvailable
551}
552
559{
560 if (!m_handler) {
561 throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian: robot is not connected"));
562 }
563
564 franka::RobotState robot_state = getRobotInternalState();
565
566 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, robot_state); // column-major
567 fJe_.resize(6, 7); // row-major
568 for (size_t i = 0; i < 6; i++) {
569 for (size_t j = 0; j < 7; j++) {
570 fJe_[i][j] = jacobian[j * 6 + i];
571 }
572 }
573 // TODO check from vpRobot fJe and fJeAvailable
574}
575
582{
583 if (!m_handler) {
584 throw(vpException(vpException::fatalError, "Cannot get Franka robot fJe jacobian: robot is not connected"));
585 }
586 if (q.size() != 7) {
587 throw(vpException(
589 "Cannot get Franka robot fJe jacobian with an input joint position vector [%u] that is not a 7-dim vector",
590 q.size()));
591 }
592
593 franka::RobotState robot_state = getRobotInternalState();
594
595 std::array<double, 7> q_array;
596 for (size_t i = 0; i < 7; i++)
597 q_array[i] = q[i];
598
599 std::array<double, 42> jacobian = m_model->zeroJacobian(franka::Frame::kEndEffector, q_array, robot_state.F_T_EE,
600 robot_state.EE_T_K); // column-major
601 fJe_.resize(6, 7); // row-major
602 for (size_t i = 0; i < 6; i++) {
603 for (size_t j = 0; j < 7; j++) {
604 fJe_[i][j] = jacobian[j * 6 + i];
605 }
606 }
607 // TODO check from vpRobot fJe and fJeAvailable
608}
609
619void vpRobotFranka::setLogFolder(const std::string &folder)
620{
621 if (!folder.empty()) {
622 if (vpIoTools::checkDirectory(folder) == false) {
623 try {
625 m_log_folder = folder;
626 }
627 catch (const vpException &e) {
628 std::string error;
629 error = "Unable to create Franka log folder: " + folder;
631 }
632 }
633 else {
634 m_log_folder = folder;
635 }
636 }
637}
638
645{
646 if (!m_handler) {
647 throw(vpException(vpException::fatalError, "Cannot set Franka robot position: robot is not connected"));
648 }
650 std::cout << "Robot was not in position-based control. "
651 "Modification of the robot state"
652 << std::endl;
654 }
655
656 if (frame == vpRobot::JOINT_STATE) {
657 double speed_factor = m_positioningVelocity / 100.;
658
659 std::array<double, 7> q_goal;
660 for (size_t i = 0; i < 7; i++) {
661 q_goal[i] = position[i];
662 }
663
664 vpJointPosTrajGenerator joint_pos_traj_generator(speed_factor, q_goal);
665
666 int nbAttempts = 10;
667 for (int attempt = 1; attempt <= nbAttempts; attempt++) {
668 try {
669 m_handler->control(joint_pos_traj_generator);
670 break;
671 }
672 catch (const franka::ControlException &e) {
673 std::cerr << "Warning: communication error: " << e.what() << "\nRetry attempt: " << attempt << std::endl;
674 m_handler->automaticErrorRecovery();
675 if (attempt == nbAttempts)
676 throw;
677 }
678 }
679 }
680 else {
682 "Cannot move the robot to a cartesian position. Only joint positioning is implemented"));
683 }
684}
685
694void vpRobotFranka::setPositioningVelocity(double velocity) { m_positioningVelocity = velocity; }
695
703{
704 switch (newState) {
705 case vpRobot::STATE_STOP: {
706 // Start primitive STOP only if the current state is velocity or force/torque
708 // Stop the robot
709 m_velControlThreadStopAsked = true;
710 if (m_velControlThread.joinable()) {
711 m_velControlThread.join();
712 m_velControlThreadStopAsked = false;
713 m_velControlThreadIsRunning = false;
714 }
715 }
717 // Stop the robot
718 m_ftControlThreadStopAsked = true;
719 if (m_ftControlThread.joinable()) {
720 m_ftControlThread.join();
721 m_ftControlThreadStopAsked = false;
722 m_ftControlThreadIsRunning = false;
723 }
724 }
725 break;
726 }
729 std::cout << "Change the control mode from velocity to position control.\n";
730 // Stop the robot
731 m_velControlThreadStopAsked = true;
732 if (m_velControlThread.joinable()) {
733 m_velControlThread.join();
734 m_velControlThreadStopAsked = false;
735 m_velControlThreadIsRunning = false;
736 }
737 }
739 std::cout << "Change the control mode from force/torque to position control.\n";
740 // Stop the robot
741 m_ftControlThreadStopAsked = true;
742 if (m_ftControlThread.joinable()) {
743 m_ftControlThread.join();
744 m_ftControlThreadStopAsked = false;
745 m_ftControlThreadIsRunning = false;
746 }
747 }
748 break;
749 }
752 std::cout << "Change the control mode from stop to velocity control.\n";
753 }
755 std::cout << "Change the control mode from position to velocity control.\n";
756 }
758 std::cout << "Change the control mode from force/torque to velocity control.\n";
759 // Stop the robot
760 m_ftControlThreadStopAsked = true;
761 if (m_ftControlThread.joinable()) {
762 m_ftControlThread.join();
763 m_ftControlThreadStopAsked = false;
764 m_ftControlThreadIsRunning = false;
765 }
766 }
767 break;
768 }
771 std::cout << "Change the control mode from stop to force/torque control.\n";
772 }
774 std::cout << "Change the control mode from position to force/torque control.\n";
775 }
777 std::cout << "Change the control mode from velocity to force/torque control.\n";
778 // Stop the robot
779 m_velControlThreadStopAsked = true;
780 if (m_velControlThread.joinable()) {
781 m_velControlThread.join();
782 m_velControlThreadStopAsked = false;
783 m_velControlThreadIsRunning = false;
784 }
785 }
786 break;
787 }
788
789 default:
790 break;
791 }
792
793 return vpRobot::setRobotState(newState);
794}
795
850{
853 "Cannot send a velocity to the robot. "
854 "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first.");
855 }
856
857 switch (frame) {
858 // Saturation in joint space
859 case JOINT_STATE: {
860 if (vel.size() != 7) {
861 throw vpRobotException(vpRobotException::wrongStateError, "Joint velocity vector (%d) is not of size 7",
862 vel.size());
863 }
864
866
867 vpColVector vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
868
869 for (size_t i = 0; i < m_dq_des.size(); i++) { // TODO create a function to convert
870 m_dq_des[i] = vel_sat[i];
871 }
872
873 break;
874 }
875
876 // Saturation in cartesian space
880 if (vel.size() != 6) {
881 throw vpRobotException(vpRobotException::wrongStateError, "Cartesian velocity vector (%d) is not of size 6",
882 vel.size());
883 }
884 vpColVector vel_max(6);
885
886 for (unsigned int i = 0; i < 3; i++)
887 vel_max[i] = getMaxTranslationVelocity();
888 for (unsigned int i = 3; i < 6; i++)
889 vel_max[i] = getMaxRotationVelocity();
890
891 m_v_cart_des = vpRobot::saturateVelocities(vel, vel_max, true);
892
893 break;
894 }
895
896 case vpRobot::MIXT_FRAME: {
897 throw vpRobotException(vpRobotException::wrongStateError, "Velocity controller not supported");
898 }
899 }
900
901 if (!m_velControlThreadIsRunning) {
902 m_velControlThreadIsRunning = true;
903 m_velControlThread =
904 std::thread(&vpJointVelTrajGenerator::control_thread, vpJointVelTrajGenerator(), std::ref(m_handler),
905 std::ref(m_velControlThreadStopAsked), m_log_folder, frame, m_eMc, std::ref(m_v_cart_des),
906 std::ref(m_dq_des), std::cref(m_q_min), std::cref(m_q_max), std::cref(m_dq_max),
907 std::cref(m_ddq_max), std::ref(m_robot_state), std::ref(m_mutex));
908 }
909}
910
911/*
912 Apply a force/torque to the robot.
913
914 \param[in] frame : Control frame in which the force/torque is applied.
915
916 \param[in] ft : Force/torque vector. The size of this vector
917 is always 6 for a cartesian force/torque skew, and 7 for joint torques.
918
919 \param[in] filter_gain : Value in range [0:1] to filter the force/torque vector \e ft.
920 To diable the filter set filter_gain to 1.
921 \param[in] activate_pi_controller : Activate proportional and integral low level controller.
922 */
924 const double &filter_gain, const bool &activate_pi_controller)
925{
926 switch (frame) {
927 // Saturation in joint space
928 case JOINT_STATE: {
929 if (ft.size() != 7) {
930 throw vpRobotException(vpRobotException::wrongStateError, "Joint torques vector (%d) is not of size 7",
931 ft.size());
932 }
933
934 for (size_t i = 0; i < m_tau_J_des.size(); i++) { // TODO create a function to convert
935 m_tau_J_des[i] = ft[i];
936 }
937 // TODO: Introduce force/torque saturation
938
939 break;
940 }
941
942 // Saturation in cartesian space
946 if (ft.size() != 6) {
947 throw vpRobotException(vpRobotException::wrongStateError, "Cartesian force/torque vector (%d) is not of size 6",
948 ft.size());
949 }
950
951 m_ft_cart_des = ft;
952 // TODO: Introduce force/torque saturation
953
954 break;
955 }
956
957 case vpRobot::MIXT_FRAME: {
958 throw vpRobotException(vpRobotException::wrongStateError, "Velocity controller not supported");
959 }
960 }
961
962 if (!m_ftControlThreadIsRunning) {
963 getRobotInternalState(); // Update m_robot_state internally
964 m_ftControlThreadIsRunning = true;
965 m_ftControlThread = std::thread(&vpForceTorqueGenerator::control_thread, vpForceTorqueGenerator(),
966 std::ref(m_handler), std::ref(m_ftControlThreadStopAsked), m_log_folder, frame,
967 std::ref(m_tau_J_des), std::ref(m_ft_cart_des), std::ref(m_robot_state),
968 std::ref(m_mutex), filter_gain, activate_pi_controller);
969 }
970}
971
973{
974 if (!m_handler) {
975 throw(vpException(vpException::fatalError, "Cannot get Franka robot state: robot is not connected"));
976 }
977 franka::RobotState robot_state;
978
979 if (!m_velControlThreadIsRunning && !m_ftControlThreadIsRunning) {
980 robot_state = m_handler->readOnce();
981
982 std::lock_guard<std::mutex> lock(m_mutex);
983 m_robot_state = robot_state;
984 }
985 else { // robot_state is updated in the velocity control thread
986 std::lock_guard<std::mutex> lock(m_mutex);
987 robot_state = m_robot_state;
988 }
989
990 return robot_state;
991}
992
999{
1000 vpColVector q_min(m_q_min.size());
1001 for (size_t i = 0; i < m_q_min.size(); i++)
1002 q_min[i] = m_q_min[i];
1003
1004 return q_min;
1005}
1006
1012{
1013 vpColVector q_max(m_q_max.size());
1014 for (size_t i = 0; i < m_q_max.size(); i++)
1015 q_max[i] = m_q_max[i];
1016
1017 return q_max;
1018}
1019
1031
1044void vpRobotFranka::set_eMc(const vpHomogeneousMatrix &eMc) { m_eMc = eMc; }
1045
1055void vpRobotFranka::move(const std::string &filename, double velocity_percentage)
1056{
1057 vpColVector q;
1058
1059 this->readPosFile(filename, q);
1061 this->setPositioningVelocity(velocity_percentage);
1063}
1064
1108
1109bool vpRobotFranka::readPosFile(const std::string &filename, vpColVector &q)
1110{
1111 std::ifstream fd(filename.c_str(), std::ios::in);
1112
1113 if (!fd.is_open()) {
1114 return false;
1115 }
1116
1117 std::string line;
1118 std::string key("R:");
1119 std::string id("#PANDA - Joint position file");
1120 bool pos_found = false;
1121 int lineNum = 0;
1122 size_t njoints = 7;
1123
1124 q.resize(njoints);
1125
1126 while (std::getline(fd, line)) {
1127 lineNum++;
1128 if (lineNum == 1) {
1129 if (!(line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
1130 std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
1131 return false;
1132 }
1133 }
1134 if ((line.compare(0, 1, "#") == 0)) { // skip comment
1135 continue;
1136 }
1137 if ((line.compare(0, key.size(), key) == 0)) { // decode position
1138 // check if there are at least njoint values in the line
1139 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1140 if (chain.size() < njoints + 1) // try to split with tab separator
1141 chain = vpIoTools::splitChain(line, std::string("\t"));
1142 if (chain.size() < njoints + 1)
1143 continue;
1144
1145 std::istringstream ss(line);
1146 std::string key_;
1147 ss >> key_;
1148 for (unsigned int i = 0; i < njoints; i++)
1149 ss >> q[i];
1150 pos_found = true;
1151 break;
1152 }
1153 }
1154
1155 // converts rotations from degrees into radians
1156 for (unsigned int i = 0; i < njoints; i++) {
1157 q[i] = vpMath::rad(q[i]);
1158 }
1159
1160 fd.close();
1161
1162 if (!pos_found) {
1163 std::cout << "Error: unable to find a position for Panda robot in " << filename << std::endl;
1164 return false;
1165 }
1166
1167 return true;
1168}
1169
1192bool vpRobotFranka::savePosFile(const std::string &filename, const vpColVector &q)
1193{
1194
1195 FILE *fd;
1196 fd = fopen(filename.c_str(), "w");
1197 if (fd == nullptr)
1198 return false;
1199
1200 fprintf(fd, "#PANDA - Joint position file\n"
1201 "#\n"
1202 "# R: q1 q2 q3 q4 q5 q6 q7\n"
1203 "# with joint positions q1 to q7 expressed in degrees\n"
1204 "#\n");
1205
1206 // Save positions in mm and deg
1207 fprintf(fd, "R: %lf %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
1208 vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]), vpMath::deg(q[6]));
1209
1210 fclose(fd);
1211 return (true);
1212}
1213
1229
1237{
1238 if (m_franka_address.empty()) {
1239 throw(vpException(vpException::fatalError, "Cannot perform franka gripper homing without ip address"));
1240 }
1241 if (m_gripper == nullptr)
1242 m_gripper = new franka::Gripper(m_franka_address);
1243
1244 m_gripper->homing();
1245}
1246
1257{
1258 if (m_franka_address.empty()) {
1259 throw(vpException(vpException::fatalError, "Cannot open franka gripper without ip address"));
1260 }
1261 if (m_gripper == nullptr)
1262 m_gripper = new franka::Gripper(m_franka_address);
1263
1264 // Check for the maximum grasping width.
1265 franka::GripperState gripper_state = m_gripper->readOnce();
1266
1267 if (gripper_state.max_width < width) {
1268 std::cout << "Finger width request is too large for the current fingers on the gripper."
1269 << "Maximum possible width is " << gripper_state.max_width << std::endl;
1270 return EXIT_FAILURE;
1271 }
1272
1273 m_gripper->move(width, 0.1);
1274 return EXIT_SUCCESS;
1275}
1276
1286
1296{
1297 if (m_franka_address.empty()) {
1298 throw(vpException(vpException::fatalError, "Cannot open franka gripper without ip address"));
1299 }
1300 if (m_gripper == nullptr)
1301 m_gripper = new franka::Gripper(m_franka_address);
1302
1303 // Check for the maximum grasping width.
1304 franka::GripperState gripper_state = m_gripper->readOnce();
1305
1306 m_gripper->move(gripper_state.max_width, 0.1);
1307 return EXIT_SUCCESS;
1308}
1309
1317{
1318 if (m_franka_address.empty()) {
1319 throw(vpException(vpException::fatalError, "Cannot release franka gripper without ip address"));
1320 }
1321 if (m_gripper == nullptr)
1322 m_gripper = new franka::Gripper(m_franka_address);
1323
1324 m_gripper->stop();
1325}
1326
1341int vpRobotFranka::gripperGrasp(double grasping_width, double force)
1342{
1343 return gripperGrasp(grasping_width, 0.1, force);
1344}
1345
1361int vpRobotFranka::gripperGrasp(double grasping_width, double speed, double force)
1362{
1363 if (m_gripper == nullptr)
1364 m_gripper = new franka::Gripper(m_franka_address);
1365
1366 // Check for the maximum grasping width.
1367 franka::GripperState gripper_state = m_gripper->readOnce();
1368 std::cout << "Gripper max witdh: " << gripper_state.max_width << std::endl;
1369 if (gripper_state.max_width < grasping_width) {
1370 std::cout << "Object is too large for the current fingers on the gripper."
1371 << "Maximum possible width is " << gripper_state.max_width << std::endl;
1372 return EXIT_FAILURE;
1373 }
1374
1375 // Grasp the object.
1376 if (!m_gripper->grasp(grasping_width, speed, force)) {
1377 std::cout << "Failed to grasp object." << std::endl;
1378 return EXIT_FAILURE;
1379 }
1380
1381 return EXIT_SUCCESS;
1382}
1383END_VISP_NAMESPACE
1384#elif !defined(VISP_BUILD_SHARED_LIBS)
1385// Work around to avoid warning: libvisp_robot.a(vpRobotFranka.cpp.o) has
1386// no symbols
1387void dummy_vpRobotFranka() { }
1388#endif
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition vpArray2D.h:448
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:435
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
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)
static bool checkDirectory(const std::string &dirname)
static void makeDirectory(const std::string &dirname)
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:175
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
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)
int nDof
number of degrees of freedom
Definition vpRobot.h:101
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:152
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition vpRobot.cpp:162
vpControlFrameType
Definition vpRobot.h:74
@ REFERENCE_FRAME
Definition vpRobot.h:75
@ JOINT_STATE
Definition vpRobot.h:79
@ TOOL_FRAME
Definition vpRobot.h:83
@ MIXT_FRAME
Definition vpRobot.h:85
@ END_EFFECTOR_FRAME
Definition vpRobot.h:80
vpRobotStateType
Definition vpRobot.h:62
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition vpRobot.h:65
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition vpRobot.h:63
@ STATE_FORCE_TORQUE_CONTROL
Initialize the force/torque controller.
Definition vpRobot.h:67
double getMaxRotationVelocity(void) const
Definition vpRobot.cpp:272
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition vpRobot.cpp:200
virtual void init()=0
double getMaxTranslationVelocity(void) const
Definition vpRobot.cpp:250
vpRobot(void)
Definition vpRobot.cpp:49