Plugin tutorial

This tutorial describes how to write a plugin for CoppeliaSim. The CoppeliaSim scene file related to this tutorial is located in scenes/tutorials/BubbleRobExt. The plugin project files of this tutorial can be found here.

CoppeliaSim automatically loads all plugins that it can find in its folder (i.e. the installation folder, or the same folder as the one that contains coppeliaSim.exe) at program start-up. CoppeliaSim recognizes plugin files with following mask: "simExt*.dll" on Windows, "libsimExt*.dylib" on Mac OS and "libsimExt*.so" on Linux. Additionally a plugin's filename should not contain any underscore. The plugin file of this tutorial is simExtBubbleRob.dll. When testing it, make sure it was properly loaded at CoppeliaSim start-up: switch the console window to visible by unchecking the Hide console window item in the user settings dialog ([Menu bar --> Tools --> Settings]). This option is only available in the Windows version. On Mac, have a look at the system's console, and on Linux try to start CoppeliaSim from within a console. The console window should display something similar to this:


As you already understood, this plugin was written for BubbleRob from the BubbleRob tutorial. Load the related scene file (scenes/tutorials/BubbleRobExt/BubbleRobExt.ttt). The BubbleRob plugin adds 4 new script functions (custom script functions should follow the convention: "simXXX.YYY" for the name, e.g. simRob.start):

simBubble.create

Description Creates an instance of a BubbleRob controller in the plugin.
Lua
synopsis
int bubbleRobHandle=simBubble.create(table[2] motorJointHandles,int sensorHandle,table[2] backRelativeVelocities)
Lua
parameters
motorJointHandles: a table containing the handles of the left and right motor joints of the BubbleRob you wish to control.
sensorHandle: the handle of the proximity sensor or the BubbleRob you wish to control
backRelativeVelocities: when BubbleRob detects an obstacle, it will move backwards for some time. relativeBackVelocities[1] is the relative velocity of the left wheel when moving back. relativeBackVelocities[2] is the relative velocity of the right wheel when moving back
Lua
return values
result: -1 in case of an error, otherwise the handle of the plugin's BubbleRob controller.
Python
synopsis
int bubbleRobHandle=simBubble.create(list motorJointHandles,int sensorHandle,list backRelativeVelocities)

simBubble.destroy

Description Destroys an instance of a BubbleRob controller previously created with simBubble.create.
Lua
synopsis
bool result=simBubble.destroy(int bubbleRobHandle)
Lua
parameters
bubbleRobHandle: the handle of a BubbleRob instance previously returned from simBubble.create.
Lua
return values
result: false in case of an error
Python
synopsis
bool result=simBubble.destroy(int bubbleRobHandle)

simBubble.start

Description Sets a BubbleRob into an automatic movement mode
Lua
synopsis
bool result=simBubble.start(int bubbleRobHandle)
Lua
parameters
bubbleRobHandle: the handle of a BubbleRob instance previously returned from simBubble.create.
Lua
return values
result: false in case of an error
Python
synopsis
bool result=simBubble.start(int bubbleRobHandle)

simBubble.stop

Description Stops the automatic movement of a BubbleRob
Lua
synopsis
bool result=simBubble.stop(int bubbleRobHandle)
Lua
parameters
bubbleRobHandle: the handle of a BubbleRob instance previously returned from simBubble.create.
Lua
return values
result: false in case of an error
Python
synopsis
bool result=simBubble.stop(int bubbleRobHandle)

Now open the threaded child script attached to the BubbleRob model in the scene (e.g. double-click the script icon next to object bubbleRob in the scene hierarchy). Inspect the code:

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() -- Check if the required plugin is there: moduleName=0 moduleVersion=0 index=0 bubbleRobModuleNotFound=true while moduleName do moduleName,moduleVersion=sim.getModuleName(index) if (moduleName=='BubbleRob') then bubbleRobModuleNotFound=false end index=index+1 end if bubbleRobModuleNotFound then sim.addLog(sim.verbosity_scripterrors,'BubbleRob plugin was not found. Simulation will not run properly.') else local jointHandles={sim.getObject('./leftMotor'),sim.getObject('./rightMotor')} local sensorHandle=sim.getObject('./sensingNose') local robHandle=simBubble.create(jointHandles,sensorHandle,{0.5,0.25}) if robHandle>=0 then simBubble.start(robHandle) -- start the robot local st=sim.getSimulationTime() sim.wait(20) -- run for 20 seconds simBubble.stop(robHandle) simBubble.destroy(robHandle) end end end

The first part of the code is in charge of checking whether the plugin required to run this script (i.e. simExtBubbleRob.dll) is available (i.e. was found and successfully loaded). If not, an error message is displayed. Otherwise, joint and sensor handles are retrieved and given to the custom script function that creates a controller instance of our BubbleRob in the plugin. If the call was successfull, then we can call simBubble.start. The function instructs the plugin to move the BubbleRob model while avoiding obstacles. Run the simulation: BubbleRob moves for 20 seconds then stops, as expected. Now leave CoppeliaSim. Temporarily rename the plugin to TEMP_simExtBubbleRob.dll so that CoppeliaSim won't load it anymore, then start CoppeliaSim again. Load the previous scene and run the simulation: an error message now appears, indicating that the required plugin could not be found. Leave CoppeliaSim again, rename back the plugin to simExtBubbleRob.dll and start CoppeliaSim again.

Let's have a look at how the plugin registers and handles the above 4 custom Lua functions. Open the BubbleRob plugin project, and have a look at file simExtBubbleRob.cpp:

Notice the 3 required plugin entry points: simStart, simEnd, and simMessage: simStart is called once when the plugin is loaded (initialization), simEnd is called once when the plugin is unloaded (clean-up), and simMessage is called on a regular basis with several type of messages.

During the initialization phase, the plugin loads the CoppeliaSim library (in order to have access to all CoppeliaSim's API functions), then registers the 4 custom script functions. A custom script function is registered by specifying:

  • a function name
  • a calling tip string
  • a callback address
  • When a script calls the specified function name, then CoppeliaSim calls the callback address. The most difficult task inside of a callback function is to correctly read the input arguments, and correctly write the output values. To ease the task, two helper classes are used, that will be in charge of that: CScriptFunctionData and CScriptFunctionDataItem, located in programming/common and programming/include.

    When writing your own custom script functions, try to use the same code layout/skeleton as was done in file simExtBubbleRob.cpp.

    In general, callback routines should execute as fast as possible, and control should then be given back to CoppeliaSim, otherwise the whole simulator will halt.