37 #include <visp3/gui/vpPlot.h>    41 main( 
int argc, 
char **argv )
    43   bool opt_coppeliasim_sync_mode = 
false;
    44   bool opt_verbose               = 
false;
    45   bool opt_save_data             = 
false;
    47   for ( 
int i = 1; i < argc; i++ )
    49     if ( std::string( argv[i] ) == 
"--enable-coppeliasim-sync-mode" )
    51       opt_coppeliasim_sync_mode = 
true;
    53     else if ( std::string( argv[i] ) == 
"--verbose" || std::string( argv[i] ) == 
"-v" )
    57     else if ( std::string( argv[i] ) == 
"--save" )
    61     else if ( std::string( argv[i] ) == 
"--help" || std::string( argv[i] ) == 
"-h" )
    63       std::cout << argv[0] << 
"[--enable-coppeliasim-sync-mode]"    65                 << 
" [--verbose] [-v] "    66                 << 
" [--help] [-h]" << std::endl;
    87       vpHomogeneousMatrix flMe(
    88           vpTranslationVector( 0, 0, 0.1034 ),
    89           vpRotationMatrix( { std::cos( vpMath::rad( 45 ) ), -std::sin( vpMath::rad( 45 ) ), 0,
    90                               std::sin( vpMath::rad( 45 ) ), std::cos( vpMath::rad( 45 ) ), 0, 0, 0, 1 } ) );
    91       vpHomogeneousMatrix fMcom( vpTranslationVector( -0.01, 0.0, 0.03 ), vpRotationMatrix() );
    93       I_l.diag( vpColVector( { 0.001, 0.0025, 0.0017 } ) ); 
    94       robot.
add_tool( flMe, mass, fMcom, I_l );
    99     std::cout << 
"Coppeliasim sync mode enabled: " << ( opt_coppeliasim_sync_mode ? 
"yes" : 
"no" ) << std::endl;
   105     vpColVector q_init( { 0, vpMath::rad( -45 ), 0, vpMath::rad( -135 ), 0, vpMath::rad( 90 ), vpMath::rad( 45 ) } );
   111     vpPlot *plotter = 
nullptr;
   113     plotter = 
new vpPlot( 4, 800, 800, 10, 10, 
"Real time curves plotter" );
   114     plotter->setTitle( 0, 
"Joint positions [rad]" );
   115     plotter->initGraph( 0, 7 );
   116     plotter->setLegend( 0, 0, 
"q1" );
   117     plotter->setLegend( 0, 1, 
"q2" );
   118     plotter->setLegend( 0, 2, 
"q3" );
   119     plotter->setLegend( 0, 3, 
"q4" );
   120     plotter->setLegend( 0, 4, 
"q5" );
   121     plotter->setLegend( 0, 5, 
"q6" );
   122     plotter->setLegend( 0, 6, 
"q7" );
   124     plotter->setTitle( 1, 
"Joint position error [rad]" );
   125     plotter->initGraph( 1, 7 );
   126     plotter->setLegend( 1, 0, 
"e_q1" );
   127     plotter->setLegend( 1, 1, 
"e_q2" );
   128     plotter->setLegend( 1, 2, 
"e_q3" );
   129     plotter->setLegend( 1, 3, 
"e_q4" );
   130     plotter->setLegend( 1, 4, 
"e_q5" );
   131     plotter->setLegend( 1, 5, 
"e_q6" );
   132     plotter->setLegend( 1, 6, 
"e_q7" );
   134     plotter->setTitle( 2, 
"Joint torque measure [Nm]" );
   135     plotter->initGraph( 2, 7 );
   136     plotter->setLegend( 2, 0, 
"Tau1" );
   137     plotter->setLegend( 2, 1, 
"Tau2" );
   138     plotter->setLegend( 2, 2, 
"Tau3" );
   139     plotter->setLegend( 2, 3, 
"Tau4" );
   140     plotter->setLegend( 2, 4, 
"Tau5" );
   141     plotter->setLegend( 2, 5, 
"Tau6" );
   142     plotter->setLegend( 2, 6, 
"Tau7" );
   144     plotter->setTitle( 3, 
"Joint error norm [rad]" );
   145     plotter->initGraph( 3, 1 );
   146     plotter->setLegend( 3, 0, 
"||qd - d||" );
   149     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 ),
   150         F( 7, 0 ), tau_d0( 7, 0 ), tau_cmd( 7, 0 ), tau( 7, 0 );
   153     std::cout << 
"Reading current joint position" << std::endl;
   155     std::cout << 
"Initial joint position: " << q0.t() << std::endl;
   162     bool final_quit       = 
false;
   163     bool first_time       = 
false;
   164     bool start_trajectory = 
false;
   166     vpMatrix K( 7, 7 ), D( 7, 7 ), I( 7, 7 );
   167     K.diag( { 400.0, 400.0, 400.0, 400.0, 400.0, 400.0, 900.0 } );
   168     D.diag( { 20.0, 45.0, 45.0, 45.0, 45.0, 45.0, 60.0 } );
   169     I.diag( { 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 60.0 } );
   171     vpColVector integral( 7, 0 );
   176     double time_start_trajectory, time_prev, time_cur;
   177     double delay_before_trajectory = 0.5; 
   180     while ( !final_quit )
   191       if ( time_cur < delay_before_trajectory )
   193         time_start_trajectory = time_cur; 
   196       else if ( !start_trajectory ) 
   198         time_start_trajectory = time_cur;
   199         start_trajectory      = 
true;
   204       qd[0]   = q0[0] + ( start_trajectory ? std::sin( 2 * M_PI * 0.1 * ( time_cur - time_start_trajectory ) ) : 0 );
   205       dqd[0]  = ( start_trajectory ? 2 * M_PI * 0.1 * std::cos( 2 * M_PI * 0.1 * ( time_cur - time_start_trajectory ) ) : 0 );
   206       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 );
   208       qd[2]   = q0[2] + ( start_trajectory ? ( M_PI / 16 ) * std::sin( 2 * M_PI * 0.2 * ( time_cur - time_start_trajectory ) ) : 0 );
   209       dqd[2]  = ( start_trajectory ? M_PI * ( M_PI / 8 ) * 0.2 * std::cos( 2 * M_PI * 0.2 * ( time_cur - time_start_trajectory ) ) : 0 );
   210       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 );
   212       qd[3]   = q0[3] + ( start_trajectory ? 0.25 * std::sin( 2 * M_PI * 0.05 * ( time_cur - time_start_trajectory ) ) : 0 );
   213       dqd[3]  = ( start_trajectory ? 2 * M_PI * 0.05 * 0.25 * std::cos( 2 * M_PI * 0.05 * ( time_cur - time_start_trajectory ) ) : 0 );
   214       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 );
   221       dt = time_cur - time_prev;
   222       if ( start_trajectory )
   224         integral += ( qd - q ) * dt;
   228       tau_d = B * ( K * ( qd - q ) + D * ( dqd - dq ) + I * ( integral ) + ddqd ) + C + F;
   235       tau_cmd = tau_d - tau_d0 * std::exp( -mu * ( time_cur - time_start_trajectory ) );
   240       vpColVector norm( 1, vpMath::deg( std::sqrt( ( qd - q ).sumSquare() ) ) );
   241       plotter->plot( 0, time_cur, q );
   242       plotter->plot( 1, time_cur, qd - q );
   243       plotter->plot( 2, time_cur, tau );
   244       plotter->plot( 3, time_cur, norm );
   245       vpMouseButton::vpMouseButtonType button;
   246       if ( vpDisplay::getClick( plotter->I, button, 
false ) )
   248         if ( button == vpMouseButton::button3 )
   252           std::cout << 
"Stop the robot " << std::endl;
   259         std::cout << 
"dt: " << dt << std::endl;
   262       time_prev = time_cur;
   263       robot.
wait( time_cur, 0.001 ); 
   268       plotter->saveData( 0, 
"sim-joint-position.txt", 
"# " );
   269       plotter->saveData( 1, 
"sim-joint-position-error.txt", 
"# " );
   270       plotter->saveData( 2, 
"sim-joint-torque-measure.txt", 
"# " );
   271       plotter->saveData( 3, 
"sim-joint-error-norm.txt", 
"# " );
   274     if ( plotter != 
nullptr )
   282   catch ( 
const vpException &e )
   284     std::cout << 
"ViSP exception: " << e.what() << std::endl;
   285     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)
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)
void setCoppeliasimSyncMode(bool enable, double sleep_ms=1000.)
void coppeliasimStartSimulation(double sleep_ms=1000.)
void setVerbose(bool verbose)
int main(int argc, char **argv)
virtual void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
ROSCPP_DECL void spinOnce()
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void getMass(vpMatrix &mass)
virtual void add_tool(const vpHomogeneousMatrix &flMe, const double mL, const vpHomogeneousMatrix &flMcom, const vpMatrix &I_L)