vpROSRobotFrankaCoppeliasim.h
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 #ifndef vpROSRobotFrankaCoppeliasim_h
39 #define vpROSRobotFrankaCoppeliasim_h
40 
41 #include <ros/ros.h>
42 
43 #include <geometry_msgs/Inertia.h>
44 #include <geometry_msgs/Pose.h>
45 #include <sensor_msgs/JointState.h>
46 #include <std_msgs/Bool.h>
47 #include <std_msgs/Float32.h>
48 #include <std_msgs/Int32.h>
49 
50 #include <visp3/core/vpConfig.h>
51 
53 
88 {
89 public:
91  virtual ~vpROSRobotFrankaCoppeliasim();
92 
93  void connect( const std::string &robot_ID = "");
94 
95  void coppeliasimPauseSimulation( double sleep_ms = 1000. );
96  void coppeliasimStartSimulation( double sleep_ms = 1000. );
97  void coppeliasimStopSimulation( double sleep_ms = 1000. );
98  void coppeliasimTriggerNextStep();
99 
100  double getCoppeliasimSimulationTime();
101  bool getCoppeliasimSimulationStepDone();
102  int getCoppeliasimSimulationState();
103 
110  inline bool getCoppeliasimSyncMode() { return m_syncModeEnabled; }
111 
115  inline bool isConnected() const { return m_connected; }
116 
117  void setCoppeliasimSyncMode( bool enable, double sleep_ms = 1000. );
118 
119  void setPosition( const vpRobot::vpControlFrameType frame,
120  const vpColVector &position );
121 
122  vpRobot::vpRobotStateType setRobotState( vpRobot::vpRobotStateType newState );
123 
130  inline void setTopicJointState( const std::string &topic_jointState )
131  {
132  m_topic_jointState = topic_jointState;
133  }
134 
141  inline void setTopicJointStateCmd( const std::string &topic_jointStateCmd )
142  {
143  m_topic_jointStateCmd = topic_jointStateCmd;
144  }
145 
152  inline void setTopicRobotStateCmd( const std::string &topic_robotState )
153  {
154  m_topic_robotStateCmd = topic_robotState;
155  }
156 
163  inline void setTopic_g0( const std::string &topic_g0 ) { m_topic_g0 = topic_g0; }
164 
171  inline void setTopic_eMc( const std::string &topic_eMc ) { m_topic_eMc = topic_eMc; }
172 
179  inline void setTopic_flMe( const std::string &topic_flMe ) { m_topic_flMe = topic_flMe; }
180 
187  inline void setTopic_flMcom( const std::string &topic_flMcom ) { m_topic_flMcom = topic_flMcom; }
188 
194  inline void setTopic_toolInertia( const std::string &topic_toolInertia ) { m_topic_toolInertia = topic_toolInertia; }
195 
196  void setCoppeliasimSimulationStepDone( bool simulationStepDone );
197 
198  void wait( double timestamp_second, double duration_second );
199 
200 protected:
201  void callbackJointState( const sensor_msgs::JointState &joint_state );
202  void callback_g0( const geometry_msgs::Vector3 &g0_msg );
203  void callback_eMc( const geometry_msgs::Pose &pose_msg );
204  void callback_flMe( const geometry_msgs::Pose &pose_msg );
205  void callback_toolInertia( const geometry_msgs::Inertia &inertia_msg );
206  void callbackSimulationStepDone( const std_msgs::Bool &msg );
207  void callbackSimulationTime( const std_msgs::Float32 &msg );
208  void callbackSimulationState( const std_msgs::Int32 &msg );
209 
210  void readingLoop();
211 
212  void positionControlLoop();
213  void torqueControlLoop();
214  void velocityControlLoop();
215 
216  std::thread m_controlThread;
217  std::thread m_acquisitionThread;
218 
219  // Subscribed topics updated by Coppeliasim
220  std::string m_topic_jointState;
221  std::string m_topic_g0;
222  std::string m_topic_eMc;
223  std::string m_topic_flMe;
224  std::string m_topic_flMcom;
225  std::string m_topic_toolInertia;
226  // Published topics to update Coppeliasim
229 
231 
232  // Position controller
233  std::atomic_bool m_posControlThreadIsRunning;
234  std::atomic_bool m_posControlThreadStopAsked;
235  std::atomic_bool m_posControlLock;
236  std::atomic_bool m_posControlNewCmd;
237 
238  // Velocity controller
239  std::atomic_bool m_velControlThreadIsRunning;
240  std::atomic_bool m_velControlThreadStopAsked;
241 
242  // Force/torque controller
243  std::atomic_bool m_ftControlThreadIsRunning;
244  std::atomic_bool m_ftControlThreadStopAsked;
245 
246  // Publisher
254 
255  // Subscriber
264 
265  // Simulation
270 
271  bool m_overwrite_toolInertia; // Flag to indicate that the inertia parameters of the tool should no more be updated
272  // from topic
273  bool m_overwrite_flMe; // Flag to indicate that flMe should no more be updated from topic
274 };
275 
276 #endif
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
ros::Publisher
vpROSRobotFrankaCoppeliasim::m_simulationState
int m_simulationState
Definition: vpROSRobotFrankaCoppeliasim.h:269
vpROSRobotFrankaCoppeliasim::m_connected
bool m_connected
Definition: vpROSRobotFrankaCoppeliasim.h:230
vpROSRobotFrankaCoppeliasim::setTopic_flMe
void setTopic_flMe(const std::string &topic_flMe)
Definition: vpROSRobotFrankaCoppeliasim.h:179
vpROSRobotFrankaCoppeliasim::m_pub_stopSimulation
ros::Publisher m_pub_stopSimulation
Definition: vpROSRobotFrankaCoppeliasim.h:251
vpRobotFrankaSim
Definition: vpRobotFrankaSim.h:67
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::setTopicJointState
void setTopicJointState(const std::string &topic_jointState)
Definition: vpROSRobotFrankaCoppeliasim.h:130
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
vpROSRobotFrankaCoppeliasim
Definition: vpROSRobotFrankaCoppeliasim.h:87
vpROSRobotFrankaCoppeliasim::m_topic_flMcom
std::string m_topic_flMcom
Definition: vpROSRobotFrankaCoppeliasim.h:224
vpROSRobotFrankaCoppeliasim::m_acquisitionThread
std::thread m_acquisitionThread
Definition: vpROSRobotFrankaCoppeliasim.h:217
wait
void wait(int seconds)
vpROSRobotFrankaCoppeliasim::setTopic_eMc
void setTopic_eMc(const std::string &topic_eMc)
Definition: vpROSRobotFrankaCoppeliasim.h:171
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_eMc
ros::Subscriber m_sub_coppeliasim_eMc
Definition: vpROSRobotFrankaCoppeliasim.h:258
vpROSRobotFrankaCoppeliasim::m_topic_g0
std::string m_topic_g0
Definition: vpROSRobotFrankaCoppeliasim.h:221
vpROSRobotFrankaCoppeliasim::m_simulationStepDone
bool m_simulationStepDone
Definition: vpROSRobotFrankaCoppeliasim.h:266
vpROSRobotFrankaCoppeliasim::m_topic_flMe
std::string m_topic_flMe
Definition: vpROSRobotFrankaCoppeliasim.h:223
vpROSRobotFrankaCoppeliasim::m_syncModeEnabled
bool m_syncModeEnabled
Definition: vpROSRobotFrankaCoppeliasim.h:268
vpROSRobotFrankaCoppeliasim::m_topic_robotStateCmd
std::string m_topic_robotStateCmd
Definition: vpROSRobotFrankaCoppeliasim.h:228
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
vpROSRobotFrankaCoppeliasim::m_simulationTime
float m_simulationTime
Definition: vpROSRobotFrankaCoppeliasim.h:267
vpROSRobotFrankaCoppeliasim::setTopic_g0
void setTopic_g0(const std::string &topic_g0)
Definition: vpROSRobotFrankaCoppeliasim.h:163
vpROSRobotFrankaCoppeliasim::getCoppeliasimSyncMode
bool getCoppeliasimSyncMode()
Definition: vpROSRobotFrankaCoppeliasim.h:110
vpROSRobotFrankaCoppeliasim::m_posControlThreadStopAsked
std::atomic_bool m_posControlThreadStopAsked
Definition: vpROSRobotFrankaCoppeliasim.h:234
vpROSRobotFrankaCoppeliasim::isConnected
bool isConnected() const
Definition: vpROSRobotFrankaCoppeliasim.h:115
vpROSRobotFrankaCoppeliasim::m_pub_triggerNextStep
ros::Publisher m_pub_triggerNextStep
Definition: vpROSRobotFrankaCoppeliasim.h:252
vpROSRobotFrankaCoppeliasim::setTopicRobotStateCmd
void setTopicRobotStateCmd(const std::string &topic_robotState)
Definition: vpROSRobotFrankaCoppeliasim.h:152
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
vpROSRobotFrankaCoppeliasim::setTopic_flMcom
void setTopic_flMcom(const std::string &topic_flMcom)
Definition: vpROSRobotFrankaCoppeliasim.h:187
vpROSRobotFrankaCoppeliasim::m_topic_jointStateCmd
std::string m_topic_jointStateCmd
Definition: vpROSRobotFrankaCoppeliasim.h:227
vpRobotFrankaSim.h
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
vpROSRobotFrankaCoppeliasim::setTopic_toolInertia
void setTopic_toolInertia(const std::string &topic_toolInertia)
Definition: vpROSRobotFrankaCoppeliasim.h:194
vpROSRobotFrankaCoppeliasim::m_posControlLock
std::atomic_bool m_posControlLock
Definition: vpROSRobotFrankaCoppeliasim.h:235
vpRobotFrankaSim::setPosition
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Definition: vpRobotFrankaSim.cpp:505
vpROSRobotFrankaCoppeliasim::m_sub_coppeliasim_flMe
ros::Subscriber m_sub_coppeliasim_flMe
Definition: vpROSRobotFrankaCoppeliasim.h:259
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::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
ros::Subscriber
vpROSRobotFrankaCoppeliasim::setTopicJointStateCmd
void setTopicJointStateCmd(const std::string &topic_jointStateCmd)
Definition: vpROSRobotFrankaCoppeliasim.h:141
vpROSRobotFrankaCoppeliasim::m_topic_jointState
std::string m_topic_jointState
Definition: vpROSRobotFrankaCoppeliasim.h:220
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