Child scripts

V-REP supports an unlimited number of child scripts per scene. Each child script represents a small code or program written in Lua allowing handling a particular function in a simulation. Child scripts are attached to (or associated with) scene objects, and they can be easily recognized from their script icon in the scene hierarchy:

[A child script associated with object youBot]


Double-clicking the script icon allows opening the script editor. You can change properties of a given script, or associate it with another object via the script dialog. You can attach a new child script to an object by selecting the object, then navigating to [menu bar --> Add --> Associated child script].

A child script's association with a scene object has important and positive consequences:

  • Very good portability: child scripts will be saved/loaded together with their associated object. Using child scripts, you are able to create extremely portable code and simulation models that do not need to rely on any system specific plugin. A fully functional model can be contained in a single file (usable without modification across various platforms), which is not the case when relying on plugins for model control. Additionally, and for the same reason, models relying on child scripts require no maintenance over time (e.g. a new OS version will not require you to adjust portions of code or recompilation, as you might have to do when using plugins).
  • Inherent scalability: if a object that has an attached child script is duplicated, its child script will also be duplicated. The duplicated child script's content will be identical to the original child script's content, however, the duplicated child script will know that is was duplicated and redirect object access correctly (e.g. if the original child script is accessing "robot", then the duplicated child script will automatically append a name suffix to "robot" in order to access the duplicated "robot" and not the original one). Refer to the section on accessing general-type objects programmatically for more details. The automatic name suffix adjustment allows duplicating objects and behavior without having to rewrite / adjust any code.
  • No conflict between different model versions: if you modify the child script of a given model (e.g. to customize it to your needs), this will have no consequence on other similar models. This is a much more critical aspect when relying on plugins instead of child scripts for model control: indeed, with plugins you always run the risk of having conflicts with previous plugin versions.
  • Very easy synchronization with the simulation loop: child scripts can run threaded and non-threaded (see further down). And even the threaded version of child scripts can be easily synchronized with the simulation loop, which represents a powerful feature.
  • Child scripts are executed in a cascaded way: each child script is executed (i.e. called or handled) by a parent child script (i.e. a parent child script is a child script located further down (towards the root) in the current scene hierarchy). If a child script has no parent child script, then the main script is in charge of executing it. Refer to the API function simHandleChildScript(). Child scripts can be of two different types: non-threaded child scripts or threaded child scripts:

    [non-threaded child script icon (left), threaded child script icon (right)]


    Non-threaded child scripts

    Non-threaded child scripts are pass-through scripts. This means that every time they are called, they should perform some task and then return control to the calling script. If control is not returned to the calling script, then the whole simulation halts. They operate as functions, and normally, non-threaded child scripts are called at each simulation step (each time with a different simulation time). This type of child script should always be used over threaded child scripts whenever possible.

    Imagine an example of a simulation model representing an automatic door: a proximity sensor in the front and the back allows detecting an approaching person. When the person is close enough, the door opens automatically. Following code shows a typical non-threaded child script illustrating above example:

    if (simGetScriptExecutionCount()==0) then
        sensorHandleFront=simGetObjectHandle("DoorSensorFront")
        sensorHandleBack=simGetObjectHandle("DoorSensorBack")
        motorHandle=simGetObjectHandle("DoorMotor")
    end
    
    simHandleChildScript(sim_handle_all_except_explicit) -- make sure children are executed!
    
    resF=simReadProximitySensor(sensorHandleFront)
    resB=simReadProximitySensor(sensorHandleBack)
    if ((resF>0)or(resB>0)) then
        simSetJointTargetVelocity(motorHandle,-0.2)
    else
        simSetJointTargetVelocity(motorHandle,0.2)
    end
    
    if (simGetSimulationState()==sim_simulation_advancing_lastbeforestop) then
        -- Put some restoration code here
    end

    A non-threaded child script should be segmented in 3 parts:

  • the initialization part: this part will be executed just one time (the first time the child script is called). This can be at the beginning of a simulation, but also in the middle of a simulation: remember that child scripts can be copy/pasted into a scene at any time, also when a simulation is running. Usually you would put some initialization code as well as handle retrieval in this part.
  • the regular part: this part will be executed at each simulation pass. The code is in charge of handling a specific part of a simulation (e.g. handle the automatic sliding door). One command is of particular interest: simHandleChildScript(sim_handle_all_except_explicit); this line of code guarantees that if an object associated with a child script is attached to the current tree hierarchy, that the attached child script will also be executed (child script execution is cascaded).
  • the restoration part: this part will be executed one time just before a simulation ends. If the object associated with the child script is erased before the end of the simulation, this part won't be executed.



  • Threaded child scripts

    Threaded child scripts are scripts that will launch in a thread. This means that a call to a threaded child script will launch a new thread and then directly return. The new thread will then execute in parallel. When a threaded child script was already launched (and didn't end yet) but is called again, then the call is ignored. An execute once option is set by default. There can be as many threaded child scripts running as needed. A threaded child script icon in the scene hierarchy is displayed in light blue instead of white to indicate that it will be launched in a thread.

    Threaded child scripts can in their turn call non-threaded as well as threaded child scripts. When a non-threaded child script is called from a thread that is not the main thread, then the child script is said to be running in a thread (i.e. it didn't launch the thread, one of the callers did). The corresponding API function is simIsScriptRunningInThread. See also simIsScriptExecutionThreaded. Threaded child scripts have several weaknesses compared to non-threaded child scripts if not programmed appropriately: they are more resource-intensive, they can waste some processing time, and they can be a little bit less responsive to a simulation stop command.

    Following shows a typical threaded child script code (the code handles the automatic sliding doors from above's example):

    simDelegateChildScriptExecution()
    sensorHandleFront=simGetObjectHandle("DoorSensorFront")
    sensorHandleBack=simGetObjectHandle("DoorSensorBack")
    motorHandle=simGetObjectHandle("DoorMotor")
    
    while (simGetSimulationState()~=sim_simulation_advancing_abouttostop) do
        resF=simReadProximitySensor(sensorHandleFront)
        resB=simReadProximitySensor(sensorHandleBack)
        if ((resF>0)or(resB>0)) then
            simSetJointTargetVelocity(motorHandle,-0.2)
        else
            simSetJointTargetVelocity(motorHandle,0.2)
        end
    end
    
    -- Put some restoration code here

    As for non-threaded child scripts, threaded child scripts should be segmented in 3 parts:

  • the initialization part: this part will be executed when the child script is called. This can be at the beginning of a simulation, but also in the middle of a simulation: remember that child scripts can be copy/pasted into a scene at any time, also when a simulation is running. Usually you would put some initialization code as well as handle retrieval in this part. If the child script was not flagged as execute once and exits the regular part (see below) before simulation end, then this part might be called several times. One command is of particular interest: simDelegateChildScriptExecution, which guarantees execution of non-explicit child scripts in this tree hierarchy, even if this script executes a blocking command (e.g. simWait(1000)).
  • the regular part: this part will be executed in a loop. Make sure that when the simulation is about to end that you exit this loop. The code in the loop is in charge of handling a specific part of a simulation (e.g. handle the automatic sliding door).
  • the restoration part: this part will be executed one time just before a simulation ends (the thread ends). If the child script was not flagged as execute once and exits the regular part (see above) before simulation end, then this part might be called several times.
  • V-REP uses threads to mimic the behavior of coroutines, instead of using them traditionally, which allows for a great deal of flexibility and control: by default a threaded child script will execute for about 1-2 milliseconds before automatically switching to another thread. This default behavior can be changed with the simSetThreadSwitchTiming command. Once the current thread was switched, it will resume execution at next simulation pass (i.e. at a time currentTime+simulationTimeStep), just before the main script is called (this default behavior can be changed with the simSetThreadResumeLocation function). The thread switching is automatic (occurs after the specified time), but the simSwitchThread command allows to shorten that time when needed. Using above three commands, an excellent synchronization with the main simulation loop can be achieved. Following code (handling the automatic sliding doors from above's example) shows child script synchronization with the main simulation loop:

    simDelegateChildScriptExecution()
    simSetThreadSwitchTiming(200) -- set the thread switch timing to the maximum (200 milliseconds)
    sensorHandleFront=simGetObjectHandle("DoorSensorFront")
    sensorHandleBack=simGetObjectHandle("DoorSensorBack")
    motorHandle=simGetObjectHandle("DoorMotor")
    
    while (simGetSimulationState()~=sim_simulation_advancing_abouttostop) do
        resF=simReadProximitySensor(sensorHandleFront)
        resB=simReadeProximitySensor(sensorHandleBack)
        if ((resF>0)or(resB>0)) then
            simSetJointTargetVelocity(motorHandle,-0.2)
        else
            simSetJointTargetVelocity(motorHandle,0.2)
        end
        simSwitchThread() -- Switch to another thread now!
        -- from now on, above loop is executed once every time the main script is about to execute
    end

    Above while loop will now execute exactly once for each main simulation loop and not waste time checking sensors again and again for same simulation times. By default, threads always resume just before the main script is called.

    The coroutine-like behavior of V-REP's threads cannot be distinguished from regular threads, with the exception that if an external command (for example socket communication commands provided by Lua libraries) is blocking, then V-REP will also appear as blocking. In that case, a non-blocking section can be defined as in following example:

    simSetThreadIsFree(true) -- Start of the non-blocking section
    
    http = require("socket.http")
    print(http.request("http://www.google.com")) -- this command may take several seconds to execute
    
    simSetThreadIsFree(false) -- End of the non-blocking section

    While in a non-blocking section, try to avoid calling sim-functions. Never forget to close the blocking section otherwise V-REP might hang or run much slowlier. Also refer to the thread-related functions and to the blocking functions for more details on thread operation in V-REP.


    Recommended topics

  • Scripts
  • The main script
  • Script dialog
  • Script editor
  • Script calling methodology
  • Script simulation parameters
  • Accessing objects programmatically
  • Explicit and non-explicit calls
  • Regular API