Go to the documentation of this file.
38 #ifndef vpROSRobotFrankaCoppeliasim_h
39 #define vpROSRobotFrankaCoppeliasim_h
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>
50 #include <visp3/core/vpConfig.h>
93 void connect(
const std::string &robot_ID =
"");
95 void coppeliasimPauseSimulation(
double sleep_ms = 1000. );
96 void coppeliasimStartSimulation(
double sleep_ms = 1000. );
97 void coppeliasimStopSimulation(
double sleep_ms = 1000. );
98 void coppeliasimTriggerNextStep();
100 double getCoppeliasimSimulationTime();
101 bool getCoppeliasimSimulationStepDone();
102 int getCoppeliasimSimulationState();
117 void setCoppeliasimSyncMode(
bool enable,
double sleep_ms = 1000. );
119 void setPosition(
const vpRobot::vpControlFrameType frame,
120 const vpColVector &position );
122 vpRobot::vpRobotStateType setRobotState( vpRobot::vpRobotStateType newState );
132 m_topic_jointState = topic_jointState;
143 m_topic_jointStateCmd = topic_jointStateCmd;
154 m_topic_robotStateCmd = topic_robotState;
163 inline void setTopic_g0(
const std::string &topic_g0 ) { m_topic_g0 = topic_g0; }
171 inline void setTopic_eMc(
const std::string &topic_eMc ) { m_topic_eMc = topic_eMc; }
179 inline void setTopic_flMe(
const std::string &topic_flMe ) { m_topic_flMe = topic_flMe; }
187 inline void setTopic_flMcom(
const std::string &topic_flMcom ) { m_topic_flMcom = topic_flMcom; }
194 inline void setTopic_toolInertia(
const std::string &topic_toolInertia ) { m_topic_toolInertia = topic_toolInertia; }
196 void setCoppeliasimSimulationStepDone(
bool simulationStepDone );
198 void wait(
double timestamp_second,
double duration_second );
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 );
212 void positionControlLoop();
213 void torqueControlLoop();
214 void velocityControlLoop();
ros::Subscriber m_sub_coppeliasim_simulationState
std::atomic_bool m_posControlNewCmd
std::thread m_controlThread
std::atomic_bool m_velControlThreadStopAsked
ros::Subscriber m_sub_coppeliasim_simulationStepDone
void setTopic_flMe(const std::string &topic_flMe)
ros::Publisher m_pub_stopSimulation
ros::Subscriber m_sub_coppeliasim_jointState
std::atomic_bool m_posControlThreadIsRunning
ros::Subscriber m_sub_coppeliasim_toolInertia
void setTopicJointState(const std::string &topic_jointState)
ros::Publisher m_pub_jointStateCmd
ros::Publisher m_pub_startSimulation
std::string m_topic_flMcom
std::thread m_acquisitionThread
void setTopic_eMc(const std::string &topic_eMc)
ros::Subscriber m_sub_coppeliasim_eMc
bool m_simulationStepDone
std::string m_topic_robotStateCmd
ros::Subscriber m_sub_coppeliasim_simulationTime
ros::Publisher m_pub_pauseSimulation
void setTopic_g0(const std::string &topic_g0)
bool getCoppeliasimSyncMode()
std::atomic_bool m_posControlThreadStopAsked
ros::Publisher m_pub_triggerNextStep
void setTopicRobotStateCmd(const std::string &topic_robotState)
bool m_overwrite_toolInertia
void setTopic_flMcom(const std::string &topic_flMcom)
std::string m_topic_jointStateCmd
std::string m_topic_toolInertia
void setTopic_toolInertia(const std::string &topic_toolInertia)
std::atomic_bool m_posControlLock
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
ros::Subscriber m_sub_coppeliasim_flMe
ros::Subscriber m_sub_coppeliasim_g0
std::atomic_bool m_ftControlThreadIsRunning
ros::Publisher m_pub_robotStateCmd
ros::Publisher m_pub_enableSyncMode
std::atomic_bool m_ftControlThreadStopAsked
void setTopicJointStateCmd(const std::string &topic_jointStateCmd)
std::string m_topic_jointState
std::atomic_bool m_velControlThreadIsRunning
visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33