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