37 #include <visp3/core/vpCameraParameters.h>    38 #include <visp3/detection/vpDetectorAprilTag.h>    39 #include <visp3/gui/vpDisplayOpenCV.h>    40 #include <visp3/gui/vpPlot.h>    41 #include <visp3/io/vpImageIo.h>    42 #include <visp3/visual_features/vpFeatureThetaU.h>    43 #include <visp3/visual_features/vpFeatureTranslation.h>    44 #include <visp3/vs/vpServo.h>    45 #include <visp3/vs/vpServoDisplay.h>    50 #include <geometry_msgs/WrenchStamped.h>    54                           std::vector< vpImagePoint > *traj_vip )
    56   for ( 
size_t i = 0; i < vip.size(); i++ )
    58     if ( traj_vip[i].size() )
    61       if ( vpImagePoint::distance( vip[i], traj_vip[i].back() ) > 1. )
    63         traj_vip[i].push_back( vip[i] );
    68       traj_vip[i].push_back( vip[i] );
    71   for ( 
size_t i = 0; i < vip.size(); i++ )
    73     for ( 
size_t j = 1; j < traj_vip[i].size(); j++ )
    75       vpDisplay::displayLine( I, traj_vip[i][j - 1], traj_vip[i][j], vpColor::green, 2 );
    81 Ta( 
const vpHomogeneousMatrix &edMe )
    83   vpMatrix Lx( 6, 6 ), Lw( 3, 3 ), skew_u( 3, 3 );
    86   vpThetaUVector tu( edMe );
    91   tu.extract( theta, u );
    92   skew_u = vpColVector::skew( u );
    96     Lw -= 0.5 * theta * skew_u;
    97     Lw += ( 1 - ( ( vpMath::sinc( theta ) ) / ( vpMath::sqr( vpMath::sinc( theta * 0.5 ) ) ) ) ) * skew_u * skew_u;
   100   Lx.insert( Lw, 3, 3 );
   105 vpColVector 
We( 6, 0 );
   112   We[0] = sensor_wrench.wrench.force.x;
   113   We[1] = sensor_wrench.wrench.force.y;
   114   We[2] = sensor_wrench.wrench.force.z;
   115   We[3] = sensor_wrench.wrench.torque.x;
   116   We[4] = sensor_wrench.wrench.torque.y;
   117   We[5] = sensor_wrench.wrench.torque.z;
   124   vpMatrix Lx( 6, 6 ), Lw( 3, 3 ), skew_u( 3, 3 );
   126   vpRotationMatrix cdRc( cdMc );
   127   vpThetaUVector tu( cdMc );
   132   tu.extract( theta, u );
   133   skew_u = vpColVector::skew( u );
   135   Lw += 0.5 * theta * skew_u;
   136   Lw += ( 1 - ( ( vpMath::sinc( theta ) ) / ( vpMath::sqr( vpMath::sinc( theta * 0.5 ) ) ) ) ) * skew_u * skew_u;
   138   Lx.insert( cdRc, 0, 0 );
   139   Lx.insert( Lw, 3, 3 );
   147   double opt_tagSize             = 0.08;
   148   bool display_tag               = 
true;
   149   int opt_quad_decimate          = 2;
   150   bool opt_verbose               = 
false;
   151   bool opt_plot                  = 
false;
   152   bool opt_adaptive_gain         = 
false;
   153   double convergence_threshold_t = 0.005, convergence_threshold_tu = 0.5;
   154   bool opt_coppeliasim_sync_mode = 
false;
   156   for ( 
int i = 1; i < argc; i++ )
   158     if ( std::string( argv[i] ) == 
"--tag_size" && i + 1 < argc )
   160       opt_tagSize = std::stod( argv[i + 1] );
   162     else if ( std::string( argv[i] ) == 
"--verbose" || std::string( argv[i] ) == 
"-v" )
   166     else if ( std::string( argv[i] ) == 
"--plot" )
   170     else if ( std::string( argv[i] ) == 
"--adaptive_gain" )
   172       opt_adaptive_gain = 
true;
   174     else if ( std::string( argv[i] ) == 
"--quad_decimate" && i + 1 < argc )
   176       opt_quad_decimate = std::stoi( argv[i + 1] );
   178     else if ( std::string( argv[i] ) == 
"--no-convergence-threshold" )
   180       convergence_threshold_t  = 0.;
   181       convergence_threshold_tu = 0.;
   183     else if ( std::string( argv[i] ) == 
"--enable-coppeliasim-sync-mode" )
   185       opt_coppeliasim_sync_mode = 
true;
   187     else if ( std::string( argv[i] ) == 
"--help" || std::string( argv[i] ) == 
"-h" )
   189       std::cout << argv[0] << 
"[--tag_size <marker size in meter; default " << opt_tagSize << 
">] "   190                 << 
"[--quad_decimate <decimation; default " << opt_quad_decimate << 
">] "   191                 << 
"[--adaptive_gain] "   193                 << 
"[--task_sequencing] "   194                 << 
"[--no-convergence-threshold] "   195                 << 
"[--enable-coppeliasim-sync-mode] "   196                 << 
"[--verbose] [-v] "   197                 << 
"[--help] [-h]" << std::endl;
   217     right_arm.
connect( 
"right_arm" );
   219     left_arm.
connect( 
"left_arm" );
   221     std::cout << 
"Coppeliasim sync mode enabled: " << ( opt_coppeliasim_sync_mode ? 
"yes" : 
"no" ) << std::endl;
   227     vpHomogeneousMatrix bMfra( vpTranslationVector( 0.040, -0.03, 0.17 ),
   228                                vpRotationMatrix( { 1, 0, 0, 0, 0, -1, 0, 1, 0 } ) );
   229     vpHomogeneousMatrix bMfla( vpTranslationVector( 0.040, 0.03, 0.17 ),
   230                                vpRotationMatrix( { 1, 0, 0, 0, 0, 1, 0, -1, 0 } ) );
   232     vpImage< unsigned char > I;
   236     g.
open( argc, argv );
   240     std::cout << 
"Image size: " << I.getWidth() << 
" x " << I.getHeight() << std::endl;
   241     vpCameraParameters cam;
   244     std::cout << cam << std::endl;
   245     vpDisplayOpenCV dc( I, 10, 10, 
"Color image" );
   247     vpDetectorAprilTag::vpAprilTagFamily tagFamily                  = vpDetectorAprilTag::TAG_36h11;
   248     vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS;
   249     vpDetectorAprilTag detector( tagFamily );
   250     detector.setAprilTagPoseEstimationMethod( poseEstimationMethod );
   251     detector.setDisplayTag( display_tag );
   252     detector.setAprilTagQuadDecimate( opt_quad_decimate );
   255     vpHomogeneousMatrix ccMo, cMo, oMo, ccMc, cdMcc, wMo, wMt;
   257     vpHomogeneousMatrix cdMo( vpTranslationVector( 0.0, 0.0, 0.2 ),
   258                               vpRotationMatrix( { 1, 0, 0, 0, -1, 0, 0, 0, -1 } ) );
   261     vpFeatureTranslation t( vpFeatureTranslation::cdMc );
   262     vpFeatureThetaU tu( vpFeatureThetaU::cdRc );
   264     tu.buildFrom( ccMc );
   266     vpFeatureTranslation td( vpFeatureTranslation::cdMc );
   267     vpFeatureThetaU tud( vpFeatureThetaU::cdRc );
   271     task.addFeature( t, td );
   272     task.addFeature( tu, tud );
   274     task.setServo( vpServo::EYEINHAND_CAMERA );
   275     task.setInteractionMatrixType( vpServo::CURRENT );
   277     if ( opt_adaptive_gain )
   279       std::cout << 
"Enable adaptive gain" << std::endl;
   280       vpAdaptiveGain lambda( 4, 1.2, 25 ); 
   281       task.setLambda( lambda );
   285       task.setLambda( 1.2 );
   288     vpPlot *plotter      = 
nullptr;
   289     vpPlot *plotter_left = 
nullptr;
   293       plotter = 
new vpPlot( 3, static_cast< int >( 250 * 2 ), 600, static_cast< int >( I.getWidth() ) + 80, 10,
   294                             "Real time curves plotter" );
   295       plotter->setTitle( 0, 
"Visual features error" );
   296       plotter->setTitle( 1, 
"Camera velocities" );
   297       plotter->setTitle( 2, 
"Measured wrench" );
   298       plotter->initGraph( 0, 6 );
   299       plotter->initGraph( 1, 6 );
   300       plotter->initGraph( 2, 6 );
   301       plotter->setLegend( 0, 0, 
"error_feat_tx" );
   302       plotter->setLegend( 0, 1, 
"error_feat_ty" );
   303       plotter->setLegend( 0, 2, 
"error_feat_tz" );
   304       plotter->setLegend( 0, 3, 
"error_feat_theta_ux" );
   305       plotter->setLegend( 0, 4, 
"error_feat_theta_uy" );
   306       plotter->setLegend( 0, 5, 
"error_feat_theta_uz" );
   307       plotter->setLegend( 1, 0, 
"vc_x" );
   308       plotter->setLegend( 1, 1, 
"vc_y" );
   309       plotter->setLegend( 1, 2, 
"vc_z" );
   310       plotter->setLegend( 1, 3, 
"wc_x" );
   311       plotter->setLegend( 1, 4, 
"wc_y" );
   312       plotter->setLegend( 1, 5, 
"wc_z" );
   313       plotter->setLegend( 2, 0, 
"F_x" );
   314       plotter->setLegend( 2, 1, 
"F_y" );
   315       plotter->setLegend( 2, 2, 
"F_z" );
   316       plotter->setLegend( 2, 3, 
"Tau_x" );
   317       plotter->setLegend( 2, 4, 
"Tau_y" );
   318       plotter->setLegend( 2, 5, 
"Tau_z" );
   320       plotter_left = 
new vpPlot( 4, 500, 600, 10, 10, 
"Real time curves plotter" );
   321       plotter_left->setTitle( 0, 
"EE Pose [m] - [rad]" );
   322       plotter_left->initGraph( 0, 6 );
   323       plotter_left->setLegend( 0, 0, 
"x" );
   324       plotter_left->setLegend( 0, 1, 
"y" );
   325       plotter_left->setLegend( 0, 2, 
"z" );
   326       plotter_left->setLegend( 0, 3, 
"tu_x" );
   327       plotter_left->setLegend( 0, 4, 
"tu_y" );
   328       plotter_left->setLegend( 0, 5, 
"tu_z" );
   330       plotter_left->setTitle( 1, 
"EE pose error [m] - [rad]" );
   331       plotter_left->initGraph( 1, 6 );
   332       plotter_left->setLegend( 1, 0, 
"e_x" );
   333       plotter_left->setLegend( 1, 1, 
"e_y" );
   334       plotter_left->setLegend( 1, 2, 
"e_z" );
   335       plotter_left->setLegend( 1, 3, 
"e_tu_x" );
   336       plotter_left->setLegend( 1, 4, 
"e_tu_y" );
   337       plotter_left->setLegend( 1, 5, 
"e_tu_z" );
   339       plotter_left->setTitle( 2, 
"Joint torque command [Nm]" );
   340       plotter_left->initGraph( 2, 7 );
   341       plotter_left->setLegend( 2, 0, 
"Tau1" );
   342       plotter_left->setLegend( 2, 1, 
"Tau2" );
   343       plotter_left->setLegend( 2, 2, 
"Tau3" );
   344       plotter_left->setLegend( 2, 3, 
"Tau4" );
   345       plotter_left->setLegend( 2, 4, 
"Tau5" );
   346       plotter_left->setLegend( 2, 5, 
"Tau6" );
   347       plotter_left->setLegend( 2, 6, 
"Tau7" );
   349       plotter_left->setTitle( 3, 
"Pose error norm [rad]" );
   350       plotter_left->initGraph( 3, 1 );
   351       plotter_left->setLegend( 3, 0, 
"||e||" ); 
   354     bool final_quit                           = 
false;
   355     bool has_converged                        = 
false;
   356     bool send_cmd                             = 
false;
   357     bool restart                              = 
false;
   358     std::vector< vpImagePoint > *traj_corners = 
nullptr; 
   361     double sim_time_prev        = sim_time;
   362     double sim_time_init_servo  = sim_time;
   363     double sim_time_img         = sim_time;
   364     double sim_time_img_prev    = sim_time;
   365     double sim_time_start       = sim_time;
   366     double sim_time_convergence = sim_time;
   369     vpMatrix K( 6, 6 ), D( 6, 6 );
   372     K.diag( { wp * wp, wp * wp, wp * wp, wo * wo, wo * wo, wo * wo } );
   373     D.diag( { 2 * wp, 2 * wp, 2 * wp, 2 * wo, 2 * wo, 2 * wo } );
   378     std::cout << 
"eMc:\n" << right_arm.
get_eMc() << std::endl;
   380     vpColVector v_c( 6, 0 ), q( 7, 0 ), dq( 7, 0 ), tau_d( 7, 0 ), C( 7, 0 ), pos( 6, 0 ), F( 7, 0 ), tau_d0( 7, 0 ),
   381         tau_cmd( 7, 0 ), x_e( 6, 0 ), dx_e( 6, 0 ), dx_ed( 6, 0 ), ddx_ed( 6, 0 );
   382     vpMatrix J( 6, 7 ), Ja( 6, 7 ), dJa( 6, 7 ), Ja_old( 6, 7 ), B( 7, 7 ), I7( 7, 7 ), Ja_pinv_B_t( 6, 7 ), Ls( 6, 6 );
   387     left_arm.
setRobotState( vpRobot::STATE_FORCE_TORQUE_CONTROL );
   392     vpRotationMatrix wRed0( { 1, 0, 0, 0, -1, 0, 0, 0, -1 } );
   393     vpHomogeneousMatrix wMed0( vpTranslationVector( 0.5, 0.0, 0.0 ), wRed0 );
   394     vpHomogeneousMatrix wMed;
   397     std::atomic_bool admittance_thread_running{ 
true };
   398     bool init_done = 
false;
   400     vpHomogeneousMatrix ftTee;
   405     std::cout << 
"ftTee:\n" << ftTee << 
"\n";
   407     vpVelocityTwistMatrix cTe;
   408     cTe.buildFrom( right_arm.
get_eMc().inverse() );
   410     vpForceTwistMatrix cFee, eeFft, eeFc;
   411     cFee.buildFrom( right_arm.
get_eMc().inverse() );
   412     eeFc.buildFrom( right_arm.
get_eMc() );
   413     eeFft.buildFrom( ftTee.inverse() );
   416     vpColVector dde_s( 6, 0 ), de_s( 6, 0 ), e_s( 6, 0 ), d_err( 6, 0 ), err( 6, 0 ), old_err( 6, 0 );
   417     vpMatrix Ks( 6, 6 ), Ds( 6, 6 ), Be( 6, 6 ), Bc_inv( 6, 6 ), I3( 3, 3 );
   422     Be.insert( 1 * I3, 0, 0 );   
   423     Be.insert( 0.1 * I3, 3, 3 ); 
   425     Bc_inv = cTe * Be.inverseByCholesky() * ( (vpMatrix)cTe ).t();
   427     vpColVector r( 3, 0 ), wFcog( 3, 0 ), ft_load( 6, 0 ), ft_meas( 6, 0 ), cfc_meas( 6, 0 ), Fs( 6, 0 );
   429     wFcog[2] = -9.81 * m;
   430     r        = right_arm.
get_flMcom().getTranslationVector();
   432     std::thread fast_thread( [&]() {
   433       std::cout << 
"fast_thread: started... \n" << std::endl;
   436         while ( admittance_thread_running )
   442             dt            = sim_time - sim_time_prev;
   443             sim_time_prev = sim_time;
   446             vpColVector aux( 3, 0 );
   447             aux = ( ( bMfra * right_arm.
get_fMe() * right_arm.
get_flMe().inverse() ).
inverse() ).getRotationMatrix() *
   452             aux        = vpColVector::skew( r ) * aux;
   456             ft_meas    = 
We - ft_load;
   459             cfc_meas = cFee * eeFft * ft_meas;
   460             task.computeControlLaw();
   463             Fs = Ls * Bc_inv * cfc_meas;
   466             dde_s = -Ks * e_s - Ds * de_s + Fs;
   470             cdMcc.insert( (vpTranslationVector)e_s.extract( 0, 3 ) );
   471             if ( 
sqrt( e_s.extract( 3, 3 ).sumSquare() ) != 0.0 )
   473               vpRotationMatrix R_aux;
   474               R_aux.buildFrom( (vpThetaUVector)e_s.extract( 3, 3 ) );
   475               cdMcc.insert( R_aux );
   479               cdMcc.insert( vpRotationMatrix() );
   481             ccMo = cdMcc.inverse() * cdMo;
   482             ccMc = ccMo * oMo * cMo.inverse();
   484             tu.buildFrom( ccMc );
   486             v_c = task.computeControlLaw();
   497               wMed[0][3] = wMed0[0][3] + 0.05 * 
sin( 2 * M_PI * 0.3 * ( sim_time - sim_time_convergence ) );
   498               wMed[1][3] = wMed0[1][3] + 0.05 * ( 1 - 
cos( 2 * M_PI * 0.3 * ( sim_time - sim_time_convergence ) ) );
   501               dx_ed[0] = 2 * M_PI * 0.3 * 0.05 * 
cos( 2 * M_PI * 0.3 * ( sim_time - sim_time_convergence ) );
   502               dx_ed[1] = 2 * M_PI * 0.3 * 0.05 * 
sin( 2 * M_PI * 0.3 * ( sim_time - sim_time_convergence ) );
   506                   -2 * M_PI * 0.3 * 2 * M_PI * 0.3 * 0.05 * 
sin( 2 * M_PI * 0.3 * ( sim_time - sim_time_convergence ) );
   508                   2 * M_PI * 0.3 * 2 * M_PI * 0.3 * 0.05 * 
cos( 2 * M_PI * 0.3 * ( sim_time - sim_time_convergence ) );
   514             RR.insert( wMed.getRotationMatrix().t(), 0, 0 );
   515             RR.insert( wMed.getRotationMatrix().t(), 3, 3 );
   517             x_e = (vpColVector)vpPoseVector( wMed.inverse() * left_arm.
get_fMe() );
   518             Ja  = 
Ta( wMed.inverse() * left_arm.
get_fMe() ) * RR * J;
   520             dx_e = 
Ta( wMed.inverse() * left_arm.
get_fMe() ) * RR * ( dx_ed - J * dq );
   524               dJa = ( Ja - Ja_old ) / dt;
   532             Ja_pinv_B_t = ( Ja * B.inverseByCholesky() * Ja.t() ).inverseByCholesky() * Ja * B.inverseByCholesky();
   535             tau_d = B * Ja.pseudoInverse() * ( -K * ( x_e ) + D * (dx_e)-dJa * dq + ddx_ed ) + C + F -
   536                     ( I7 - Ja.t() * Ja_pinv_B_t ) * B * dq * 100;
   552               tau_cmd = tau_d - tau_d0 * std::exp( -mu * ( sim_time - c_time ) );
   555             right_arm.
setVelocity( vpRobot::CAMERA_FRAME, v_c );
   561           right_arm.
wait( sim_time, 0.002 );
   564       catch ( 
const vpException &e )
   566         std::cout << 
"ViSP exception: " << e.what() << std::endl;
   567         admittance_thread_running = 
false;
   571         std::cout << 
"Something wrong happens: " << std::endl;
   572         admittance_thread_running = 
false;
   574       std::cout << 
"fast_thread: exiting..." << std::endl;
   579     while ( !final_quit )
   582       vpDisplay::display( I );
   584       std::vector< vpHomogeneousMatrix > cMo_vec;
   585       detector.detect( I, opt_tagSize, cam, cMo_vec );
   588         std::stringstream ss;
   589         ss << 
"Left click to " << ( send_cmd ? 
"stop the robot" : 
"servo the robot" ) << 
", right click to quit.";
   590         vpDisplay::displayText( I, 20, 20, ss.str(), vpColor::red );
   594       if ( cMo_vec.size() == 1 )
   601           std::vector< vpHomogeneousMatrix > v_oMo( 2 ), v_cdMc( 2 );
   602           v_oMo[1].buildFrom( 0, 0, 0, 0, 0, M_PI );
   603           for ( 
size_t i = 0; i < 2; i++ )
   605             v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
   607           if ( std::fabs( v_cdMc[0].getThetaUVector().getTheta() ) <
   608                std::fabs( v_cdMc[1].getThetaUVector().getTheta() ) )
   614             std::cout << 
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
   617           sim_time_start = sim_time;
   622         ccMc = ccMo * oMo * cMo.inverse();
   624         tu.buildFrom( ccMc );
   630         vpDisplay::displayFrame( I, cdMo * oMo, cam, opt_tagSize / 1.5, vpColor::yellow, 2 );
   631         vpDisplay::displayFrame( I, ccMo * oMo, cam, opt_tagSize / 2, vpColor::none, 3 );
   632         vpDisplay::displayFrame( I, cMo, cam, opt_tagSize / 2, vpColor::none, 3 );
   635         std::vector< vpImagePoint > corners = detector.getPolygon( 0 );
   638         corners.push_back( detector.getCog( 0 ) );
   642           traj_corners = 
new std::vector< vpImagePoint >[corners.size()];
   648         vpTranslationVector cd_t_c = ccMc.getTranslationVector();
   649         vpThetaUVector cd_tu_c     = ccMc.getThetaUVector();
   650         double error_tr            = 
sqrt( cd_t_c.sumSquare() );
   651         double error_tu            = vpMath::deg( 
sqrt( cd_tu_c.sumSquare() ) );
   653         std::stringstream ss;
   654         ss << 
"error_t [m]: " << error_tr;
   655         vpDisplay::displayText( I, 20, static_cast< int >( I.getWidth() ) - 160, ss.str(), vpColor::red );
   657         ss << 
"error_tu [deg]: " << error_tu;
   658         vpDisplay::displayText( I, 40, static_cast< int >( I.getWidth() ) - 160, ss.str(), vpColor::red );
   660         if ( !has_converged && error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu )
   662           has_converged        = 
true;
   663           sim_time_convergence = sim_time;
   664           std::cout << 
"Servo task has converged \n";
   665           vpDisplay::displayText( I, 100, 20, 
"Servo task has converged", vpColor::red );
   681         plotter->plot( 0, static_cast< double >( sim_time ), task.getError() );
   682         plotter->plot( 1, static_cast< double >( sim_time ), v_c );
   683         plotter->plot( 2, static_cast< double >( sim_time ), cfc_meas );
   685         plotter_left->plot( 0, sim_time, (vpColVector)vpPoseVector( bMfla * left_arm.
get_fMe() ) );
   686         plotter_left->plot( 1, sim_time, x_e );
   687         plotter_left->plot( 2, sim_time, tau_cmd );
   688         plotter_left->plot( 3, sim_time, vpColVector( 1, 
sqrt( x_e.sumSquare() ) ) );
   691       std::stringstream ss;
   692       ss << 
"Loop time [s]: " << std::round( ( sim_time_img - sim_time_img_prev ) * 1000. ) / 1000.;
   693       ss << 
" Simulation time [s]: " << sim_time_img;
   694       sim_time_img_prev = sim_time_img;
   695       vpDisplay::displayText( I, 40, 20, ss.str(), vpColor::red );
   697       vpMouseButton::vpMouseButtonType button;
   698       if ( vpDisplay::getClick( I, button, 
false ) )
   702         case vpMouseButton::button1:
   703           send_cmd = !send_cmd;
   706         case vpMouseButton::button3:
   710           admittance_thread_running = 
false;
   718       vpDisplay::flush( I );
   721     if ( opt_plot && plotter != 
nullptr && plotter_left != 
nullptr )
   726       plotter_left = 
nullptr;
   734       while ( !final_quit )
   737         vpDisplay::display( I );
   739         vpDisplay::displayText( I, 20, 20, 
"Click to quit the program.", vpColor::red );
   740         vpDisplay::displayText( I, 40, 20, 
"Visual servo converged.", vpColor::red );
   742         if ( vpDisplay::getClick( I, 
false ) )
   747         vpDisplay::flush( I );
   750     if ( fast_thread.joinable() )
   753       std::cout << 
"fast thread joined.. \n ";
   757       delete[] traj_corners;
   760   catch ( 
const vpException &e )
   762     std::cout << 
"ViSP exception: " << e.what() << std::endl;
   763     std::cout << 
"Stop the robot " << std::endl;
 
void connect(const std::string &robot_ID="")
vpHomogeneousMatrix get_eMc() const
Class for cameras video capture for ROS cameras. 
void getFriction(vpColVector &friction)
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
vpHomogeneousMatrix get_flMe() const
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 open(int argc, char **argv)
void getCoriolis(vpColVector &coriolis)
bool getCameraInfo(vpCameraParameters &cam)
void setImageTopic(const std::string &topic_name)
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
void coppeliasimStopSimulation(double sleep_ms=1000.)
void wait(double timestamp_second, double duration_second)
vpMatrix compute_interaction_matrix_3D(const vpHomogeneousMatrix &cdMc)
vpMatrix Ta(const vpHomogeneousMatrix &edMe)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
int main(int argc, char **argv)
void setCoppeliasimSyncMode(bool enable, double sleep_ms=1000.)
void get_fJe(vpMatrix &fJe)
vpHomogeneousMatrix get_flMcom() const
class for Camera video capture for ROS middleware. 
void display_point_trajectory(const vpImage< unsigned char > &I, const std::vector< vpImagePoint > &vip, std::vector< vpImagePoint > *traj_vip)
void Wrench_callback(const geometry_msgs::WrenchStamped &sensor_wrench)
void coppeliasimStartSimulation(double sleep_ms=1000.)
void setVerbose(bool verbose)
void setCameraInfoTopic(const std::string &topic_name)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
double get_tool_mass() const
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)
void acquire(vpImage< unsigned char > &I)
vpHomogeneousMatrix get_fMe(const vpColVector &q)