ZeroMQ remote API
The ZeroMQ remote API is one of several ways an application can connect with CoppeliaSim.
The ZeroMQ remote API allows to control a simulation (or the simulator itself) from an external application or a remote hardware (e.g. real robot, remote computer, etc.). It offers all API functions also available via a CoppeliaSim script: this includes all regular API functions (i.e. sim.* -type functions), but also all API functions provided by plugins (e.g. simOMPL.*, simUI.*, simIK.*, etc.), if enabled.
The ZeroMQ remote API functions are interacting with CoppeliaSim via ZeroMQ and its interface plugin to CoppeliaSim and the ZMQ remote API add-on. All this happens in a hidden fashion to the user. The remote API can let one or several external applications interact with CoppeliaSim in a stepped (i.e. synchronized with each simulation step) or non-stepped way (i.e. the normal operation mode), and even remote control of the simulator is supported (e.g. remotely loading a scene, starting, pausing or stopping a simulation for instance).
Note: the Python ZeroMQ remote API also runs on CoppeliaSim V4.2, if you follow this procedure: clone the ZeroMQ remote API repository into your CoppeliaSim/programming folder. Then use the simAddOnZMQ remote API.lua compatibility add-on and the cbor.lua script, and place them into your CoppeliaSim/ and CoppeliaSim/Lua folders respectively.
See programming/zmqRemoteApi folder or its related repository for examples.
Python client
ZeroMQ and CBOR are required packages:
$ /path/to/python -m pip install pyzmq
$ /path/to/python -m pip install cbor
It is also helpful to have the location of the Python remote API items in either Python's sys.path, or in the PYTHONPATH environment variable:
$ export PYTHONPATH=/path/to/zmqRemoteApi/clients/python
Following is a very simple example ZeroMQ remote API client code, which starts then runs a stepped simulation for 3 seconds:
import time
from zmqRemoteApi import RemoteAPIClient
client = RemoteAPIClient()
sim = client.getObject('sim')
client.setStepping(True)
sim.startSimulation()
while (t := sim.getSimulationTime()) < 3:
s = f'Simulation time: {t:.2f} [s]'
print(s)
client.step()
sim.stopSimulation()
C++ client
Any C++ client requires the jsoncons and cppzmq package: those are automatically downloaded and used when compiling via cmake. For details see programming/zmqRemoteApi/clients/cpp/, which contains several examples.
Build them with:
$ mkdir build
$ cd build
$ cmake -DGENERATE=OFF ..
$ cmake --build . --config Release
Following is a very simple C++ ZeroMQ remote API client code, which starts then runs a stepped simulation for 3 seconds:
#include "RemoteAPIClient.h"
int main(int argc,char* argv[])
{
RemoteAPIClient client;
auto sim = client.getObject().sim();
client.setStepping(true);
sim.startSimulation();
double t=0.0;
do
{
t=sim.getSimulationTime();
printf("Simulation time: %.2f [s]\n",t);
client.step();
} while (t<3.0);
sim.stopSimulation();
return(0);
}
Matlab & Octave clients
Matlab clients require the bundled JeroMQ, which installs automatically if not yet present.
Octave clients require Octave 6.4+, the octave communications and zeromq packages. Those can be installed with:
pkg install -forge communications
pkg install -forge zeromq
Following is a very simple Matlab/Octave ZeroMQ remote API client code, which starts then runs a stepped simulation for 3 seconds:
client = RemoteAPIClient();
sim = client.getObject('sim');
client.setStepping(true);
sim.startSimulation();
while true
t = sim.getSimulationTime();
if t >= 3; break; end
fprintf('Simulation time: %.2f [s]\n', t);
client.step();
end
sim.stopSimulation();
Lua client
Currently, a Lua client is only supported from within a CoppeliaSim script, e.g. in order to connect 2 or more CoppeliaSim instances.
Following is a very simple Lua ZeroMQ remote API client code, which synchronizes the simulation steps with another CoppeliaSim instance:
function sysCall_init()
remoteApiClient=require'luaZmqRemoteApi'
remoteApiClient.init('127.0.0.1',23002)
simx=remoteApiClient.getObject('sim')
remoteApiClient.setStepping(true)
simx.startSimulation()
end
function sysCall_sensing()
remoteApiClient.step()
end
function sysCall_cleanup()
simx.stopSimulation()
remoteApiClient.cleanup()
end
|