37 #include <visp3/gui/vpPlot.h>    41 Ta( 
const vpHomogeneousMatrix &edMe )
    43   vpMatrix Lx( 6, 6 ), Lw( 3, 3 ), skew_u( 3, 3 );
    46   vpThetaUVector tu( edMe );
    51   tu.extract( theta, u );
    52   skew_u = vpColVector::skew( u );
    56     Lw -= 0.5 * theta * skew_u;
    57     Lw += ( 1 - ( ( vpMath::sinc( theta ) ) / ( vpMath::sqr( vpMath::sinc( theta * 0.5 ) ) ) ) ) * skew_u * skew_u;
    60   Lx.insert( Lw, 3, 3 );
    66 main( 
int argc, 
char **argv )
    68   bool opt_coppeliasim_sync_mode = 
false;
    69   bool opt_verbose               = 
false;
    70   bool opt_save_data             = 
false;
    72   for ( 
int i = 1; i < argc; i++ )
    74     if ( std::string( argv[i] ) == 
"--enable-coppeliasim-sync-mode" )
    76       opt_coppeliasim_sync_mode = 
true;
    78     else if ( std::string( argv[i] ) == 
"--verbose" || std::string( argv[i] ) == 
"-v" )
    82     else if ( std::string( argv[i] ) == 
"--save" )
    86     else if ( std::string( argv[i] ) == 
"--help" || std::string( argv[i] ) == 
"-h" )
    88       std::cout << argv[0] << 
"[--enable-coppeliasim-sync-mode]"    90                 << 
" [--verbose] [-v] "    91                 << 
" [--help] [-h]" << std::endl;
   111     std::cout << 
"Coppeliasim sync mode enabled: " << ( opt_coppeliasim_sync_mode ? 
"yes" : 
"no" ) << std::endl;
   117     vpColVector q_init( { 0, vpMath::rad( -45 ), 0, vpMath::rad( -135 ), 0, vpMath::rad( 90 ), vpMath::rad( 45 ) } );
   123     vpPlot *plotter = 
nullptr;
   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" );
   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" );
   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" );
   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||" );
   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 );
   165     std::cout << 
"Reading current joint position" << std::endl;
   167     std::cout << 
"Initial joint position: " << q.t() << std::endl;
   172     vpHomogeneousMatrix fMed, fMed0;
   176     bool final_quit       = 
false;
   177     bool first_time       = 
false;
   178     bool start_trajectory = 
false;
   180     vpMatrix K( 6, 6 ), D( 6, 6 ), edVf( 6, 6 );
   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 } );
   191     double time_start_trajectory, time_prev, time_cur;
   192     double delay_before_trajectory = 0.5; 
   195     while ( !final_quit )
   207       if ( time_cur < delay_before_trajectory )
   209         time_start_trajectory = time_cur; 
   212       else if ( !start_trajectory ) 
   214         time_start_trajectory = time_cur;
   215         start_trajectory      = 
true;
   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) ;
   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) ;
   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) ;
   230       edVf.insert( fMed.getRotationMatrix().t(), 0, 0 );
   231       edVf.insert( fMed.getRotationMatrix().t(), 3, 3 );
   233       x_e = (vpColVector)vpPoseVector( fMed.inverse() * robot.
get_fMe() ); 
   234       Ja  = 
Ta( fMed.inverse() * robot.
get_fMe() ) * edVf * fJe;
   236       dx_e = 
Ta( fMed.inverse() * robot.
get_fMe() ) * edVf * ( dx_ed - fJe * dq );
   238       dt = time_cur - time_prev;
   242         dJa = ( Ja - Ja_old ) / dt;
   250       Ja_pinv_B_t = ( Ja * B.inverseByCholesky() * Ja.t() ).inverseByCholesky() * Ja * B.inverseByCholesky();
   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;
   261       tau_cmd = tau_d - tau_d0 * std::exp( -mu * ( time_cur - time_start_trajectory ) );
   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 );
   272       vpMouseButton::vpMouseButtonType button;
   273       if ( vpDisplay::getClick( plotter->I, button, 
false ) )
   275         if ( button == vpMouseButton::button3 )
   279           std::cout << 
"Stop the robot " << std::endl;
   286         std::cout << 
"dt: " << dt << std::endl;
   289       time_prev = time_cur;
   290       robot.
wait( time_cur, 0.001 ); 
   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", 
"# " );
   301     if ( plotter != 
nullptr )
   308   catch ( 
const vpException &e )
   310     std::cout << 
"ViSP exception: " << e.what() << std::endl;
   311     std::cout << 
"Stop the robot " << std::endl;
 void connect(const std::string &robot_ID="")
void getFriction(vpColVector &friction)
virtual void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position)
double getCoppeliasimSimulationTime()
virtual void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &force)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
void getCoriolis(vpColVector &coriolis)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void coppeliasimStopSimulation(double sleep_ms=1000.)
void wait(double timestamp_second, double duration_second)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
void setCoppeliasimSyncMode(bool enable, double sleep_ms=1000.)
void get_fJe(vpMatrix &fJe)
vpMatrix Ta(const vpHomogeneousMatrix &edMe)
void coppeliasimStartSimulation(double sleep_ms=1000.)
void setVerbose(bool verbose)
virtual void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ROSCPP_DECL void spinOnce()
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void getMass(vpMatrix &mass)
vpHomogeneousMatrix get_fMe(const vpColVector &q)