37 #include <visp3/gui/vpPlot.h>
38 #include <visp3/robot/vpRobotFranka.h>
40 #if defined( VISP_HAVE_FRANKA ) && defined( VISP_HAVE_DISPLAY )
43 main(
int argc,
char **argv )
45 std::string opt_robot_ip =
"192.168.1.1";
46 bool opt_verbose =
false;
47 bool opt_save_data =
false;
49 for (
int i = 1; i < argc; i++ )
51 if ( std::string( argv[i] ) ==
"--ip" && i + 1 < argc )
53 opt_robot_ip = std::string( argv[i + 1] );
55 else if ( std::string( argv[i] ) ==
"--verbose" || std::string( argv[i] ) ==
"-v" )
59 else if ( std::string( argv[i] ) ==
"--save" )
63 else if ( std::string( argv[i] ) ==
"--help" || std::string( argv[i] ) ==
"-h" )
65 std::cout << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">]"
67 <<
" [--verbose] [-v]"
68 <<
" [--help] [-h] " << std::endl;
76 std::cout <<
"ip: " << opt_robot_ip << std::endl;
77 robot.connect( opt_robot_ip );
79 vpColVector q_init( { 0, vpMath::rad( -45 ), 0, vpMath::rad( -135 ), 0, vpMath::rad( 90 ), vpMath::rad( 45 ) } );
81 robot.setRobotState( vpRobot::STATE_POSITION_CONTROL );
82 robot.setPosition( vpRobot::JOINT_STATE, q_init );
85 vpPlot *plotter =
nullptr;
87 plotter =
new vpPlot( 4, 800, 800, 10, 10,
"Real time curves plotter" );
88 plotter->setTitle( 0,
"Joint position [rad]" );
89 plotter->initGraph( 0, 7 );
90 plotter->setLegend( 0, 0,
"q1" );
91 plotter->setLegend( 0, 1,
"q2" );
92 plotter->setLegend( 0, 2,
"q3" );
93 plotter->setLegend( 0, 3,
"q4" );
94 plotter->setLegend( 0, 4,
"q5" );
95 plotter->setLegend( 0, 5,
"q6" );
96 plotter->setLegend( 0, 6,
"q7" );
98 plotter->setTitle( 1,
"Joint position error [rad]" );
99 plotter->initGraph( 1, 7 );
100 plotter->setLegend( 1, 0,
"e_q1" );
101 plotter->setLegend( 1, 1,
"e_q2" );
102 plotter->setLegend( 1, 2,
"e_q3" );
103 plotter->setLegend( 1, 3,
"e_q4" );
104 plotter->setLegend( 1, 4,
"e_q5" );
105 plotter->setLegend( 1, 5,
"e_q6" );
106 plotter->setLegend( 1, 6,
"e_q7" );
108 plotter->setTitle( 2,
"Joint torque measure [Nm]" );
109 plotter->initGraph( 2, 7 );
110 plotter->setLegend( 2, 0,
"Tau1" );
111 plotter->setLegend( 2, 1,
"Tau2" );
112 plotter->setLegend( 2, 2,
"Tau3" );
113 plotter->setLegend( 2, 3,
"Tau4" );
114 plotter->setLegend( 2, 4,
"Tau5" );
115 plotter->setLegend( 2, 5,
"Tau6" );
116 plotter->setLegend( 2, 6,
"Tau7" );
118 plotter->setTitle( 3,
"Joint error norm [deg]" );
119 plotter->initGraph( 3, 1 );
120 plotter->setLegend( 3, 0,
"||qd - d||" );
123 vpColVector q( 7, 0 ), qd( 7, 0 ), dq( 7, 0 ), dqd( 7, 0 ), ddqd( 7, 0 ), tau_d( 7, 0 ), C( 7, 0 ), q0( 7, 0 ),
124 F( 7, 0 ), tau_d0( 7, 0 ), tau_cmd( 7, 0 ), tau( 7, 0 );
127 std::cout <<
"Reading current joint position" << std::endl;
128 robot.getPosition( vpRobot::JOINT_STATE, q0 );
129 std::cout <<
"Initial joint position: " << q0.t() << std::endl;
131 robot.setRobotState( vpRobot::STATE_FORCE_TORQUE_CONTROL );
134 bool final_quit =
false;
135 bool first_time =
true;
136 bool start_trajectory =
false;
138 vpMatrix K( 7, 7 ), D( 7, 7 ), I( 7, 7 );
139 K.diag( { 400.0, 400.0, 400.0, 400.0, 400.0, 400.0, 900.0 } );
140 D.diag( { 20.0, 45.0, 45.0, 45.0, 45.0, 45.0, 60.0 } );
141 I.diag( { 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 60.0 } );
143 vpColVector integral( 7, 0 ), G( 7, 0 ), tau_J( 7, 0 ), sig( 7, 0 );
148 double time_ref = vpTime::measureTimeSecond();
149 double time_start_trajectory, time_prev, time_cur;
150 double delay_before_trajectory = 0.5;
152 while ( !final_quit )
154 time_cur = vpTime::measureTimeSecond();
156 robot.getPosition( vpRobot::JOINT_STATE, q );
157 robot.getVelocity( vpRobot::JOINT_STATE, dq );
158 robot.getForceTorque( vpRobot::JOINT_STATE, tau );
160 robot.getCoriolis( C );
163 if ( time_cur - time_ref < delay_before_trajectory )
165 time_start_trajectory = time_cur;
168 else if ( !start_trajectory )
170 time_start_trajectory = time_cur;
171 start_trajectory =
true;
176 qd[0] = q0[0] + ( start_trajectory ? std::sin( 2 * M_PI * 0.1 * ( time_cur - time_start_trajectory ) ) : 0 );
177 dqd[0] = ( start_trajectory ? 2 * M_PI * 0.1 * std::cos( 2 * M_PI * 0.1 * ( time_cur - time_start_trajectory ) ) : 0 );
178 ddqd[0] = ( start_trajectory ? - std::pow( 2 * 0.1 * M_PI, 2 ) * std::sin( 2 * M_PI * 0.1 * ( time_cur - time_start_trajectory ) ) : 0 );
180 qd[2] = q0[2] + ( start_trajectory ? ( M_PI / 16 ) * std::sin( 2 * M_PI * 0.2 * ( time_cur - time_start_trajectory ) ) : 0 );
181 dqd[2] = ( start_trajectory ? M_PI * ( M_PI / 8 ) * 0.2 * std::cos( 2 * M_PI * 0.2 * ( time_cur - time_start_trajectory ) ) : 0 );
182 ddqd[2] = ( start_trajectory ? -M_PI * M_PI * 0.2 * ( M_PI / 4 ) * std::sin( 2 * M_PI * 0.2 * ( time_cur - time_start_trajectory ) ) : 0 );
184 qd[3] = q0[3] + ( start_trajectory ? 0.25 * std::sin( 2 * M_PI * 0.05 * ( time_cur - time_start_trajectory ) ) : 0 );
185 dqd[3] = ( start_trajectory ? 2 * M_PI * 0.05 * 0.25 * std::cos( 2 * M_PI * 0.05 * ( time_cur - time_start_trajectory ) ) : 0 );
186 ddqd[3] = ( start_trajectory ? -0.25 * std::pow( 2 * 0.05 * M_PI, 2 ) * std::sin( 2 * M_PI * 0.05 * ( time_cur - time_start_trajectory ) ) : 0 );
193 dt = time_cur - time_prev;
194 if ( start_trajectory )
196 integral += ( qd - q ) * dt;
200 tau_d = B * ( K * ( qd - q ) + D * ( dqd - dq ) + I * ( integral ) + ddqd ) + C + F;
207 tau_cmd = tau_d - tau_d0 * std::exp( -mu * ( time_cur - time_start_trajectory ) );
210 robot.setForceTorque( vpRobot::JOINT_STATE, tau_cmd );
212 vpColVector norm( 1, vpMath::deg( std::sqrt( ( qd - q ).sumSquare() ) ) );
213 plotter->plot( 0, time_cur - time_ref, q );
214 plotter->plot( 1, time_cur - time_ref, qd - q );
215 plotter->plot( 2, time_cur - time_ref, tau );
216 plotter->plot( 3, time_cur - time_ref, norm );
218 vpMouseButton::vpMouseButtonType button;
219 if ( vpDisplay::getClick( plotter->I, button,
false ) )
221 if ( button == vpMouseButton::button3 )
225 std::cout <<
"Stop the robot " << std::endl;
226 robot.setRobotState( vpRobot::STATE_STOP );
232 std::cout <<
"dt: " << dt << std::endl;
235 time_prev = time_cur;
236 vpTime::wait( time_cur * 1000., 1. );
241 plotter->saveData( 0,
"real-joint-position.txt",
"# " );
242 plotter->saveData( 1,
"real-joint-position-error.txt",
"# " );
243 plotter->saveData( 2,
"real-joint-torque-measure.txt",
"# " );
244 plotter->saveData( 3,
"real-joint-error-norm.txt",
"# " );
246 if ( plotter !=
nullptr )
252 catch (
const vpException &e )
254 std::cout <<
"ViSP exception: " << e.what() << std::endl;
255 std::cout <<
"Stop the robot " << std::endl;
256 robot.setRobotState( vpRobot::STATE_STOP );
259 catch (
const franka::NetworkException &e )
261 std::cout <<
"Franka network exception: " << e.what() << std::endl;
262 std::cout <<
"Check if you are connected to the Franka robot"
263 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
267 catch (
const std::exception &e )
269 std::cout <<
"Franka exception: " << e.what() << std::endl;
279 #if !defined( VISP_HAVE_DISPLAY )
280 std::cout <<
"Install display capabilities: X11, OpenCV" << std::endl;
282 #if !defined( VISP_HAVE_FRANKA )
283 std::cout <<
"Install libfranka." << std::endl;