tutorial-franka-coppeliasim-cartesian-impedance-control.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2021 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  *****************************************************************************/
32 
34 
35 #include <iostream>
36 
37 #include <visp3/gui/vpPlot.h>
39 
40 vpMatrix
41 Ta( const vpHomogeneousMatrix &edMe )
42 {
43  vpMatrix Lx( 6, 6 ), Lw( 3, 3 ), skew_u( 3, 3 );
44 
45  Lx.eye();
46  vpThetaUVector tu( edMe );
47 
48  vpColVector u;
49  double theta;
50 
51  tu.extract( theta, u );
52  skew_u = vpColVector::skew( u );
53  Lw.eye();
54  if ( theta != 0.0 )
55  {
56  Lw -= 0.5 * theta * skew_u;
57  Lw += ( 1 - ( ( vpMath::sinc( theta ) ) / ( vpMath::sqr( vpMath::sinc( theta * 0.5 ) ) ) ) ) * skew_u * skew_u;
58  }
59 
60  Lx.insert( Lw, 3, 3 );
61 
62  return Lx;
63 }
64 
65 int
66 main( int argc, char **argv )
67 {
68  bool opt_coppeliasim_sync_mode = false;
69  bool opt_verbose = false;
70  bool opt_save_data = false;
71 
72  for ( int i = 1; i < argc; i++ )
73  {
74  if ( std::string( argv[i] ) == "--enable-coppeliasim-sync-mode" )
75  {
76  opt_coppeliasim_sync_mode = true;
77  }
78  else if ( std::string( argv[i] ) == "--verbose" || std::string( argv[i] ) == "-v" )
79  {
80  opt_verbose = true;
81  }
82  else if ( std::string( argv[i] ) == "--save" )
83  {
84  opt_save_data = true;
85  }
86  else if ( std::string( argv[i] ) == "--help" || std::string( argv[i] ) == "-h" )
87  {
88  std::cout << argv[0] << "[--enable-coppeliasim-sync-mode]"
89  << " [--save]"
90  << " [--verbose] [-v] "
91  << " [--help] [-h]" << std::endl;
92  return EXIT_SUCCESS;
93  }
94  }
95 
97 
98  try
99  {
100  //------------------------------------------------------------------------//
101  //------------------------------------------------------------------------//
102  // ROS node
103  ros::init( argc, argv, "visp_ros" );
104  ros::NodeHandlePtr n = boost::make_shared< ros::NodeHandle >();
105  ros::Rate loop_rate( 1000 );
106  ros::spinOnce();
107 
108  robot.setVerbose( opt_verbose );
109  robot.connect();
110 
111  std::cout << "Coppeliasim sync mode enabled: " << ( opt_coppeliasim_sync_mode ? "yes" : "no" ) << std::endl;
112  robot.coppeliasimStopSimulation(); // Allows to reset simulation, moving the robot to initial position
113  robot.setCoppeliasimSyncMode( false );
115 
116  // Move to a secure initial position
117  vpColVector q_init( { 0, vpMath::rad( -45 ), 0, vpMath::rad( -135 ), 0, vpMath::rad( 90 ), vpMath::rad( 45 ) } );
118 
119  robot.setRobotState( vpRobot::STATE_POSITION_CONTROL );
120  robot.setPosition( vpRobot::JOINT_STATE, q_init );
121  vpTime::wait( 500 );
122 
123  vpPlot *plotter = nullptr;
124 
125  plotter = new vpPlot( 4, 800, 800, 10, 10, "Real time curves plotter" );
126  plotter->setTitle( 0, "Joint positions [rad]" );
127  plotter->initGraph( 0, 7 );
128  plotter->setLegend( 0, 0, "q1" );
129  plotter->setLegend( 0, 1, "q2" );
130  plotter->setLegend( 0, 2, "q3" );
131  plotter->setLegend( 0, 3, "q4" );
132  plotter->setLegend( 0, 4, "q5" );
133  plotter->setLegend( 0, 5, "q6" );
134  plotter->setLegend( 0, 6, "q7" );
135 
136  plotter->setTitle( 1, "Joint torques measure [Nm]" );
137  plotter->initGraph( 1, 7 );
138  plotter->setLegend( 1, 0, "Tau1" );
139  plotter->setLegend( 1, 1, "Tau2" );
140  plotter->setLegend( 1, 2, "Tau3" );
141  plotter->setLegend( 1, 3, "Tau4" );
142  plotter->setLegend( 1, 4, "Tau5" );
143  plotter->setLegend( 1, 5, "Tau6" );
144  plotter->setLegend( 1, 6, "Tau7" );
145 
146  plotter->setTitle( 2, "Cartesian EE pose error [m] - [rad]" );
147  plotter->initGraph( 2, 6 );
148  plotter->setLegend( 2, 0, "e_x" );
149  plotter->setLegend( 2, 1, "e_y" );
150  plotter->setLegend( 2, 2, "e_z" );
151  plotter->setLegend( 2, 3, "e_tu_x" );
152  plotter->setLegend( 2, 4, "e_tu_y" );
153  plotter->setLegend( 2, 5, "e_tu_z" );
154 
155  plotter->setTitle( 3, "Pose error norm [m] - [rad]" );
156  plotter->initGraph( 3, 2 );
157  plotter->setLegend( 3, 0, "||e_p||" );
158  plotter->setLegend( 3, 1, "||e_o||" );
159 
160  vpColVector q( 7, 0 ), dq( 7, 0 ), tau_d( 7, 0 ), C( 7, 0 ), F( 7, 0 ), tau_d0( 7, 0 ), tau_cmd( 7, 0 ),
161  x_e( 6, 0 ), dx_e( 6, 0 ), dx_ed( 6, 0 ), ddx_ed( 6, 0 );
162  vpMatrix fJe( 6, 7 ), Ja( 6, 7 ), dJa( 6, 7 ), Ja_old( 6, 7 ), B( 7, 7 ), I7( 7, 7 ), Ja_pinv_B_t( 6, 7 );
163  vpColVector pose_err_norm( 2, 0 ), tau( 7, 0 );
164 
165  std::cout << "Reading current joint position" << std::endl;
166  robot.getPosition( vpRobot::JOINT_STATE, q );
167  std::cout << "Initial joint position: " << q.t() << std::endl;
168 
169  robot.setRobotState( vpRobot::STATE_FORCE_TORQUE_CONTROL );
170  robot.setCoppeliasimSyncMode( opt_coppeliasim_sync_mode );
171 
172  vpHomogeneousMatrix fMed, fMed0;
173  fMed0 = robot.get_fMe();
174  fMed = fMed0;
175 
176  bool final_quit = false;
177  bool first_time = false;
178  bool start_trajectory = false;
179 
180  vpMatrix K( 6, 6 ), D( 6, 6 ), edVf( 6, 6 );
181 
182  double wp = 50;
183  double wo = 20;
184  K.diag( { wp * wp, wp * wp, wp * wp, wo * wo, wo * wo, wo * wo } );
185  D.diag( { 2 * wp, 2 * wp, 2 * wp, 2 * wo, 2 * wo, 2 * wo } );
186  I7.eye();
187 
188  double mu = 4;
189  double dt = 0;
190 
191  double time_start_trajectory, time_prev, time_cur;
192  double delay_before_trajectory = 0.5; // Start sinusoidal joint trajectory after this delay in [s]
193 
194  // Control loop
195  while ( !final_quit )
196  {
197  time_cur = robot.getCoppeliasimSimulationTime();
198 
199  robot.getPosition( vpRobot::JOINT_STATE, q );
200  robot.getVelocity( vpRobot::JOINT_STATE, dq );
201  robot.getMass( B );
202  robot.getCoriolis( C );
203  robot.getFriction( F );
204  robot.get_fJe( fJe );
205  robot.getForceTorque( vpRobot::JOINT_STATE, tau );
206 
207  if ( time_cur < delay_before_trajectory )
208  {
209  time_start_trajectory = time_cur; // To ensure exp() = 1
210  first_time = true;
211  }
212  else if ( !start_trajectory ) // After the delay we start joint trajectory
213  {
214  time_start_trajectory = time_cur;
215  start_trajectory = true;
216  }
217 
218  // Compute Cartesian trajectories
219  // clang-format off
220  fMed[1][3] = fMed0[1][3] + ( start_trajectory ? ( 0.1 * sin( 2 * M_PI * 0.3 * ( time_cur - time_start_trajectory ) ) ) : 0 );
221  fMed[2][3] = fMed0[2][3] - ( start_trajectory ? ( 0.05 * sin( 2 * M_PI * 0.6 * ( time_cur - time_start_trajectory ) ) ) : 0) ;
222 
223  dx_ed[1] = ( start_trajectory ? (2 * M_PI * 0.3 * 0.1 * cos( 2 * M_PI * 0.3 * ( time_cur - time_start_trajectory ) ) ) : 0) ;
224  dx_ed[2] = ( start_trajectory ? (-2 * M_PI * 0.6 * 0.05 * cos( 2 * M_PI * 0.6 * ( time_cur - time_start_trajectory ) ) ) : 0) ;
225 
226  ddx_ed[1] = ( start_trajectory ? (-2 * M_PI * 0.3 * 2 * M_PI * 0.3 * 0.1 * sin( 2 * M_PI * 0.3 * ( time_cur - time_start_trajectory ) ) ) : 0) ;
227  ddx_ed[2] = ( start_trajectory ? (2 * M_PI * 0.6 * 2 * M_PI * 0.6 * 0.05 * sin( 2 * M_PI * 0.6 * ( time_cur - time_start_trajectory ) ) ) : 0) ;
228  // clang-format on
229 
230  edVf.insert( fMed.getRotationMatrix().t(), 0, 0 );
231  edVf.insert( fMed.getRotationMatrix().t(), 3, 3 );
232 
233  x_e = (vpColVector)vpPoseVector( fMed.inverse() * robot.get_fMe() ); // edMe
234  Ja = Ta( fMed.inverse() * robot.get_fMe() ) * edVf * fJe;
235 
236  dx_e = Ta( fMed.inverse() * robot.get_fMe() ) * edVf * ( dx_ed - fJe * dq );
237 
238  dt = time_cur - time_prev;
239 
240  if ( dt != 0 )
241  {
242  dJa = ( Ja - Ja_old ) / dt;
243  }
244  else
245  {
246  dJa = 0;
247  }
248  Ja_old = Ja;
249 
250  Ja_pinv_B_t = ( Ja * B.inverseByCholesky() * Ja.t() ).inverseByCholesky() * Ja * B.inverseByCholesky();
251 
252  // Compute the control law
253  tau_d = B * Ja.pseudoInverse() * ( -K * ( x_e ) + D * (dx_e)-dJa * dq + ddx_ed ) + C + F -
254  ( I7 - Ja.t() * Ja_pinv_B_t ) * B * dq * 100;
255 
256  if ( first_time )
257  {
258  tau_d0 = tau_d;
259  }
260 
261  tau_cmd = tau_d - tau_d0 * std::exp( -mu * ( time_cur - time_start_trajectory ) );
262 
263  robot.setForceTorque( vpRobot::JOINT_STATE, tau_cmd );
264 
265  plotter->plot( 0, time_cur, q );
266  plotter->plot( 1, time_cur, tau );
267  plotter->plot( 2, time_cur, x_e );
268  pose_err_norm[0] = sqrt( x_e.extract( 0, 3 ).sumSquare() );
269  pose_err_norm[1] = sqrt( x_e.extract( 3, 3 ).sumSquare() );
270  plotter->plot( 3, time_cur, pose_err_norm );
271 
272  vpMouseButton::vpMouseButtonType button;
273  if ( vpDisplay::getClick( plotter->I, button, false ) )
274  {
275  if ( button == vpMouseButton::button3 )
276  {
277  final_quit = true;
278  tau_cmd = 0;
279  std::cout << "Stop the robot " << std::endl;
280  robot.setRobotState( vpRobot::STATE_STOP );
281  }
282  }
283 
284  if ( opt_verbose )
285  {
286  std::cout << "dt: " << dt << std::endl;
287  }
288 
289  time_prev = time_cur;
290  robot.wait( time_cur, 0.001 ); // Sync loop at 1000 Hz (1 ms)
291  } // end while
292 
293  if ( opt_save_data )
294  {
295  plotter->saveData( 0, "sim-cart-joint-position.txt", "# " );
296  plotter->saveData( 1, "sim-cart-joint-torques.txt", "# " );
297  plotter->saveData( 2, "sim-cart-pose-error.txt", "# " );
298  plotter->saveData( 3, "sim-cart-pose-error-norm.txt", "# " );
299  }
300 
301  if ( plotter != nullptr )
302  {
303  delete plotter;
304  plotter = nullptr;
305  }
307  }
308  catch ( const vpException &e )
309  {
310  std::cout << "ViSP exception: " << e.what() << std::endl;
311  std::cout << "Stop the robot " << std::endl;
312  robot.setRobotState( vpRobot::STATE_STOP );
313  return EXIT_FAILURE;
314  }
315 
316  return 0;
317 }
vpRobotFrankaSim::getForceTorque
virtual void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
Definition: vpRobotFrankaSim.cpp:825
boost::shared_ptr< NodeHandle >
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
vpRobotFrankaSim::getPosition
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
Definition: vpRobotFrankaSim.cpp:417
vpRobotFrankaSim::get_fJe
void get_fJe(vpMatrix &fJe)
Definition: vpRobotFrankaSim.cpp:264
vpROSRobotFrankaCoppeliasim
Definition: vpROSRobotFrankaCoppeliasim.h:87
ros::spinOnce
ROSCPP_DECL void spinOnce()
Ta
vpMatrix Ta(const vpHomogeneousMatrix &edMe)
Definition: tutorial-franka-coppeliasim-cartesian-impedance-control.cpp:41
vpRobotFrankaSim::get_fMe
vpHomogeneousMatrix get_fMe(const vpColVector &q)
Definition: vpRobotFrankaSim.cpp:978
vpROSRobotFrankaCoppeliasim::setRobotState
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Definition: vpROSRobotFrankaCoppeliasim.cpp:764
vpROSRobotFrankaCoppeliasim::wait
void wait(double timestamp_second, double duration_second)
Definition: vpROSRobotFrankaCoppeliasim.cpp:976
vpRobotFrankaSim::setForceTorque
virtual void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &force)
Definition: vpRobotFrankaSim.cpp:875
vpRobotFrankaSim::setVerbose
void setVerbose(bool verbose)
Definition: vpRobotFrankaSim.h:111
vpROSRobotFrankaCoppeliasim.h
vpROSRobotFrankaCoppeliasim::coppeliasimStopSimulation
void coppeliasimStopSimulation(double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:268
vpROSRobotFrankaCoppeliasim::setPosition
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Definition: vpROSRobotFrankaCoppeliasim.cpp:947
vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationTime
double getCoppeliasimSimulationTime()
Definition: vpROSRobotFrankaCoppeliasim.cpp:342
vpRobotFrankaSim::getMass
void getMass(vpMatrix &mass)
Definition: vpRobotFrankaSim.cpp:1019
vpROSRobotFrankaCoppeliasim::coppeliasimStartSimulation
void coppeliasimStartSimulation(double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:248
vpRobotFrankaSim::getCoriolis
void getCoriolis(vpColVector &coriolis)
Definition: vpRobotFrankaSim.cpp:1042
main
int main(int argc, char **argv)
Definition: tutorial-franka-coppeliasim-cartesian-impedance-control.cpp:66
vpROSRobotFrankaCoppeliasim::setCoppeliasimSyncMode
void setCoppeliasimSyncMode(bool enable, double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:209
vpRobotFrankaSim::getFriction
void getFriction(vpColVector &friction)
Definition: vpRobotFrankaSim.cpp:144
ros::Rate
vpROSRobotFrankaCoppeliasim::connect
void connect(const std::string &robot_ID="")
Definition: vpROSRobotFrankaCoppeliasim.cpp:132
vpRobotFrankaSim::getVelocity
virtual void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position)
Definition: vpRobotFrankaSim.cpp:627


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33