vpROSRobotFrankaCoppeliasim.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of the ViSP software.
3  * Copyright (C) 2005 - 2021 by INRIA. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * ("GPL") version 2 as published by the Free Software Foundation.
8  * See the file LICENSE.txt at the root directory of this source
9  * distribution for additional information about the GNU GPL.
10  *
11  * For using ViSP with software that can not be combined with the GNU
12  * GPL, please contact INRIA about acquiring a ViSP Professional
13  * Edition License.
14  *
15  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
16  *
17  * This software was developed at:
18  * INRIA Rennes - Bretagne Atlantique
19  * Campus Universitaire de Beaulieu
20  * 35042 Rennes Cedex
21  * France
22  * http://www.irisa.fr/lagadic
23  *
24  * If you have questions regarding the use of this file, please contact
25  * INRIA at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Franka robot ROS simulator coupled with Coppeliasim.
32  *
33  * Authors:
34  * Alexander Oliva
35  * Fabien Spindler
36  */
37 
38 #include <ros/ros.h>
39 #include <std_msgs/Int32.h>
40 
41 #include <visp_bridge/3dpose.h>
42 
44 
45 #ifdef VISP_HAVE_IIR
46 #include <Iir.h>
47 #endif
48 
53  : m_controlThread()
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 )
92 {
93 }
94 
99 {
100  m_mutex.lock();
101  m_connected = false;
105  m_mutex.unlock();
106 
107  if ( m_controlThread.joinable() )
108  {
109  m_controlThread.join();
116  }
117 
118  if ( m_acquisitionThread.joinable() )
119  {
120  m_acquisitionThread.join();
121  }
122 }
123 
131 void
132 vpROSRobotFrankaCoppeliasim::connect( const std::string &robot_ID )
133 {
134  ros::NodeHandlePtr n = boost::make_shared< ros::NodeHandle >();
135 
136  if ( robot_ID != "" ) // TODO: regex to check name is valid for ROS topic
137  {
138  m_topic_jointState = "/coppeliasim/franka/" + robot_ID + "/joint_state";
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";
142  m_topic_flMcom = "/coppeliasim/franka/" + robot_ID + "/flMcom";
143  m_topic_toolInertia = "/coppeliasim/franka/" + robot_ID + "/tool/inertia";
144  m_topic_jointStateCmd = "/fakeFCI/" + robot_ID + "/joint_state";
145  m_topic_robotStateCmd = "/fakeFCI/" + robot_ID + "/robot_state";
146  }
147 
148  if ( m_verbose )
149  {
150  std::cout << "Subscribe " << m_topic_jointState << std::endl;
151  std::cout << "Subscribe " << m_topic_g0 << std::endl;
152  std::cout << "Subscribe " << m_topic_eMc << std::endl;
153  std::cout << "Subscribe " << m_topic_flMe << std::endl;
154  std::cout << "Subscribe " << m_topic_flMcom << std::endl;
155  std::cout << "Subscribe " << m_topic_toolInertia << std::endl;
156  }
164 
165  if ( m_verbose )
166  {
167  std::cout << "Advertise " << m_topic_jointStateCmd << std::endl;
168  std::cout << "Advertise " << m_topic_robotStateCmd << std::endl;
169  }
170  m_pub_jointStateCmd = n->advertise< sensor_msgs::JointState >( m_topic_jointStateCmd, 1 );
171  m_pub_robotStateCmd = n->advertise< std_msgs::Int32 >( m_topic_robotStateCmd, 1 );
172 
173  // Coppeliasim specific topic names
175  n->subscribe( "/simulationStepDone", 1, &vpROSRobotFrankaCoppeliasim::callbackSimulationStepDone, this );
177  n->subscribe( "/simulationTime", 1, &vpROSRobotFrankaCoppeliasim::callbackSimulationTime, this );
179  n->subscribe( "/simulationState", 1, &vpROSRobotFrankaCoppeliasim::callbackSimulationState, this );
180 
181  m_pub_startSimulation = n->advertise< std_msgs::Bool >( "/startSimulation", 1 );
182  m_pub_pauseSimulation = n->advertise< std_msgs::Bool >( "/pauseSimulation", 1 );
183  m_pub_stopSimulation = n->advertise< std_msgs::Bool >( "/stopSimulation", 1 );
184  m_pub_enableSyncMode = n->advertise< std_msgs::Bool >( "/enableSyncMode", 1 );
185  m_pub_triggerNextStep = n->advertise< std_msgs::Bool >( "/triggerNextStep", 1 );
186 
187  std::lock_guard< std::mutex > lock( m_mutex );
188  m_connected = true;
189  m_acquisitionThread = std::thread( [this] { readingLoop(); } );
190 
191  // Sleep a couple of ms to ensure thread is launched and topics are created
192  vpTime::sleepMs( 3000 );
193  std::cout << "ROS is initialized ? " << ( ros::isInitialized() ? "yes" : "no" ) << std::endl;
194 }
195 
208 void
210 {
211  std_msgs::Bool msg_enableSyncMode;
212  msg_enableSyncMode.data = enable;
213  m_pub_enableSyncMode.publish( msg_enableSyncMode );
214  m_syncModeEnabled = enable;
215  ros::Rate loop_rate( 1000. / sleep_ms );
216  loop_rate.sleep();
217 }
218 
228 void
230 {
231  std_msgs::Bool msg_pauseSimulation;
232  msg_pauseSimulation.data = true;
233  m_pub_pauseSimulation.publish( msg_pauseSimulation );
234  ros::Rate loop_rate( 1000. / sleep_ms );
235  loop_rate.sleep();
236 }
237 
247 void
249 {
250  std_msgs::Bool msg_startSimulation;
251  msg_startSimulation.data = true;
252  m_pub_startSimulation.publish( msg_startSimulation );
253  ros::Rate loop_rate( 1000. / sleep_ms );
254  loop_rate.sleep();
256 }
257 
267 void
269 {
270  std_msgs::Bool msg_stopSimulation;
271  msg_stopSimulation.data = true;
272  m_pub_stopSimulation.publish( msg_stopSimulation );
273  ros::Rate loop_rate( 1000. / sleep_ms );
274  loop_rate.sleep();
275 }
276 
286 void
288 {
289  std_msgs::Bool msg_triggerNextStep;
290  msg_triggerNextStep.data = true;
291  m_pub_triggerNextStep.publish( msg_triggerNextStep );
292 }
293 
298 void
300 {
301  std::lock_guard< std::mutex > lock( m_mutex );
302  m_simulationStepDone = msg.data;
303 }
304 
308 bool
310 {
311  std::lock_guard< std::mutex > lock( m_mutex );
312  return m_simulationStepDone;
313 }
314 
320 void
322 {
323  std::lock_guard< std::mutex > lock( m_mutex );
324  m_simulationStepDone = simulationStepDone;
325 }
326 
331 void
333 {
334  std::lock_guard< std::mutex > lock( m_mutex );
335  m_simulationTime = msg.data;
336 }
337 
341 double
343 {
344  std::lock_guard< std::mutex > lock( m_mutex );
345  return static_cast< double >( m_simulationTime );
346 }
347 
352 void
354 {
355  std::lock_guard< std::mutex > lock( m_mutex );
356  m_simulationState = msg.data;
357 }
358 
366 int
368 {
369  std::lock_guard< std::mutex > lock( m_mutex );
370  return m_simulationState;
371 }
372 
379 void
381 {
382  ros::Rate loop_rate( 500 ); // Hz
383 
384  while ( ros::ok() && m_connected )
385  {
386  loop_rate.sleep();
387  ros::spinOnce();
388  }
389 
390  std::lock_guard< std::mutex > lock( m_mutex );
391  m_connected = false;
392 }
393 
399 void
400 vpROSRobotFrankaCoppeliasim::callbackJointState( const sensor_msgs::JointState &joint_state )
401 {
402  std::lock_guard< std::mutex > lock( m_mutex );
403  for ( unsigned int i = 0; i < 7; i++ )
404  {
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]; // Using CoppeliaSim we need to inverse the sign
408  }
409 }
410 
417 void
418 vpROSRobotFrankaCoppeliasim::callback_g0( const geometry_msgs::Vector3 &g0_msg )
419 {
420  vpColVector g0( 3, 0 );
421  g0[0] = g0_msg.x;
422  g0[1] = g0_msg.y;
423  g0[2] = g0_msg.z;
424  this->set_g0( g0 );
425 }
426 
433 void
434 vpROSRobotFrankaCoppeliasim::callback_eMc( const geometry_msgs::Pose &pose_msg )
435 {
436  if ( !m_camMounted )
437  {
438  this->set_eMc( visp_bridge::toVispHomogeneousMatrix( pose_msg ) );
439  }
440 }
441 
450 void
451 vpROSRobotFrankaCoppeliasim::callback_flMe( const geometry_msgs::Pose &pose_msg )
452 {
454  {
455  this->set_flMe( visp_bridge::toVispHomogeneousMatrix( pose_msg ) );
456  m_overwrite_flMe = false;
457 
459  {
460  m_toolMounted = true;
461  if ( m_verbose )
462  {
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;
468  }
469  }
470  }
471 }
472 
482 void
483 vpROSRobotFrankaCoppeliasim::callback_toolInertia( const geometry_msgs::Inertia &inertia_msg )
484 {
485  std::lock_guard< std::mutex > lock( m_mutex );
487  {
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;
495 
496  vpMatrix R( 3, 3 );
497 
498  vpColVector eig;
499  m_Il.eigenValues( eig, R );
500 
501  m_Il = R.t() * m_Il * R;
502 
503  m_flMcom = vpHomogeneousMatrix( vpTranslationVector( inertia_msg.com.x, inertia_msg.com.y, inertia_msg.com.z ),
504  (vpRotationMatrix)R.t() );
505 
506  m_overwrite_toolInertia = false;
507 
509  {
510  m_toolMounted = true;
511  if ( m_verbose )
512  {
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;
518  }
519  }
520  }
521 }
522 
526 void
528 {
529  if ( m_verbose )
530  {
531  std::cout << "Position controller thread launched" << std::endl;
532  }
533  ros::NodeHandlePtr n = boost::make_shared< ros::NodeHandle >();
534  ros::Rate loop_rate( 500 ); // Hz
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++ )
540  {
541  joint_state_cmd_msg.name[i] = "J" + std::to_string( i );
542  }
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 };
545 
546  vpMatrix Kp( 7, 7 ), Kd( 7, 7 );
547 
548  gains = { 6.0, 6.0, 6.0, 6.0, 3.5, 2.5, 2.0 };
549  Kp.diag( gains );
550  gains = { 0.5, 0.5, 0.5, 0.5, 0.3, 0.25, 0.2 };
551  Kd.diag( gains );
552 
553  // Publish robot state to the corresponding ROS topic
554  std_msgs::Int32 robot_ctrl_type_msg;
555  robot_ctrl_type_msg.data = static_cast< int >( m_stateRobot );
557  robot_ctrl_type_msg ); // Should be published more than one time to be received by CoppeliaSim !
558 
560 
561  bool backup_sync_mode = m_syncModeEnabled;
562 
563  if ( backup_sync_mode )
564  {
565  setCoppeliasimSyncMode( false );
566  }
567 
569  {
570  loop_rate.sleep();
572  robot_ctrl_type_msg ); // Should be published more than one time to be received by CoppeliaSim !
573 
574  m_mutex.lock();
575  m_dq_des = Kp * 10. * ( m_q_des - m_q ) - Kd * m_dq;
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 )
578  {
579  for ( unsigned int i = 0; i < 7; i++ )
580  {
581  joint_state_cmd_msg.velocity[i] = dq_sat[i];
582  }
583  }
584  else
585  {
586  for ( unsigned int i = 0; i < 7; i++ )
587  {
588  joint_state_cmd_msg.velocity[i] = 0;
589  }
590  m_posControlNewCmd = false;
591  }
592 
593  m_mutex.unlock();
594  m_pub_jointStateCmd.publish( joint_state_cmd_msg );
595  }
596 
597  for ( unsigned int i = 0; i < 7; i++ )
598  {
599  joint_state_cmd_msg.velocity[i] = 0.;
600  }
601  m_pub_jointStateCmd.publish( joint_state_cmd_msg );
603 
604  if ( backup_sync_mode )
605  {
606  setCoppeliasimSyncMode( true );
607  }
608 
609  if ( m_verbose )
610  {
611  std::cout << "Position controller thread finished" << std::endl;
612  }
613 }
614 
618 void
620 {
621  if ( m_verbose )
622  {
623  std::cout << "Velocity controller thread launched" << std::endl;
624  }
625  ros::NodeHandlePtr n = boost::make_shared< ros::NodeHandle >();
626  ros::Rate loop_rate( 500 ); // Hz
627 
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++ )
633  {
634  joint_state_cmd_msg.name[i] = "J" + std::to_string( i );
635  }
636 
637  // Publish robot state to the corresponding ROS topic
638  std_msgs::Int32 robot_ctrl_type_msg;
639  robot_ctrl_type_msg.data = static_cast< int >( m_stateRobot );
641  robot_ctrl_type_msg ); // Should be published more than one time to be received by CoppeliaSim !
642 
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 };
645 
647 
648  while ( ros::ok() && !m_velControlThreadStopAsked )
649  {
650  loop_rate.sleep();
652  robot_ctrl_type_msg ); // Should be published more than one time to be received by CoppeliaSim !
653  m_mutex.lock();
654  dq_sat = vpRobot::saturateVelocities( m_dq_des, vel_max, true );
655  for ( unsigned int i = 0; i < 7; i++ )
656  {
657  joint_state_cmd_msg.velocity[i] = dq_sat[i];
658  }
659  m_mutex.unlock();
660  m_pub_jointStateCmd.publish( joint_state_cmd_msg );
661  }
662 
663  for ( unsigned int i = 0; i < 7; i++ )
664  {
665  joint_state_cmd_msg.velocity[i] = 0;
666  }
667  m_pub_jointStateCmd.publish( joint_state_cmd_msg );
669 
670  if ( m_verbose )
671  {
672  std::cout << "Velocity controller thread finished" << std::endl;
673  }
674 }
675 
679 void
681 {
682  if ( m_verbose )
683  {
684  std::cout << "Torque controller thread launched" << std::endl;
685  }
686  ros::NodeHandlePtr n = boost::make_shared< ros::NodeHandle >();
687  ros::Rate loop_rate( 500 ); // Hz
688 
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++ )
694  {
695  joint_state_cmd_msg.name[i] = "J" + std::to_string( i );
696  }
697 
698  // Publish robot state to the corresponding ROS topic
699  std_msgs::Int32 robot_ctrl_type_msg;
700  robot_ctrl_type_msg.data = static_cast< int >( m_stateRobot );
702  robot_ctrl_type_msg ); // Should be published more than one time to be received by CoppeliaSim !
703 
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 };
706 #ifdef VISP_HAVE_IIR
707  const int order = 1; // ex: 4th order (=2 biquads)
708  const double samplingrate = 1000.; // Hz
709  const double cutoff_frequency = 10.; // Hz
710  std::array< Iir::Butterworth::LowPass< order >, 7 > TorqueFilter;
711  for ( unsigned int i = 0; i < 7; i++ )
712  {
713  TorqueFilter[i].setup( samplingrate, cutoff_frequency );
714  }
715 #endif
716 
718 
719  while ( ros::ok() && !m_ftControlThreadStopAsked )
720  {
721  loop_rate.sleep();
723  robot_ctrl_type_msg ); // Should be published more than one time to be received by CoppeliaSim !
724  this->getGravity( g ); // as for the real robot, we compensate for the gravity
725  this->getFriction( f ); // this is to simulate the dynamic friction
726 
727  m_mutex.lock();
728  for ( unsigned int i = 0; i < 7; i++ )
729  {
730 #ifdef VISP_HAVE_IIR
731  m_tau_J_des_filt[i] = TorqueFilter[i].filter( m_tau_J_des[i] );
732  joint_state_cmd_msg.effort[i] = m_tau_J_des_filt[i] + g[i] - f[i];
733 #else
734  joint_state_cmd_msg.effort[i] = m_tau_J_des[i] + g[i] - f[i];
735 #endif
736  if ( m_verbose && std::abs( joint_state_cmd_msg.effort[i] ) > tau_max[i] )
737  {
738  std::cout << "Excess torque " << joint_state_cmd_msg.effort[i] << " axis nr. " << i << std::endl;
739  }
740  }
741  m_mutex.unlock();
742  m_pub_jointStateCmd.publish( joint_state_cmd_msg );
743  }
744 
745  for ( unsigned int i = 0; i < 7; i++ )
746  {
747  joint_state_cmd_msg.effort[i] = 0;
748  }
749  m_pub_jointStateCmd.publish( joint_state_cmd_msg );
751 
752  if ( m_verbose )
753  {
754  std::cout << "Torque controller thread finished" << std::endl;
755  }
756 }
757 
763 vpRobot::vpRobotStateType
764 vpROSRobotFrankaCoppeliasim::setRobotState( vpRobot::vpRobotStateType newState )
765 {
766  switch ( newState )
767  {
768  case vpRobot::STATE_STOP:
769  {
770  // Start primitive STOP only if the current state is velocity or force/torque
771  if ( vpRobot::STATE_POSITION_CONTROL == getRobotState() )
772  {
773  std::cout << "Change the control mode from position control to stop.\n";
774  m_mutex.lock();
776  m_mutex.unlock();
777  }
778  else if ( vpRobot::STATE_VELOCITY_CONTROL == getRobotState() )
779  {
780  std::cout << "Change the control mode from velocity control to stop.\n";
781  m_mutex.lock();
783  m_mutex.unlock();
784  }
785  else if ( vpRobot::STATE_FORCE_TORQUE_CONTROL == getRobotState() )
786  {
787  std::cout << "Change the control mode from force/torque control to stop.\n";
789  }
790 
791  if ( m_controlThread.joinable() )
792  {
793  m_controlThread.join();
794  m_mutex.lock();
801  m_mutex.unlock();
802  }
803  this->m_stateRobot = newState;
804  break;
805  }
806  case vpRobot::STATE_POSITION_CONTROL:
807  {
808  if ( vpRobot::STATE_STOP == getRobotState() )
809  {
810  std::cout << "Change the control mode from stop to position control.\n";
811  }
812  else if ( vpRobot::STATE_VELOCITY_CONTROL == getRobotState() )
813  {
814  std::cout << "Change the control mode from velocity to position control.\n";
815  // Stop the velocity control loop
816  m_mutex.lock();
818  m_mutex.unlock();
819  }
820  else if ( vpRobot::STATE_FORCE_TORQUE_CONTROL == getRobotState() )
821  {
822  std::cout << "Change the control mode from force/torque to position control.\n";
823  // Stop the force control loop
824  m_mutex.lock();
826  m_mutex.unlock();
827  }
828  if ( m_controlThread.joinable() )
829  {
830  m_controlThread.join();
831  m_mutex.lock();
836  m_mutex.unlock();
837  }
838  // m_controlThread = std::thread([this] {this->positionControlLoop();});
839  this->m_stateRobot = newState;
840  break;
841  }
842  case vpRobot::STATE_VELOCITY_CONTROL:
843  {
844  if ( vpRobot::STATE_STOP == getRobotState() )
845  {
846  std::cout << "Change the control mode from stop to velocity control.\n";
847  }
848  else if ( vpRobot::STATE_POSITION_CONTROL == getRobotState() )
849  {
850  std::cout << "Change the control mode from position to velocity control.\n";
851  m_mutex.lock();
853  m_mutex.unlock();
854  }
855  else if ( vpRobot::STATE_FORCE_TORQUE_CONTROL == getRobotState() )
856  {
857  std::cout << "Change the control mode from force/torque to velocity control.\n";
858  // Stop the force control loop
859  m_mutex.lock();
861  m_mutex.unlock();
862  }
863 
864  if ( getRobotState() != vpRobot::STATE_VELOCITY_CONTROL )
865  {
866  if ( m_controlThread.joinable() )
867  {
868  m_controlThread.join();
869  m_mutex.lock();
874  m_mutex.unlock();
875  }
876  }
878  {
879  m_controlThread = std::thread( [this] { this->velocityControlLoop(); } );
880  }
881  this->m_stateRobot = newState;
882  break;
883  }
884  case vpRobot::STATE_FORCE_TORQUE_CONTROL:
885  {
886  if ( vpRobot::STATE_STOP == getRobotState() )
887  {
888  std::cout << "Change the control mode from stop to force/torque control.\n";
889  }
890  else if ( vpRobot::STATE_POSITION_CONTROL == getRobotState() )
891  {
892  std::cout << "Change the control mode from position to force/torque control.\n";
894  }
895  else if ( vpRobot::STATE_VELOCITY_CONTROL == getRobotState() )
896  {
897  std::cout << "Change the control mode from velocity to force/torque control.\n";
898  m_mutex.lock();
900  m_mutex.unlock();
901  }
902  if ( getRobotState() != vpRobot::STATE_FORCE_TORQUE_CONTROL )
903  {
904  if ( m_controlThread.joinable() )
905  {
906  m_controlThread.join();
907  m_mutex.lock();
912  m_mutex.unlock();
913  }
914  }
916  {
917  m_controlThread = std::thread( [this] { this->torqueControlLoop(); } );
918  }
919  this->m_stateRobot = newState;
920  break;
921  }
922 
923  default:
924  break;
925  }
926 
927  return newState;
928 }
929 
946 void
947 vpROSRobotFrankaCoppeliasim::setPosition( const vpRobot::vpControlFrameType frame, const vpColVector &position )
948 {
949  vpRobotFrankaSim::setPosition( frame, position );
950 
951  m_posControlNewCmd = true;
952 
953  if ( vpRobot::STATE_POSITION_CONTROL == getRobotState() )
954  {
955  m_controlThread = std::thread( [this] { this->positionControlLoop(); } );
956 
957  if ( m_controlThread.joinable() )
958  {
959  m_controlThread.join();
960  }
961  }
962  else
963  {
964  std::cout << "Robot is not in position state control. "
965  << "You should call vpROSRobotFrankaCoppeliasim::setRobotState(vpRobot::STATE_POSITION_CONTROL)"
966  << std::endl;
967  }
968 }
969 
975 void
976 vpROSRobotFrankaCoppeliasim::wait( double timestamp_second, double duration_second )
977 {
978  ros::Rate loop_rate( 1000 ); // Hz
979  if ( m_syncModeEnabled )
980  {
982 
983  double epsilon = 0.0001; // 100 ns
984  do
985  {
988  {
989  loop_rate.sleep();
990  }
992 
993  } while ( getCoppeliasimSimulationTime() < timestamp_second + duration_second - epsilon );
994  }
995  else
996  {
997  while ( getCoppeliasimSimulationTime() < timestamp_second + duration_second )
998  {
999  loop_rate.sleep();
1000  }
1001  }
1002 }
vpRobotFrankaSim::m_q_des
vpColVector m_q_des
Definition: vpRobotFrankaSim.h:146
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_simulationState
ros::Subscriber m_sub_coppeliasim_simulationState
Definition: vpROSRobotFrankaCoppeliasim.h:263
vpROSRobotFrankaCoppeliasim::m_posControlNewCmd
std::atomic_bool m_posControlNewCmd
Definition: vpROSRobotFrankaCoppeliasim.h:236
vpROSRobotFrankaCoppeliasim::m_controlThread
std::thread m_controlThread
Definition: vpROSRobotFrankaCoppeliasim.h:216
vpROSRobotFrankaCoppeliasim::m_velControlThreadStopAsked
std::atomic_bool m_velControlThreadStopAsked
Definition: vpROSRobotFrankaCoppeliasim.h:240
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_simulationStepDone
ros::Subscriber m_sub_coppeliasim_simulationStepDone
Definition: vpROSRobotFrankaCoppeliasim.h:261
vpROSRobotFrankaCoppeliasim::m_simulationState
int m_simulationState
Definition: vpROSRobotFrankaCoppeliasim.h:269
vpRobotFrankaSim::m_toolMounted
bool m_toolMounted
Definition: vpRobotFrankaSim.h:122
epsilon
double epsilon
vpROSRobotFrankaCoppeliasim::coppeliasimPauseSimulation
void coppeliasimPauseSimulation(double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:229
vpROSRobotFrankaCoppeliasim::~vpROSRobotFrankaCoppeliasim
virtual ~vpROSRobotFrankaCoppeliasim()
Definition: vpROSRobotFrankaCoppeliasim.cpp:98
vpROSRobotFrankaCoppeliasim::m_connected
bool m_connected
Definition: vpROSRobotFrankaCoppeliasim.h:230
vpRobotFrankaSim::m_tau_J
vpColVector m_tau_J
Definition: vpRobotFrankaSim.h:116
boost::shared_ptr< NodeHandle >
vpROSRobotFrankaCoppeliasim::callbackSimulationTime
void callbackSimulationTime(const std_msgs::Float32 &msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:332
vpRobotFrankaSim::m_dq_des
vpColVector m_dq_des
Definition: vpRobotFrankaSim.h:148
vpROSRobotFrankaCoppeliasim::m_pub_stopSimulation
ros::Publisher m_pub_stopSimulation
Definition: vpROSRobotFrankaCoppeliasim.h:251
vpROSRobotFrankaCoppeliasim::callback_toolInertia
void callback_toolInertia(const geometry_msgs::Inertia &inertia_msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:483
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_jointState
ros::Subscriber m_sub_coppeliasim_jointState
Definition: vpROSRobotFrankaCoppeliasim.h:256
vpROSRobotFrankaCoppeliasim::m_posControlThreadIsRunning
std::atomic_bool m_posControlThreadIsRunning
Definition: vpROSRobotFrankaCoppeliasim.h:233
ros.h
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_toolInertia
ros::Subscriber m_sub_coppeliasim_toolInertia
Definition: vpROSRobotFrankaCoppeliasim.h:260
vpROSRobotFrankaCoppeliasim::callback_eMc
void callback_eMc(const geometry_msgs::Pose &pose_msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:434
vpRobotFrankaSim::getRobotState
vpRobot::vpRobotStateType getRobotState(void)
Definition: vpRobotFrankaSim.cpp:254
vpROSRobotFrankaCoppeliasim::m_pub_jointStateCmd
ros::Publisher m_pub_jointStateCmd
Definition: vpROSRobotFrankaCoppeliasim.h:247
vpROSRobotFrankaCoppeliasim::m_pub_startSimulation
ros::Publisher m_pub_startSimulation
Definition: vpROSRobotFrankaCoppeliasim.h:249
ros::spinOnce
ROSCPP_DECL void spinOnce()
vpROSRobotFrankaCoppeliasim::positionControlLoop
void positionControlLoop()
Definition: vpROSRobotFrankaCoppeliasim.cpp:527
vpROSRobotFrankaCoppeliasim::m_topic_flMcom
std::string m_topic_flMcom
Definition: vpROSRobotFrankaCoppeliasim.h:224
vpROSRobotFrankaCoppeliasim::m_acquisitionThread
std::thread m_acquisitionThread
Definition: vpROSRobotFrankaCoppeliasim.h:217
vpROSRobotFrankaCoppeliasim::vpROSRobotFrankaCoppeliasim
vpROSRobotFrankaCoppeliasim()
Definition: vpROSRobotFrankaCoppeliasim.cpp:52
vpRobotFrankaSim::m_q_kdl
KDL::JntArray m_q_kdl
Definition: vpRobotFrankaSim.h:133
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
vpROSRobotFrankaCoppeliasim::callback_flMe
void callback_flMe(const geometry_msgs::Pose &pose_msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:451
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_eMc
ros::Subscriber m_sub_coppeliasim_eMc
Definition: vpROSRobotFrankaCoppeliasim.h:258
ros::ok
ROSCPP_DECL bool ok()
vpROSRobotFrankaCoppeliasim::m_topic_g0
std::string m_topic_g0
Definition: vpROSRobotFrankaCoppeliasim.h:221
f
f
vpROSRobotFrankaCoppeliasim::m_simulationStepDone
bool m_simulationStepDone
Definition: vpROSRobotFrankaCoppeliasim.h:266
vpROSRobotFrankaCoppeliasim::setRobotState
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Definition: vpROSRobotFrankaCoppeliasim.cpp:764
vpROSRobotFrankaCoppeliasim::m_topic_flMe
std::string m_topic_flMe
Definition: vpROSRobotFrankaCoppeliasim.h:223
vpROSRobotFrankaCoppeliasim::wait
void wait(double timestamp_second, double duration_second)
Definition: vpROSRobotFrankaCoppeliasim.cpp:976
vpRobotFrankaSim::set_flMe
virtual void set_flMe(const vpHomogeneousMatrix &flMe)
Definition: vpRobotFrankaSim.cpp:172
vpROSRobotFrankaCoppeliasim::m_syncModeEnabled
bool m_syncModeEnabled
Definition: vpROSRobotFrankaCoppeliasim.h:268
vpROSRobotFrankaCoppeliasim.h
vpRobotFrankaSim::m_tau_J_des_filt
vpColVector m_tau_J_des_filt
Definition: vpRobotFrankaSim.h:153
vpROSRobotFrankaCoppeliasim::callbackSimulationState
void callbackSimulationState(const std_msgs::Int32 &msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:353
vpRobotFrankaSim::m_camMounted
bool m_camMounted
Definition: vpRobotFrankaSim.h:123
vpROSRobotFrankaCoppeliasim::coppeliasimStopSimulation
void coppeliasimStopSimulation(double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:268
vpROSRobotFrankaCoppeliasim::m_topic_robotStateCmd
std::string m_topic_robotStateCmd
Definition: vpROSRobotFrankaCoppeliasim.h:228
vpRobotFrankaSim::m_tau_J_des
vpColVector m_tau_J_des
Definition: vpRobotFrankaSim.h:152
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_simulationTime
ros::Subscriber m_sub_coppeliasim_simulationTime
Definition: vpROSRobotFrankaCoppeliasim.h:262
vpROSRobotFrankaCoppeliasim::m_pub_pauseSimulation
ros::Publisher m_pub_pauseSimulation
Definition: vpROSRobotFrankaCoppeliasim.h:250
3dpose.h
vpROSRobotFrankaCoppeliasim::readingLoop
void readingLoop()
Definition: vpROSRobotFrankaCoppeliasim.cpp:380
vpROSRobotFrankaCoppeliasim::setPosition
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Definition: vpROSRobotFrankaCoppeliasim.cpp:947
vpROSRobotFrankaCoppeliasim::m_simulationTime
float m_simulationTime
Definition: vpROSRobotFrankaCoppeliasim.h:267
ros::isInitialized
ROSCPP_DECL bool isInitialized()
vpROSRobotFrankaCoppeliasim::callbackSimulationStepDone
void callbackSimulationStepDone(const std_msgs::Bool &msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:299
vpRobotFrankaSim::m_mL
double m_mL
Definition: vpRobotFrankaSim.h:118
vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationTime
double getCoppeliasimSimulationTime()
Definition: vpROSRobotFrankaCoppeliasim.cpp:342
vpROSRobotFrankaCoppeliasim::m_posControlThreadStopAsked
std::atomic_bool m_posControlThreadStopAsked
Definition: vpROSRobotFrankaCoppeliasim.h:234
ros::Rate::sleep
bool sleep()
vpROSRobotFrankaCoppeliasim::coppeliasimStartSimulation
void coppeliasimStartSimulation(double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:248
vpRobotFrankaSim::m_q
vpColVector m_q
Definition: vpRobotFrankaSim.h:114
vpRobotFrankaSim::m_flMcom
vpHomogeneousMatrix m_flMcom
Definition: vpRobotFrankaSim.h:119
vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationState
int getCoppeliasimSimulationState()
Definition: vpROSRobotFrankaCoppeliasim.cpp:367
vpROSRobotFrankaCoppeliasim::m_pub_triggerNextStep
ros::Publisher m_pub_triggerNextStep
Definition: vpROSRobotFrankaCoppeliasim.h:252
vpRobotFrankaSim::getGravity
void getGravity(vpColVector &gravity)
Definition: vpRobotFrankaSim.cpp:1030
vpROSRobotFrankaCoppeliasim::torqueControlLoop
void torqueControlLoop()
Definition: vpROSRobotFrankaCoppeliasim.cpp:680
vpROSRobotFrankaCoppeliasim::callbackJointState
void callbackJointState(const sensor_msgs::JointState &joint_state)
Definition: vpROSRobotFrankaCoppeliasim.cpp:400
vpROSRobotFrankaCoppeliasim::m_topic_eMc
std::string m_topic_eMc
Definition: vpROSRobotFrankaCoppeliasim.h:222
vpROSRobotFrankaCoppeliasim::m_overwrite_toolInertia
bool m_overwrite_toolInertia
Definition: vpROSRobotFrankaCoppeliasim.h:271
vpRobotFrankaSim::m_verbose
bool m_verbose
Definition: vpRobotFrankaSim.h:158
vpROSRobotFrankaCoppeliasim::velocityControlLoop
void velocityControlLoop()
Definition: vpROSRobotFrankaCoppeliasim.cpp:619
vpROSRobotFrankaCoppeliasim::coppeliasimTriggerNextStep
void coppeliasimTriggerNextStep()
Definition: vpROSRobotFrankaCoppeliasim.cpp:287
vpROSRobotFrankaCoppeliasim::setCoppeliasimSyncMode
void setCoppeliasimSyncMode(bool enable, double sleep_ms=1000.)
Definition: vpROSRobotFrankaCoppeliasim.cpp:209
vpROSRobotFrankaCoppeliasim::m_topic_jointStateCmd
std::string m_topic_jointStateCmd
Definition: vpROSRobotFrankaCoppeliasim.h:227
vpROSRobotFrankaCoppeliasim::m_topic_toolInertia
std::string m_topic_toolInertia
Definition: vpROSRobotFrankaCoppeliasim.h:225
vpROSRobotFrankaCoppeliasim::m_overwrite_flMe
bool m_overwrite_flMe
Definition: vpROSRobotFrankaCoppeliasim.h:273
vpRobotFrankaSim::m_Il
vpMatrix m_Il
Definition: vpRobotFrankaSim.h:120
vpRobotFrankaSim::m_stateRobot
vpRobot::vpRobotStateType m_stateRobot
Definition: vpRobotFrankaSim.h:144
vpRobotFrankaSim::set_g0
virtual void set_g0(const vpColVector &g0)
Definition: vpRobotFrankaSim.cpp:205
vpROSRobotFrankaCoppeliasim::callback_g0
void callback_g0(const geometry_msgs::Vector3 &g0_msg)
Definition: vpROSRobotFrankaCoppeliasim.cpp:418
vpRobotFrankaSim::setPosition
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Definition: vpRobotFrankaSim.cpp:505
vpRobotFrankaSim::getFriction
void getFriction(vpColVector &friction)
Definition: vpRobotFrankaSim.cpp:144
ros::Rate
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_flMe
ros::Subscriber m_sub_coppeliasim_flMe
Definition: vpROSRobotFrankaCoppeliasim.h:259
vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationStepDone
bool getCoppeliasimSimulationStepDone()
Definition: vpROSRobotFrankaCoppeliasim.cpp:309
vpROSRobotFrankaCoppeliasim::setCoppeliasimSimulationStepDone
void setCoppeliasimSimulationStepDone(bool simulationStepDone)
Definition: vpROSRobotFrankaCoppeliasim.cpp:321
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_g0
ros::Subscriber m_sub_coppeliasim_g0
Definition: vpROSRobotFrankaCoppeliasim.h:257
vpROSRobotFrankaCoppeliasim::m_ftControlThreadIsRunning
std::atomic_bool m_ftControlThreadIsRunning
Definition: vpROSRobotFrankaCoppeliasim.h:243
vpROSRobotFrankaCoppeliasim::connect
void connect(const std::string &robot_ID="")
Definition: vpROSRobotFrankaCoppeliasim.cpp:132
vpROSRobotFrankaCoppeliasim::m_pub_robotStateCmd
ros::Publisher m_pub_robotStateCmd
Definition: vpROSRobotFrankaCoppeliasim.h:248
vpROSRobotFrankaCoppeliasim::m_pub_enableSyncMode
ros::Publisher m_pub_enableSyncMode
Definition: vpROSRobotFrankaCoppeliasim.h:253
vpROSRobotFrankaCoppeliasim::m_ftControlThreadStopAsked
std::atomic_bool m_ftControlThreadStopAsked
Definition: vpROSRobotFrankaCoppeliasim.h:244
visp_bridge::toVispHomogeneousMatrix
vpHomogeneousMatrix toVispHomogeneousMatrix(const geometry_msgs::Pose &pose)
vpRobotFrankaSim::set_eMc
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition: vpRobotFrankaSim.cpp:157
vpRobotFrankaSim::m_mutex
std::mutex m_mutex
Definition: vpRobotFrankaSim.h:127
vpROSRobotFrankaCoppeliasim::m_topic_jointState
std::string m_topic_jointState
Definition: vpROSRobotFrankaCoppeliasim.h:220
vpRobotFrankaSim::m_dq
vpColVector m_dq
Definition: vpRobotFrankaSim.h:115
vpROSRobotFrankaCoppeliasim::m_velControlThreadIsRunning
std::atomic_bool m_velControlThreadIsRunning
Definition: vpROSRobotFrankaCoppeliasim.h:239


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