48 #include <visp3/core/vpConfig.h> 50 #if defined(VISP_HAVE_FRANKA) 52 #include <visp3/robot/vpRobotFranka.h> 55 int main(
int argc,
char **argv)
57 std::string robot_ip =
"192.168.1.1";
59 for (
int i = 1; i < argc; i++) {
60 if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
61 robot_ip = std::string(argv[i + 1]);
63 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
64 std::cout << argv[0] <<
" [--ip 192.168.1.1] [--help] [-h]" 71 std::cout <<
"-- Start test 1/4" << std::endl;
77 for (
unsigned i = 0; i < 10; i++) {
79 std::cout <<
"Joint position: " << q.
t() << std::endl;
85 std::cout <<
"fMe pose vector: " << fPe.
t() << std::endl;
89 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
92 catch(
const franka::NetworkException &e) {
93 std::cout <<
"Franka network exception: " << e.what() << std::endl;
94 std::cout <<
"Check if you are connected to the Franka robot" 95 <<
" or if you specified the right IP using --ip command" 96 <<
" line option set by default to 192.168.1.1. " << std::endl;
99 catch(
const std::exception &e) {
100 std::cout <<
"Franka exception: " << e.what() << std::endl;
105 std::cout <<
"-- Start test 2/4" << std::endl;
111 std::array<double, 16> pose = handler->readOnce().O_T_EE;
113 for (
unsigned int i=0; i< 4; i++) {
114 for (
unsigned int j=0; j< 4; j++) {
115 oMee[i][j] = pose[j*4 + i];
118 std::cout <<
"oMee: \n" << oMee << std::endl;
121 pose = handler->readOnce().F_T_EE;
123 for (
unsigned int i=0; i< 4; i++) {
124 for (
unsigned int j=0; j< 4; j++) {
125 fMee[i][j] = pose[j*4 + i];
128 std::cout <<
"fMee: \n" << fMee << std::endl;
131 pose = handler->readOnce().EE_T_K;
133 for (
unsigned int i=0; i< 4; i++) {
134 for (
unsigned int j=0; j< 4; j++) {
135 eeMk[i][j] = pose[j*4 + i];
138 std::cout <<
"eeMk: \n" << eeMk << std::endl;
141 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
144 catch(
const franka::NetworkException &e) {
145 std::cout <<
"Franka network exception: " << e.what() << std::endl;
146 std::cout <<
"Check if you are connected to the Franka robot" 147 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " << std::endl;
150 catch(
const std::exception &e) {
151 std::cout <<
"Franka exception: " << e.what() << std::endl;
156 std::cout <<
"-- Start test 3/4" << std::endl;
162 std::cout <<
"Mass matrix:\n" << mass << std::endl;
166 std::cout <<
"Gravity vector: " << gravity.
t() << std::endl;
170 std::cout <<
"Coriolis vector: " << coriolis.
t() << std::endl;
173 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
176 catch(
const franka::NetworkException &e) {
177 std::cout <<
"Franka network exception: " << e.what() << std::endl;
178 std::cout <<
"Check if you are connected to the Franka robot" 179 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " << std::endl;
182 catch(
const std::exception &e) {
183 std::cout <<
"Franka exception: " << e.what() << std::endl;
188 std::cout <<
"-- Start test 4/4" << std::endl;
194 std::cout <<
"Joint position: " << q.
t() << std::endl;
198 std::cout <<
"Jacobian fJe:\n" << fJe << std::endl;
201 std::cout <<
"Jacobian fJe:\n" << fJe << std::endl;
205 std::cout <<
"Jacobian eJe:\n" << eJe << std::endl;
208 std::cout <<
"Jacobian eJe:\n" << eJe << std::endl;
211 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
214 catch(
const franka::NetworkException &e) {
215 std::cout <<
"Franka network exception: " << e.what() << std::endl;
216 std::cout <<
"Check if you are connected to the Franka robot" 217 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " << std::endl;
220 catch(
const std::exception &e) {
221 std::cout <<
"Franka exception: " << e.what() << std::endl;
225 std::cout <<
"The end" << std::endl;
232 std::cout <<
"ViSP is not build with libfranka..." << std::endl;
Implementation of a matrix and operations on matrices.
VISP_EXPORT int wait(double t0, double t)
void getCoriolis(vpColVector &coriolis)
Implementation of an homogeneous matrix and operations on such kind of matrices.
void getGravity(vpColVector &gravity)
error that can be emited by ViSP classes.
franka::Robot * getHandler()
void getMass(vpMatrix &mass)
void get_eJe(vpMatrix &eJe)
const char * what() const
void get_fJe(vpMatrix &fJe)
Implementation of column vector and the associated operations.
Implementation of a pose vector and operations on poses.
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void connect(const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)