Messaging/interfaces/connectivity

There are several ways messages or data can be exchanged/transmitted/received in and around CoppeliaSim. One can exchange data within CoppeliaSim, via:

  • signals
  • custom data blocks
  • calling plugin functions
  • Data can also be exchanged with an external application, other computer, machine, etc., via:

  • calling script functions
  • ZMQ
  • ROS
  • the remote API
  • BlueZero
  • serial port
  • sockets


  • Signals

    Signals can be seen as global variables. They can be defined, redefined, read and cleared. For example:

    -- script 1 writes the data to string signal mySignalName:
    
    local myData={1,2,{"Hello","world",true,{value1=63,value2="aString"}}}
    sim.setStringSignal("mySignalName",sim.packTable(myData))
    -- script 2 reads the data from string signal mySignalName:
    
    local myData=sim.getStringSignal("mySignalName")
    if myData then
        myData=sim.unpackTable(myData)
    end

    Custom data blocks

    Custom data blocks is data that is stored inside of a scene object, or inside a scene. It can be used to store custom data to be saved together with a model or scene, but also as a means of communication. For example:

    -- script 1 writes the data to the scene:
    
    local myData={1,2,{"Hello","world",true,{value1=63,value2="aString"}}}
    sim.writeCustomDataBlock(sim.handle_scene,"myTag",sim.packTable(myData))
    -- script 2 reads the data from the scene:
    
    local myData=sim.readCustomDataBlock(sim.handle_scene,"myTag")
    if myData then
        myData=sim.unpackTable(myData)
    end

    Calling plugin functions

    Scripts can call specific plugin functions, so-called callback functions: in order to be able to do this, the plugin must first register its callback functions via simRegisterScriptFunction. This is a convenient mechanism to extend CoppeliaSim's functionality, but can also be used for complex data exchange between scripts and plugins. Following illustrates a very simple plugin function and its registration:

    void myCallbackFunc(SScriptCallBack* p)
    {
        int stack=p->stackID;
        CStackArray inArguments;
        inArguments.buildFromStack(stack);
    	
        if ( (inArguments.getSize()>0)&&inArguments.isString(0) )
        {
            std::string tmp("we received a string: ");
            tmp+=inArguments.getString(0);
            simAddLog("ABC",sim_verbosity_msgs,tmp.c_str());
    		
    		CStackArray outArguments;
    		outArguments.pushString("Hello to you too!");
    		outArguments.buildOntoStack(stack);
        }
        else
            simSetLastError("simABC.func","Not enough arguments or wrong arguments.");
    }
    
    // Somewhere in the plugin's initialization code:
    simRegisterScriptCallbackFunction("simABC.func@ABC","string reply=simABC.func(string inputStr)",myCallbackFunc);

    Calling script functions

    A script function can obviously be called from within the same script, but also:

  • across scripts (via sim.callScriptFunction)
  • from a plugin (via simCallScriptFunctionEx)
  • from a ROS client (via a callback mechanism)
  • or from a remote API client (via simxCallScriptFunction (legacy remote API) and simxCallScriptFunction (B0-based remote API)
  • The called script function can perform various tasks, then send back data to the caller. This is also a simple way to extend the functionality of an external application in a quick manner. It is however important that the called script doesn't perform lengthly tasks, otherwise everything will come to a halt (lengthly tasks should rather be triggered externally, and processed at an appropriate moment by the script itself when called from the regular system callbacks).


    ZMQ

    The ZeroMQ library, wrapped inside the ZMQ plugin, offers several API functions related to ZeroMQ messaging. Following illustrates a simple requester:

    function sysCall_init()
        corout=coroutine.create(coroutineMain)
    end
    
    function sysCall_actuation()
        if coroutine.status(corout)~='dead' then
            local ok,errorMsg=coroutine.resume(corout)
            if errorMsg then
                error(debug.traceback(corout,errorMsg),2)
            end
        end
    end
    
    function coroutineMain()
        printf('Connecting to hello world server...')
        context=simZMQ.ctx_new()
        requester=simZMQ.socket(context,simZMQ.REQ)
        simZMQ.connect(requester,'tcp://localhost:5555')
    
        for request_nbr=0,10 do
            print('-----------------------------------------')
            local data='Hello'
            printf('[requester] Sending "%s"...',data)
            simZMQ.send(requester,data,0)
            local rc,data=simZMQ.recv(requester,0)
            printf('[requester] Received "%s"',data)
        end
    end
    
    function sysCall_cleanup()
        simZMQ.close(requester)
        simZMQ.ctx_term(context)
    end

    And following would be the corresponding responder:

    function sysCall_init()
        corout=coroutine.create(coroutineMain)
    end
    
    function sysCall_actuation()
        if coroutine.status(corout)~='dead' then
            local ok,errorMsg=coroutine.resume(corout)
            if errorMsg then
                error(debug.traceback(corout,errorMsg),2)
            end
        end
    end
    
    function coroutineMain()
        context=simZMQ.ctx_new()
        responder=simZMQ.socket(context,simZMQ.REP)
        local rc=simZMQ.bind(responder,'tcp://*:5555')
        if rc~=0 then error('failed bind') end
        
        while true do
            local rc,data=simZMQ.recv(responder,0)
            printf('[responder] Received "%s"',data)
            data='World'
            printf('[responder] Sending "%s"...',data)
            simZMQ.send(responder,data,0)
        end
    end
    
    function sysCall_cleanup()
        simZMQ.close(responder)
        simZMQ.ctx_term(context)
    end

    ROS

    Using ROS or ROS2, one can communicate with the outside world, but also within CoppeliaSim. For example, a vision sensor ROS2 publisher could look like:

    function sysCall_init()
        visionSensor=sim.getObjectHandle('Vision_sensor')
    
        -- Enable an image publisher:
        pub=simROS2.createPublisher('/image', 'sensor_msgs/msg/Image')
        simROS2.publisherTreatUInt8ArrayAsString(pub)
    end
    
    function sysCall_sensing()
        -- Publish the image of the vision sensor:
        local img,w,h=sim.getVisionSensorCharImage(visionSensor)
        data={}
        data.header={stamp=simROS2.getTime(), frame_id='a'}
        data.height=h
        data.width=w
        data.encoding='rgb8'
        data.is_bigendian=1
        data.step=w*3
        data.data=img
        simROS2.publish(pub,data)
    end
    
    function sysCall_cleanup()
        simROS2.shutdownPublisher(pub)
    end

    The subscriber on the other hand could look like:

    function sysCall_init()
        -- Enable an image subscriber:
        sub=simROS2.createSubscription('/image', 'sensor_msgs/msg/Image', 'image_callback')
        simROS2.subscriptionTreatUInt8ArrayAsString(sub)
    end
    
    function image_callback(msg)
        -- Here we have received an image
    end
    
    function sysCall_cleanup()
        simROS2.shutdownSubscription(sub)
    end

    Remote API

    Using the legacy remote API, or the B0-based remote API, one can communicate with the outside world, but also within CoppeliaSim. For example, a Python legacy remote API client receiving and applying back a vision sensor image could look like:

    import sim
    from time import sleep
    clientID=sim.simxStart('127.0.0.1',19997,True,True,5000,5)
    if clientID!=-1:
        res,sensor1Handle=sim.simxGetObjectHandle(clientID,'VisionSensor1',sim.simx_opmode_oneshot_wait)
        res,sensor2Handle=sim.simxGetObjectHandle(clientID,'VisionSensor2',sim.simx_opmode_oneshot_wait)
    
        res,resolution,image=sim.simxGetVisionSensorImage(clientID,sensor1Handle,0,sim.simx_opmode_streaming)
        sim.simxStartSimulation(clientID,sim.simx_opmode_oneshot)
        while (sim.simxGetConnectionId(clientID)!=-1):
            res,resolution,image=sim.simxGetVisionSensorImage(clientID,sensor1Handle,0,sim.simx_opmode_buffer)
            if res==sim.simx_return_ok:
                res=sim.simxSetVisionSensorImage(clientID,sensor2Handle,image,0,sim.simx_opmode_oneshot)
            sleep(0.01)
        sim.simxFinish(clientID)

    The same example as above, but for a B0-based remote API client:

    import b0RemoteApi
    from time import sleep
    with b0RemoteApi.RemoteApiClient('b0RemoteApi_pythonClient','b0RemoteApi') as client:    
            
        def imageCallback(msg):
            client.simxSetVisionSensorImage(sensor2Handle[1],False,msg[2],client.simxDefaultPublisher())
        
        sensor1Handle=client.simxGetObjectHandle('VisionSensor1',client.simxServiceCall())
        sensor2Handle=client.simxGetObjectHandle('VisionSensor2',client.simxServiceCall())
        client.simxGetVisionSensorImage(sensor1Handle[1],False,client.simxDefaultSubscriber(imageCallback))
        client.simxStartSimulation(client.simxDefaultPublisher())
        while True: 
            client.simxSpinOnce()
            sleep(0.01)
        client.simxStopSimulation(client.simxDefaultPublisher())

    BlueZero

    Using BlueZero, one can communicate with the outside world, but also within CoppeliaSim. For example, a vision sensor publisher could look like:

    function sysCall_init()
        visionSensor=sim.getObjectHandle('Vision_sensor')
    
        -- Enable an image publisher:
        b0Node=simB0.nodeCreate('b0Node')
        pub=simB0.publisherCreate(b0Node,'image')
        simB0.nodeInit(b0Node)
    end
    
    function sysCall_sensing()
        -- Publish the image of the vision sensor:
        local msg=sim.getVisionSensorCharImage(visionSensor)
        simB0.publisherPublish(pub,msg)
    end
    
    function sysCall_cleanup()
        if b0Node then
            simB0.nodeCleanup(b0Node)
            simB0.publisherDestroy(pub)
            simB0.nodeDestroy(b0Node)
        end
    end

    The subscriber on the other hand could look like:

    function sysCall_init()
        -- Enable an image subscriber:
        b0Node=simB0.nodeCreate('b0Node')
        sub=simB0.subscriberCreate(b0Node,'image','image_callback')
        simB0.nodeInit(b0Node)
    end
    
    function image_callback(msg)
        -- Here we have received an image
    end
    
    function sysCall_sensing()
        simB0.nodeSpinOnce(b0Node)
    end
    
    function sysCall_cleanup()
        if b0Node then
            simB0.nodeCleanup(b0Node)
            simB0.subscriberDestroy(sub)
            simB0.nodeDestroy(b0Node)
        end
    end

    Serial port

    CoppeliaSim implements several serial port API functions.


    LuaSocket

    CoppeliaSim ships with the LuaSocket extension library. Following illustrates how to fetch a webpage:

    http=require('socket.http')
    page=http.request('http://www.google.com')