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. Consider following scenario: a mobile robot is navigating in a maze that contains several automatic sliding doors. Typically, each simulation unit (or element) should handle itself, which is quite different from the traditional approach where one single program handles everything. This means that in V-REP modularization is encouraged and will also lead to better, more flexible and scalable simulations. Following figure illustrates the traditional approach to the problem (for now the maze contains one automatic sliding door):

[Traditional control of a simulation: one program handles everything]


Notice in above's example how one single program (that might contain several sub-routines or specialized functions) is in charge of everything. Now imagine you want to add 2 identical automatic sliding doors and 2 additional robots (different from each other). Handling this new scenario doesn't work unless the control program is rewritten and adjusted to take into account the newly added elements. This is usually done by copy/pasting entire code sections (does the user know which section to copy and where to?), and handle retrieval functions also need to have their argument correctly renamed.

Now compare the traditional approach with V-REP's approach as illustrated in following figure:

[V-REP's approach to control a simulation: the control is distributed / modularized]


You can see that the door and the robot have their own control program. The door child script is only in charge of handling the door (detecting obstacles, opening/closing the door), while the robot child script is only in charge of handling the robot (handle navigation and obstacle avoidance). The main script is the default main script and doesn't require any specific code. If you now want to add 2 identical automatic sliding doors, just copy/paste the original door elements; the associated door child script will also be duplicated. Adding 2 additional robots to the scene also doesn't require any special attention: just load the appropriate robot models. Without having to adjust any code, the new scenario will perfectly work. This is illustrated in following figures:

[Modified scene with two additional automatic sliding doors and 2 additional robots]


[(1) Maze example containing automatic sliding doors and mobile robots, (2) corresponding scene hierarchy]


Child scripts are always associated with a scene object. In the scene hierarchy, objects associated with a child script will have a small script icon on the right. Double-clicking the script icon allows opening the script editor. A child script's association with a scene object has an important consequence: if the scene object 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.

A child script does not have a name on its own. Rather, the child script will adopt the same name as its associated scene object. 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. 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. Following shows a typical non-threaded child script code (the code handles the automatic sliding doors from above's example):

if (simGetScriptExecutionCount()==0) then
    sensorHandleFront=simGetObjectHandle("DoorSensorFront")
    sensorHandleBack=simGetObjectHandle("DoorSensorBack")
    motorHandle=simGetObjectHandle("DoorMotor")
end

simHandleChildScript(sim_handle_all_except_explicit)
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 can of course be 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 difficult to synchronize with the main simulation loop, 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, a good 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