39 #include <std_msgs/Int32.h> 
   54   , m_acquisitionThread()
 
   55   , m_topic_jointState( 
"/coppeliasim/franka/joint_state" )
 
   56   , m_topic_g0( 
"/coppeliasim/franka/g0" )
 
   57   , m_topic_eMc( 
"/coppeliasim/franka/eMc" )
 
   58   , m_topic_flMe( 
"/coppeliasim/franka/flMe" )
 
   59   , m_topic_flMcom( 
"/coppeliasim/franka/flMcom" )
 
   60   , m_topic_toolInertia( 
"/coppeliasim/franka/tool/inertia" )
 
   61   , m_topic_jointStateCmd( 
"/fakeFCI/joint_state" )
 
   62   , m_topic_robotStateCmd( 
"/fakeFCI/robot_state" )
 
   63   , m_connected( false )
 
   64   , m_posControlThreadIsRunning( false )
 
   65   , m_posControlThreadStopAsked( false )
 
   66   , m_posControlLock( false )
 
   67   , m_posControlNewCmd( false )
 
   68   , m_velControlThreadIsRunning( false )
 
   69   , m_velControlThreadStopAsked( false )
 
   70   , m_ftControlThreadIsRunning( false )
 
   71   , m_ftControlThreadStopAsked( false )
 
   72   , m_pub_jointStateCmd()
 
   73   , m_pub_robotStateCmd()
 
   74   , m_pub_startSimulation()
 
   75   , m_pub_pauseSimulation()
 
   76   , m_pub_stopSimulation()
 
   77   , m_pub_triggerNextStep()
 
   78   , m_pub_enableSyncMode()
 
   79   , m_sub_coppeliasim_jointState()
 
   80   , m_sub_coppeliasim_eMc()
 
   81   , m_sub_coppeliasim_simulationStepDone()
 
   82   , m_sub_coppeliasim_simulationTime()
 
   83   , m_sub_coppeliasim_simulationState()
 
   84   , m_sub_coppeliasim_flMe()
 
   85   , m_sub_coppeliasim_toolInertia()
 
   86   , m_simulationStepDone( false )
 
   87   , m_simulationTime( 0. )
 
   88   , m_syncModeEnabled( false )
 
   89   , m_simulationState( 0 )
 
   90   , m_overwrite_flMe( true )
 
   91   , m_overwrite_toolInertia( true )
 
  136   if ( robot_ID != 
"" ) 
 
  139     m_topic_g0            = 
"/coppeliasim/franka/" + robot_ID + 
"/g0";
 
  140     m_topic_eMc           = 
"/coppeliasim/franka/" + robot_ID + 
"/eMc";
 
  141     m_topic_flMe          = 
"/coppeliasim/franka/" + robot_ID + 
"/flMe";
 
  151     std::cout << 
"Subscribe " << 
m_topic_g0 << std::endl;
 
  152     std::cout << 
"Subscribe " << 
m_topic_eMc << std::endl;
 
  187   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  192   vpTime::sleepMs( 3000 );
 
  193   std::cout << 
"ROS is initialized ? " << ( 
ros::isInitialized() ? 
"yes" : 
"no" ) << std::endl;
 
  211   std_msgs::Bool msg_enableSyncMode;
 
  212   msg_enableSyncMode.data = enable;
 
  231   std_msgs::Bool msg_pauseSimulation;
 
  232   msg_pauseSimulation.data = 
true;
 
  250   std_msgs::Bool msg_startSimulation;
 
  251   msg_startSimulation.data = 
true;
 
  270   std_msgs::Bool msg_stopSimulation;
 
  271   msg_stopSimulation.data = 
true;
 
  289   std_msgs::Bool msg_triggerNextStep;
 
  290   msg_triggerNextStep.data = 
true;
 
  301   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  311   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  323   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  334   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  344   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  355   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  369   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  390   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  402   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  403   for ( 
unsigned int i = 0; i < 7; i++ )
 
  405     m_q_kdl( i ) = 
m_q[i] = joint_state.position[i];
 
  406     m_dq[i]               = joint_state.velocity[i];
 
  407     m_tau_J[i]            = -joint_state.effort[i]; 
 
  420   vpColVector g0( 3, 0 );
 
  463         std::cout << 
"A tool has been mounted on the robot.\n";
 
  464         std::cout << 
"Mass: " << 
m_mL << 
" [kg]\n";
 
  465         std::cout << 
"Inertia Tensor in flange frame:\n" << 
m_Il << 
" [kg*m^2]\n";
 
  466         std::cout << 
"CoM position in flange frame: " << 
m_flMcom.getTranslationVector().t() << 
" [m]\n";
 
  467         std::cout << 
"CoM orientation in flange frame: \n" << 
m_flMcom.getRotationMatrix() << std::endl;
 
  485   std::lock_guard< std::mutex > lock( 
m_mutex );
 
  488     m_mL       = inertia_msg.m;
 
  489     m_Il[0][0] = inertia_msg.ixx;
 
  490     m_Il[0][1] = 
m_Il[1][0] = inertia_msg.ixy;
 
  491     m_Il[0][2] = 
m_Il[2][0] = inertia_msg.ixz;
 
  492     m_Il[1][1]              = inertia_msg.iyy;
 
  493     m_Il[1][2] = 
m_Il[2][1] = inertia_msg.iyz;
 
  494     m_Il[2][2]              = inertia_msg.izz;
 
  499     m_Il.eigenValues( eig, R );
 
  503     m_flMcom = vpHomogeneousMatrix( vpTranslationVector( inertia_msg.com.x, inertia_msg.com.y, inertia_msg.com.z ),
 
  504                                     (vpRotationMatrix)R.t() );
 
  513         std::cout << 
"A tool has been mounted on the robot.\n";
 
  514         std::cout << 
"Mass: " << 
m_mL << 
" [kg]\n";
 
  515         std::cout << 
"Inertia Tensor in flange frame:\n" << 
m_Il << 
" [kg*m^2]\n";
 
  516         std::cout << 
"CoM position in flange frame: " << 
m_flMcom.getTranslationVector().t() << 
" [m]\n";
 
  517         std::cout << 
"CoM orientation in flange frame: \n" << 
m_flMcom.getRotationMatrix() << std::endl;
 
  531     std::cout << 
"Position controller thread launched" << std::endl;
 
  535   sensor_msgs::JointState joint_state_cmd_msg;
 
  536   joint_state_cmd_msg.velocity.resize( 7 );
 
  537   joint_state_cmd_msg.name.resize( 7 );
 
  538   joint_state_cmd_msg.header.frame_id = 
"Joint_velocity_cmd";
 
  539   for ( 
unsigned int i = 0; i < 7; i++ )
 
  541     joint_state_cmd_msg.name[i] = 
"J" + std::to_string( i );
 
  543   vpColVector vel_max( 7, 0 ), dq_sat( 7, 0 ), gains( 7, 0 );
 
  544   vel_max = { 2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100 };
 
  546   vpMatrix Kp( 7, 7 ), Kd( 7, 7 );
 
  548   gains = { 6.0, 6.0, 6.0, 6.0, 3.5, 2.5, 2.0 };
 
  550   gains = { 0.5, 0.5, 0.5, 0.5, 0.3, 0.25, 0.2 };
 
  554   std_msgs::Int32 robot_ctrl_type_msg;
 
  555   robot_ctrl_type_msg.data = 
static_cast< int >( 
m_stateRobot );
 
  557       robot_ctrl_type_msg ); 
 
  563   if ( backup_sync_mode )
 
  572         robot_ctrl_type_msg ); 
 
  576     dq_sat   = vpRobot::saturateVelocities( 
m_dq_des, vel_max, 
false );
 
  577     if ( std::sqrt( ( ( 180. / M_PI ) * ( 
m_q_des - 
m_q ) ).sumSquare() ) > 0.1 )
 
  579       for ( 
unsigned int i = 0; i < 7; i++ )
 
  581         joint_state_cmd_msg.velocity[i] = dq_sat[i];
 
  586       for ( 
unsigned int i = 0; i < 7; i++ )
 
  588         joint_state_cmd_msg.velocity[i] = 0;
 
  597   for ( 
unsigned int i = 0; i < 7; i++ )
 
  599     joint_state_cmd_msg.velocity[i] = 0.;
 
  604   if ( backup_sync_mode )
 
  611     std::cout << 
"Position controller thread finished" << std::endl;
 
  623     std::cout << 
"Velocity controller thread launched" << std::endl;
 
  628   sensor_msgs::JointState joint_state_cmd_msg;
 
  629   joint_state_cmd_msg.velocity.resize( 7 );
 
  630   joint_state_cmd_msg.name.resize( 7 );
 
  631   joint_state_cmd_msg.header.frame_id = 
"Joint_velocity_cmd";
 
  632   for ( 
unsigned int i = 0; i < 7; i++ )
 
  634     joint_state_cmd_msg.name[i] = 
"J" + std::to_string( i );
 
  638   std_msgs::Int32 robot_ctrl_type_msg;
 
  639   robot_ctrl_type_msg.data = 
static_cast< int >( 
m_stateRobot );
 
  641       robot_ctrl_type_msg ); 
 
  643   vpColVector vel_max( 7, 0 ), dq_sat( 7, 0 );
 
  644   vel_max = { 2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100 };
 
  652         robot_ctrl_type_msg ); 
 
  654     dq_sat = vpRobot::saturateVelocities( 
m_dq_des, vel_max, 
true );
 
  655     for ( 
unsigned int i = 0; i < 7; i++ )
 
  657       joint_state_cmd_msg.velocity[i] = dq_sat[i];
 
  663   for ( 
unsigned int i = 0; i < 7; i++ )
 
  665     joint_state_cmd_msg.velocity[i] = 0;
 
  672     std::cout << 
"Velocity controller thread finished" << std::endl;
 
  684     std::cout << 
"Torque controller thread launched" << std::endl;
 
  689   sensor_msgs::JointState joint_state_cmd_msg;
 
  690   joint_state_cmd_msg.effort.resize( 7 );
 
  691   joint_state_cmd_msg.name.resize( 7 );
 
  692   joint_state_cmd_msg.header.frame_id = 
"Joint_torque_cmd";
 
  693   for ( 
unsigned int i = 0; i < 7; i++ )
 
  695     joint_state_cmd_msg.name[i] = 
"J" + std::to_string( i );
 
  699   std_msgs::Int32 robot_ctrl_type_msg;
 
  700   robot_ctrl_type_msg.data = 
static_cast< int >( 
m_stateRobot );
 
  702       robot_ctrl_type_msg ); 
 
  704   vpColVector g( 7, 0 ), tau_max( 7, 0 ), tau_sat( 7, 0 ), 
f( 7, 0 );
 
  705   tau_max = { 87, 87, 87, 87, 12, 12, 12 };
 
  708   const double samplingrate     = 1000.; 
 
  709   const double cutoff_frequency = 10.;   
 
  710   std::array< Iir::Butterworth::LowPass< order >, 7 > TorqueFilter;
 
  711   for ( 
unsigned int i = 0; i < 7; i++ )
 
  713     TorqueFilter[i].setup( samplingrate, cutoff_frequency );
 
  723         robot_ctrl_type_msg ); 
 
  728     for ( 
unsigned int i = 0; i < 7; i++ )
 
  734       joint_state_cmd_msg.effort[i] = 
m_tau_J_des[i] + g[i] - 
f[i];
 
  736       if ( 
m_verbose && std::abs( joint_state_cmd_msg.effort[i] ) > tau_max[i] )
 
  738         std::cout << 
"Excess torque " << joint_state_cmd_msg.effort[i] << 
" axis nr. " << i << std::endl;
 
  745   for ( 
unsigned int i = 0; i < 7; i++ )
 
  747     joint_state_cmd_msg.effort[i] = 0;
 
  754     std::cout << 
"Torque controller thread finished" << std::endl;
 
  763 vpRobot::vpRobotStateType
 
  768   case vpRobot::STATE_STOP:
 
  773       std::cout << 
"Change the control mode from position control to stop.\n";
 
  778     else if ( vpRobot::STATE_VELOCITY_CONTROL == 
getRobotState() )
 
  780       std::cout << 
"Change the control mode from velocity control to stop.\n";
 
  785     else if ( vpRobot::STATE_FORCE_TORQUE_CONTROL == 
getRobotState() )
 
  787       std::cout << 
"Change the control mode from force/torque control to stop.\n";
 
  806   case vpRobot::STATE_POSITION_CONTROL:
 
  810       std::cout << 
"Change the control mode from stop to position control.\n";
 
  812     else if ( vpRobot::STATE_VELOCITY_CONTROL == 
getRobotState() )
 
  814       std::cout << 
"Change the control mode from velocity to position control.\n";
 
  820     else if ( vpRobot::STATE_FORCE_TORQUE_CONTROL == 
getRobotState() )
 
  822       std::cout << 
"Change the control mode from force/torque to position control.\n";
 
  842   case vpRobot::STATE_VELOCITY_CONTROL:
 
  846       std::cout << 
"Change the control mode from stop to velocity control.\n";
 
  848     else if ( vpRobot::STATE_POSITION_CONTROL == 
getRobotState() )
 
  850       std::cout << 
"Change the control mode from position to velocity control.\n";
 
  855     else if ( vpRobot::STATE_FORCE_TORQUE_CONTROL == 
getRobotState() )
 
  857       std::cout << 
"Change the control mode from force/torque to velocity control.\n";
 
  884   case vpRobot::STATE_FORCE_TORQUE_CONTROL:
 
  888       std::cout << 
"Change the control mode from stop to force/torque control.\n";
 
  890     else if ( vpRobot::STATE_POSITION_CONTROL == 
getRobotState() )
 
  892       std::cout << 
"Change the control mode from position to force/torque control.\n";
 
  895     else if ( vpRobot::STATE_VELOCITY_CONTROL == 
getRobotState() )
 
  897       std::cout << 
"Change the control mode from velocity to force/torque control.\n";
 
  902     if ( 
getRobotState() != vpRobot::STATE_FORCE_TORQUE_CONTROL )
 
  964     std::cout << 
"Robot is not in position state control. " 
  965               << 
"You should call vpROSRobotFrankaCoppeliasim::setRobotState(vpRobot::STATE_POSITION_CONTROL)"