#include <vpROSRobotFrankaCoppeliasim.h>
Public Member Functions | |
void | connect (const std::string &robot_ID="") |
void | coppeliasimPauseSimulation (double sleep_ms=1000.) |
void | coppeliasimStartSimulation (double sleep_ms=1000.) |
void | coppeliasimStopSimulation (double sleep_ms=1000.) |
void | coppeliasimTriggerNextStep () |
int | getCoppeliasimSimulationState () |
bool | getCoppeliasimSimulationStepDone () |
double | getCoppeliasimSimulationTime () |
bool | getCoppeliasimSyncMode () |
bool | isConnected () const |
void | setCoppeliasimSimulationStepDone (bool simulationStepDone) |
void | setCoppeliasimSyncMode (bool enable, double sleep_ms=1000.) |
void | setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &position) |
vpRobot::vpRobotStateType | setRobotState (vpRobot::vpRobotStateType newState) |
void | setTopic_eMc (const std::string &topic_eMc) |
void | setTopic_flMcom (const std::string &topic_flMcom) |
void | setTopic_flMe (const std::string &topic_flMe) |
void | setTopic_g0 (const std::string &topic_g0) |
void | setTopic_toolInertia (const std::string &topic_toolInertia) |
void | setTopicJointState (const std::string &topic_jointState) |
void | setTopicJointStateCmd (const std::string &topic_jointStateCmd) |
void | setTopicRobotStateCmd (const std::string &topic_robotState) |
vpROSRobotFrankaCoppeliasim () | |
void | wait (double timestamp_second, double duration_second) |
virtual | ~vpROSRobotFrankaCoppeliasim () |
Public Member Functions inherited from vpRobotFrankaSim | |
virtual void | add_tool (const vpHomogeneousMatrix &flMe, const double mL, const vpHomogeneousMatrix &flMcom, const vpMatrix &I_L) |
void | get_eJe (const vpColVector &q, vpMatrix &fJe) |
void | get_eJe (vpMatrix &eJe_) |
vpHomogeneousMatrix | get_eMc () const |
void | get_fJe (const vpColVector &q, vpMatrix &fJe) |
void | get_fJe (vpMatrix &fJe) |
vpHomogeneousMatrix | get_flMcom () const |
vpHomogeneousMatrix | get_flMe () const |
vpHomogeneousMatrix | get_fMe () |
vpHomogeneousMatrix | get_fMe (const vpColVector &q) |
double | get_tool_mass () const |
void | getCoriolis (vpColVector &coriolis) |
void | getCoriolisMatrix (vpMatrix &coriolis) |
virtual void | getForceTorque (const vpRobot::vpControlFrameType frame, vpColVector &force) |
void | getFriction (vpColVector &friction) |
void | getGravity (vpColVector &gravity) |
void | getMass (vpMatrix &mass) |
virtual void | getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position) |
virtual void | getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position) |
vpRobot::vpRobotStateType | getRobotState (void) |
virtual void | getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &d_position) |
virtual void | set_eMc (const vpHomogeneousMatrix &eMc) |
virtual void | set_flMe (const vpHomogeneousMatrix &flMe) |
virtual void | set_g0 (const vpColVector &g0) |
virtual void | setForceTorque (const vpRobot::vpControlFrameType frame, const vpColVector &force) |
virtual void | setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel) |
void | setVerbose (bool verbose) |
vpRobotFrankaSim () | |
virtual | ~vpRobotFrankaSim () |
Protected Member Functions | |
void | callback_eMc (const geometry_msgs::Pose &pose_msg) |
void | callback_flMe (const geometry_msgs::Pose &pose_msg) |
void | callback_g0 (const geometry_msgs::Vector3 &g0_msg) |
void | callback_toolInertia (const geometry_msgs::Inertia &inertia_msg) |
void | callbackJointState (const sensor_msgs::JointState &joint_state) |
void | callbackSimulationState (const std_msgs::Int32 &msg) |
void | callbackSimulationStepDone (const std_msgs::Bool &msg) |
void | callbackSimulationTime (const std_msgs::Float32 &msg) |
void | positionControlLoop () |
void | readingLoop () |
void | torqueControlLoop () |
void | velocityControlLoop () |
Protected Member Functions inherited from vpRobotFrankaSim | |
vpColVector | getVelDes () |
vpColVector | solveIK (const vpHomogeneousMatrix &edMw) |
This class does the connexion using ROS 1 between Franka robot simulator implemented in vpRobotFrankaSim and Coppeliasim simulator.
It subscribes to default topics emited and updated on Coppeliasim side:
/coppeliasim/franka/joint_state
topic that contains the robot joint state as sensor_msgs::JointState message. To change this topic name use setTopicJointState()./coppeliasim/franka/eMc
that contains the camera extrinsic homogeneous transformation from end-effector to camera frame as a geometry_msgs::Pose message.To change this topic name use setTopic_eMc().Given the type of command to apply to the simulated robot, it published default topics that are taken into account by Coppeliasim to update the robot state:
/fakeFCI/joint_state
topic that contains the command to apply to the robot as a sensor_msgs::JointState message. To change this topic name use setTopicJointStateCmd()./fakeFCI/robot_state
topic that contains the kind of robot control as a std_msgs::Int32 message. The values of this message should match the one in vpRobot::vpRobotStateType. To change this topic name use setTopicRobotStateCmd().Note that changing topic names should be achieved before calling connect().
If you decide to change the topic names, be aware that you should also change their names in Coppeliasim scene lua script.
Definition at line 87 of file vpROSRobotFrankaCoppeliasim.h.
vpROSRobotFrankaCoppeliasim::vpROSRobotFrankaCoppeliasim | ( | ) |
Default constructor.
Definition at line 52 of file vpROSRobotFrankaCoppeliasim.cpp.
|
virtual |
Destructor.
Definition at line 98 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that updates camera extrinsics with the transformation considered on Coppeliasim side.
[in] | pose_msg | : Message associated to the topic set by setTopic_eMc() that contains the homogeneous transformation between end-effector and camera frame. |
Definition at line 434 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that updates end-effector extrinsics w.r.t. the robot flange with the transformation considered on Coppeliasim side.
[in] | pose_msg | : Message associated to the topic set by setTopic_flMe() that contains the homogeneous transformation between end-effector and flange frame. This callback works jointly with the callback_toolInertia to automatically retrieve the kinematic and dynamic parameters of the tool. |
Definition at line 451 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that updates the gravitational acceleration vector as perceived at the robot's base considered on Coppeliasim side.
[in] | g0_msg | : Message associated to the topic set by setTopic_g0() the absolute acceleration vector in base frame. |
Definition at line 418 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that updates the tool inertial parameters.
[in] | inertia_msg | : Message associated to the topic set by setTopic_toolInertia() that contains the inertial parameters of the mounted tool as considered on Coppeliasim side. The inertia tensor must be specified in flange frame as well as the center of mass. This callback works jointly with the callback_flMe to automatically retrieve the kinematic and dynamic parameters of the tool. |
Definition at line 483 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that updates robot joint state (joint position, joint velocity, joint torque) with the values updated on Coppeliasim side.
[in] | joint_state | : Joint state message associated to the topic set by setTopicJointState(). |
Definition at line 400 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that allows to update the Coppeliasim simulation state.
[in] | msg | : Simulation state message. |
Definition at line 353 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that allows to know when a simulation step is done on Coppeliasim side.
[in] | msg | : Simulation step done message send by Coppeliasim |
Definition at line 299 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Callback that allows to update the Coppeliasim simulation time.
[in] | msg | : Simulation time message. |
Definition at line 332 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::connect | ( | const std::string & | robot_ID = "" | ) |
Connect to Coppeliasim simulator by subscribing to the requested topics.
It is possible to change the default topic names, before calling this function.
Definition at line 132 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::coppeliasimPauseSimulation | ( | double | sleep_ms = 1000. | ) |
Pause Coppeliasim simulation by publishing a std_msgs::Bool message on /pauseSimulation
topic.
[in] | sleep_ms | : Sleeping time in [ms] added after publishing the message to ensure that it will be taken into account by Coppeliasim. |
Definition at line 229 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::coppeliasimStartSimulation | ( | double | sleep_ms = 1000. | ) |
Start Coppeliasim simulation by publishing a a std_msgs::Bool message on /startSimulation
topic.
[in] | sleep_ms | : Sleeping time in [ms] added after publishing the message to ensure that it will be taken into account by Coppeliasim. |
Definition at line 248 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::coppeliasimStopSimulation | ( | double | sleep_ms = 1000. | ) |
Stop Coppeliasim simulation by publishing a std_msgs::Bool message on /stopSimulation
topic.
[in] | sleep_ms | : Sleeping time in [ms] added after publishing the message to ensure that it will be taken into account by Coppeliasim. |
Definition at line 268 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::coppeliasimTriggerNextStep | ( | ) |
Trigger Coppeliasim next simulation step by publishing a std_msgs::Bool message on /triggerNextStep
topic, while in the synchronous simulation mode.
Definition at line 287 of file vpROSRobotFrankaCoppeliasim.cpp.
int vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationState | ( | ) |
Return Coppeliasim simulation state. 0 indicates that the simulation is stopped, 1 that it is running and 2 that it is paused.
Definition at line 367 of file vpROSRobotFrankaCoppeliasim.cpp.
bool vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationStepDone | ( | ) |
Return true when a simulation step is done on Coppeliasim side, false otherwise.
Definition at line 309 of file vpROSRobotFrankaCoppeliasim.cpp.
double vpROSRobotFrankaCoppeliasim::getCoppeliasimSimulationTime | ( | ) |
Return Coppeliasim simulation time.
Definition at line 342 of file vpROSRobotFrankaCoppeliasim.cpp.
|
inline |
Get Coppeliasim synchronous mode.
Definition at line 110 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Return true when ROS connexion with Coppeliasim is established.
Definition at line 115 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Infinite loop launched when the control is done in position.
Definition at line 527 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Subscribes to topics updated on Coppeliasim side and runs an infinite loop that updates the robot state.
Definition at line 380 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::setCoppeliasimSimulationStepDone | ( | bool | simulationStepDone | ) |
Set Coppeliasim simulation step done flag.
[in] | simulationStepDone | : True to indicate that the simmulation step is done, false otherwise. |
Definition at line 321 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::setCoppeliasimSyncMode | ( | bool | enable, |
double | sleep_ms = 1000. |
||
) |
Enable/disable Coppeliasim synchronous simulation mode by publishing a std_msgs::Bool message on /enableSyncMode
topic.
[in] | enable | : Set true to enable synchronous simulation mode, false otherwise. When synchronous simulation mode is enable, you need to call coppeliasimTriggerNextStep() to run a new simulation step. |
[in] | sleep_ms | : Sleeping time in [ms] added after publishing the message to ensure that it will be taken into account by Coppeliasim. |
Definition at line 209 of file vpROSRobotFrankaCoppeliasim.cpp.
|
virtual |
Set robot position. This function is blocking and returns only when the desired position is reached.
[in] | frame | : Control frame to consider. |
[in] | position | : Position to reach.
|
Reimplemented from vpRobotFrankaSim.
Definition at line 947 of file vpROSRobotFrankaCoppeliasim.cpp.
vpRobot::vpRobotStateType vpROSRobotFrankaCoppeliasim::setRobotState | ( | vpRobot::vpRobotStateType | newState | ) |
Change robot state.
newState | : New robot state. |
Definition at line 764 of file vpROSRobotFrankaCoppeliasim.cpp.
|
inline |
Set topic name that contains eMc
corresponding to the end-effector to camera transformation.
topic_eMc | : Topic name. |
Definition at line 171 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Set topic name that contains flMcom
corresponding to the flange to Center-of-Mass transformation.
topic_flMcom | : Topic name. |
Definition at line 187 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Set topic name that contains flMe
corresponding to the flange to end-effector transformation.
topic_flMe | : Topic name. |
Definition at line 179 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Set topic name that contains g0
corresponding to the absolute acceleration vector at the robot's base.
topic_g0 | : Topic name. |
Definition at line 163 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Set topic name that contains the Inertia
parameters of the tool.
topic_toolInertia | : Topic name. |
Definition at line 194 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Set topic name that contains the robot state including position, velocity and effort for all the joints.
topic_jointState | : Topic name. |
Definition at line 130 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Name of the topic used to public joint state command that has to be applied to the robot.
topic_jointStateCmd | : Topic name. |
Definition at line 141 of file vpROSRobotFrankaCoppeliasim.h.
|
inline |
Set topic name that contains the robot controller state (stopped, position, velocity, force/torque).
topic_robotState | : Topic name. |
Definition at line 152 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Infinite loop launched when the control is done in joint torque.
Definition at line 680 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Infinite loop launched when the control is done in joint velocity.
Definition at line 619 of file vpROSRobotFrankaCoppeliasim.cpp.
void vpROSRobotFrankaCoppeliasim::wait | ( | double | timestamp_second, |
double | duration_second | ||
) |
Wait a given time in [s].
timestamp_second | : Simulation time in [s] used to start the chrono. |
duration_second | : Wait the given duration time in [s] since chrono is started |
Definition at line 976 of file vpROSRobotFrankaCoppeliasim.cpp.
|
protected |
Definition at line 217 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 230 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 216 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 243 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 244 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 273 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 271 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 235 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 236 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 233 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 234 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 253 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 247 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 250 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 248 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 249 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 251 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 252 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 269 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 266 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 267 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 258 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 259 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 257 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 256 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 263 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 261 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 262 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 260 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 268 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 222 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 224 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 223 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 221 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 220 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 227 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 228 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 225 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 239 of file vpROSRobotFrankaCoppeliasim.h.
|
protected |
Definition at line 240 of file vpROSRobotFrankaCoppeliasim.h.