Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
testFrankaGetPose.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2024 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 * Test Franka robot behavior
32 */
33
39
40#include <iostream>
41
42#include <visp3/core/vpConfig.h>
43
44#if defined(VISP_HAVE_FRANKA)
45
46#include <visp3/robot/vpRobotFranka.h>
47
48int main(int argc, char **argv)
49{
50#ifdef ENABLE_VISP_NAMESPACE
51 using namespace VISP_NAMESPACE_NAME;
52#endif
53 std::string robot_ip = "192.168.1.1";
54
55 for (int i = 1; i < argc; i++) {
56 if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
57 robot_ip = std::string(argv[i + 1]);
58 }
59 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
60 std::cout << argv[0] << " [--ip 192.168.1.1] [--help] [-h]"
61 << "\n";
62 return EXIT_SUCCESS;
63 }
64 }
65
66 try {
67 std::cout << "-- Start test 1/4" << std::endl;
68 vpRobotFranka robot;
69 robot.connect(robot_ip);
70
72
73 for (unsigned i = 0; i < 10; i++) {
74 robot.getPosition(vpRobot::JOINT_STATE, q);
75 std::cout << "Joint position: " << q.t() << std::endl;
76 vpTime::wait(10);
77 }
78
79 vpPoseVector fPe;
80 robot.getPosition(vpRobot::END_EFFECTOR_FRAME, fPe);
81 std::cout << "fMe pose vector: " << fPe.t() << std::endl;
82 std::cout << "fMe pose matrix: \n" << vpHomogeneousMatrix(fPe) << std::endl;
83 }
84 catch (const vpException &e) {
85 std::cout << "ViSP exception: " << e.what() << std::endl;
86 return EXIT_FAILURE;
87 }
88 catch (const franka::NetworkException &e) {
89 std::cout << "Franka network exception: " << e.what() << std::endl;
90 std::cout << "Check if you are connected to the Franka robot"
91 << " or if you specified the right IP using --ip command"
92 << " line option set by default to 192.168.1.1. " << std::endl;
93 return EXIT_FAILURE;
94 }
95 catch (const std::exception &e) {
96 std::cout << "Franka exception: " << e.what() << std::endl;
97 return EXIT_FAILURE;
98 }
99
100 try {
101 std::cout << "-- Start test 2/4" << std::endl;
102 vpRobotFranka robot(robot_ip);
103
104 franka::Robot *handler = robot.getHandler();
105
106 // Get end-effector cartesian position
107 std::array<double, 16> pose = handler->readOnce().O_T_EE;
109 for (unsigned int i = 0; i < 4; i++) {
110 for (unsigned int j = 0; j < 4; j++) {
111 oMee[i][j] = pose[j * 4 + i];
112 }
113 }
114 std::cout << "oMee: \n" << oMee << std::endl;
115
116 // Get flange to end-effector frame transformation
117 pose = handler->readOnce().F_T_EE;
119 for (unsigned int i = 0; i < 4; i++) {
120 for (unsigned int j = 0; j < 4; j++) {
121 fMee[i][j] = pose[j * 4 + i];
122 }
123 }
124 std::cout << "fMee: \n" << fMee << std::endl;
125
126 // Get end-effector to K frame transformation
127 pose = handler->readOnce().EE_T_K;
129 for (unsigned int i = 0; i < 4; i++) {
130 for (unsigned int j = 0; j < 4; j++) {
131 eeMk[i][j] = pose[j * 4 + i];
132 }
133 }
134 std::cout << "eeMk: \n" << eeMk << std::endl;
135 }
136 catch (const vpException &e) {
137 std::cout << "ViSP exception: " << e.what() << std::endl;
138 return EXIT_FAILURE;
139 }
140 catch (const franka::NetworkException &e) {
141 std::cout << "Franka network exception: " << e.what() << std::endl;
142 std::cout << "Check if you are connected to the Franka robot"
143 << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
144 << std::endl;
145 return EXIT_FAILURE;
146 }
147 catch (const std::exception &e) {
148 std::cout << "Franka exception: " << e.what() << std::endl;
149 return EXIT_FAILURE;
150 }
151
152 try {
153 std::cout << "-- Start test 3/4" << std::endl;
154 vpRobotFranka robot;
155 robot.connect(robot_ip);
156
157 vpMatrix mass;
158 robot.getMass(mass);
159 std::cout << "Mass matrix:\n" << mass << std::endl;
160
161 vpColVector gravity;
162 robot.getGravity(gravity);
163 std::cout << "Gravity vector: " << gravity.t() << std::endl;
164
165 vpColVector coriolis;
166 robot.getCoriolis(coriolis);
167 std::cout << "Coriolis vector: " << coriolis.t() << std::endl;
168 }
169 catch (const vpException &e) {
170 std::cout << "ViSP exception: " << e.what() << std::endl;
171 return EXIT_FAILURE;
172 }
173 catch (const franka::NetworkException &e) {
174 std::cout << "Franka network exception: " << e.what() << std::endl;
175 std::cout << "Check if you are connected to the Franka robot"
176 << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
177 << std::endl;
178 return EXIT_FAILURE;
179 }
180 catch (const std::exception &e) {
181 std::cout << "Franka exception: " << e.what() << std::endl;
182 return EXIT_FAILURE;
183 }
184
185 try {
186 std::cout << "-- Start test 4/4" << std::endl;
187 vpRobotFranka robot;
188 robot.connect(robot_ip);
189
190 vpColVector q;
191 robot.getPosition(vpRobot::JOINT_STATE, q);
192 std::cout << "Joint position: " << q.t() << std::endl;
193
194 vpMatrix fJe;
195 robot.get_fJe(fJe);
196 std::cout << "Jacobian fJe:\n" << fJe << std::endl;
197
198 robot.get_fJe(q, fJe);
199 std::cout << "Jacobian fJe:\n" << fJe << std::endl;
200
201 vpMatrix eJe;
202 robot.get_eJe(eJe);
203 std::cout << "Jacobian eJe:\n" << eJe << std::endl;
204
205 robot.get_eJe(q, eJe);
206 std::cout << "Jacobian eJe:\n" << eJe << std::endl;
207 }
208 catch (const vpException &e) {
209 std::cout << "ViSP exception: " << e.what() << std::endl;
210 return EXIT_FAILURE;
211 }
212 catch (const franka::NetworkException &e) {
213 std::cout << "Franka network exception: " << e.what() << std::endl;
214 std::cout << "Check if you are connected to the Franka robot"
215 << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
216 << std::endl;
217 return EXIT_FAILURE;
218 }
219 catch (const std::exception &e) {
220 std::cout << "Franka exception: " << e.what() << std::endl;
221 return EXIT_FAILURE;
222 }
223
224 std::cout << "The end" << std::endl;
225 return EXIT_SUCCESS;
226}
227
228#else
229int main() { std::cout << "ViSP is not build with libfranka..." << std::endl; }
230#endif
Implementation of column vector and the associated operations.
vpRowVector t() const
error that can be emitted by ViSP classes.
Definition vpException.h:60
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.
vpRowVector t() const
void connect(const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
@ JOINT_STATE
Definition vpRobot.h:79
@ END_EFFECTOR_FRAME
Definition vpRobot.h:80
VISP_EXPORT int wait(double t0, double t)