Child scripts

A child script is a simulation script. V-REP supports an unlimited number of child scripts per scene. Each child script represents a small collection of routines 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 an 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 can have a list of simulation parameters attached to them, called script simulation parameters. Those parameters can be used as a quick way of adjusting values of a specific simulation model for example (e.g. the maximum velocity of a mobile robot or the resolution of a sensor).

    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 contain a collection of blocking functions. This means that every time they are called, they should perform some task and then return control. If control is not returned, then the whole simulation halts. Non-threaded child script functions are called by the main script twice per simulation step from the main script's actuation and sensing functions. The system will also call child scripts when appropriate (e.g. during child script initialization, clean-up, or when a joint callback function or contact callback function is defined). This type of child script should always be chosen over threaded child scripts whenever possible.

    Non-threaded child scripts are called in a cascaded way: child scripts are called starting with root objects (or parentless objects), and ending with leaf objects (or childless objects). The command sim.handleChildScripts, called from the default main script, handles the calling of non-threaded child scripts.

    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:

    function sysCall_init()
        sensorHandleFront=sim.getObjectHandle("DoorSensorFront")
        sensorHandleBack=sim.getObjectHandle("DoorSensorBack")
        motorHandle=sim.getObjectHandle("DoorMotor")
    end
    
    function sysCall_actuation()
        resF=sim.readProximitySensor(sensorHandleFront) 
        resB=sim.readProximitySensor(sensorHandleBack)
        if ((resF>0)or(resB>0)) then
            sim.setJointTargetVelocity(motorHandle,-0.2)
        else
            sim.setJointTargetVelocity(motorHandle,0.2)
        end
    end
    
    function sysCall_sensing()
    
    end
    
    function sysCall_cleanup()
        -- Put some restoration code here
    end
    
    function sysCall_jointCallback(inData)
        -- See the joint callback function section in the user manual for details about input/output arguments
        return outData
    end
    
    function sysCall_contactCallback(inData)
        -- See the contact callback function section in the user manual for details about input/output arguments
        return outData
    end
    
    function sysCall_beforeCopy(inData)
        for key,value in pairs(inData.objectHandles) do
            print("Object with handle "..key.." will be copied")
        end
    end
    
    function sysCall_afterCopy(inData)
        for key,value in pairs(inData.objectHandles) do
            print("Object with handle "..key.." was copied")
        end
    end
    
    function sysCall_beforeDelete(inData)
        for key,value in pairs(inData.objectHandles) do
            print("Object with handle "..key.." will be deleted")
        end
        -- inData.allObjects indicates if all objects in the scene will be deleted
    end
    
    function sysCall_afterDelete(inData)
        for key,value in pairs(inData.objectHandles) do
            print("Object with handle "..key.." was deleted")
        end
        -- inData.allObjects indicates if all objects in the scene were deleted
    end

    A non-threaded child script should be segmented into 4 main functions:

  • the initialization function: sysCall_init. 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 objects associated with 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 actuation function: sysCall_actuation. This part will be executed in each simulation step, during the actuation phase of a simulation step. Refer to the main script default code for more details about the actuation phase, but typically, you would do some actuation in this part (no sensing).
  • the sensing function: sysCall_sensing. This part will be executed in each simulation step, during the sensing phase of a simulation step. Refer to the main script default code for more details about the sensing phase, but typically, you would only do sensing in this part (no actuation).
  • the restoration function: sysCall_cleanup. This part will be executed one time just before a simulation ends, or before the script is destroyed.



  • Threaded child scripts

    Threaded child scripts are scripts that will launch in a thread. The launch of threaded child scripts is handled by the default main script code, via the sim.launchThreadedChildScripts function, in a cascaded way. When a threaded child script's execution is still underway, it will not be launched a second time. When a threaded child script ended, it can be relaunched only if the execute once item in the script properties is unchecked. 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 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, which is however not perfect since it is wasting precious computation time in the loop (the code handles the automatic sliding doors from above's example):

    function sysCall_threadmain()
        -- Put some initialization code here:
        sensorHandleFront=sim.getObjectHandle("DoorSensorFront")
        sensorHandleBack=sim.getObjectHandle("DoorSensorBack")
        motorHandle=sim.getObjectHandle("DoorMotor")
        
        -- Here we execute the regular thread code:
        while sim.getSimulationState()~=sim.simulation_advancing_abouttostop do
            resF=sim.readProximitySensor(sensorHandleFront)
            resB=sim.readProximitySensor(sensorHandleBack)
            if ((resF>0)or(resB>0)) then
                sim.setJointTargetVelocity(motorHandle,-0.2)
            else
                sim.setJointTargetVelocity(motorHandle,0.2)
            end
            -- this loop wastes precious computation time since we should only read new
            -- values when the simulation time has changed (i.e. in next simulation step).
        end
    end
    
    function sysCall_cleanup()
    	-- Put some clean-up code here:
    end

    Threaded child scripts should be segmented in 2 parts:

  • the main part: this part will be executed when the thread starts, until shortly before the thread ends. This can be at the beginning of a simulation, but also in the middle of a simulation: remember that objects associated with 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 the main loop in this part: the code in the loop is in charge of handling a specific part of a simulation (e.g. handle the automatic sliding door). In above specific example, the loop is wasting precious computation time and is running asynchronously with the main simulation loop. See further down for a better example.
  • the restoration part: this part will be executed one time just before a simulation ends, or before the thread ends.
  • 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 sim.setThreadSwitchTiming or sim.setThreadAutomaticSwitch. Once the current thread was switched, it will resume execution at next simulation pass (i.e. at a time currentTime+simulationTimeStep). The thread switching is automatic (occurs after the specified time), but the sim.switchThread 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:

    function sysCall_threadmain()
        -- Put some initialization code here:
        sim.setThreadAutomaticSwitch(false) -- disable automatic thread switches
        sensorHandleFront=sim.getObjectHandle("DoorSensorFront")
        sensorHandleBack=sim.getObjectHandle("DoorSensorBack")
        motorHandle=sim.getObjectHandle("DoorMotor")
        
        -- Here we execute the regular thread code:
        while sim.getSimulationState()~=sim.simulation_advancing_abouttostop do
            resF=sim.readProximitySensor(sensorHandleFront)
            resB=sim.readProximitySensor(sensorHandleBack)
            if ((resF>0)or(resB>0)) then
                sim.setJointTargetVelocity(motorHandle,-0.2)
            else
                sim.setJointTargetVelocity(motorHandle,0.2)
            end
            sim.switchThread() -- Explicitely switch to another thread now!
            -- from now on, above loop is executed once every time the main script is about to execute.
            -- this way you do not waste precious computation time and run synchronously.
        end
    end
    
    function sysCall_cleanup()
        -- Put some clean-up code here
    end

    Above while loop will now execute exactly once for each main simulation loop and not waste time reading sensors states again and again for same simulation times. By default, threads always resume when the main script calls sim.resumeThreads(sim.scriptthreadresume_default). If you need to make sure your thread runs only while the main script is in the sensing phase, you can resquedule the thread's resume location with the API function sim.setThreadResumeLocation.

    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:

    sim.setThreadIsFree(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
    
    sim.setThreadIsFree(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.

    Some operation should not be interrupted in order to execute correctly (imagine moving several objects in a loop). In that case, you can temporarily forbid thread switches with the sim.setThreadAutomaticSwitch function.


    Recommended topics

  • The main script