Joint callback functions

Scripts can include a joint callback function, which is one of many system callback functions. When present for a given joint, then it will be called by CoppeliaSim in various situations:

  • When the joint is in kinematic mode: a call to sim.setJointTargetPosition or sim.setJointTargetVelocity will trigger the joint callback function. The main script contains such a joint callback function, that offers a default behaviour, i.e. a specific motion profile will be applied
  • When the joint is in dynamic mode, is dynamically enabled, and is set to custom control: the physics engine will trigger the joint callback function for each dynamics simulation step, which is quite often, normally 10 times per simulation step for a given joint
  • Joint callback functions enable the user to customize the control loop for specific joints in order to write low-level control algorithms.

    Following represents a simple position control joint callback function, for a joint in dynamic mode:

    #python def sysCall_joint(inData): # inData['mode'] : sim.jointmode_kinematic or sim.jointmode_dynamic # inData['handle'] : the handle of the joint to control # inData['revolute'] : whether the joint is revolute or prismatic # inData['cyclic'] : whether the joint is cyclic or not # inData['lowLimit'] : the lower limit of the joint (if the joint is not cyclic) # inData['highLimit'] : the higher limit of the joint (if the joint is not cyclic) # inData['dt'] : the step size used for the calculations # inData['pos'] : the current position # inData['vel'] : the current velocity # inData['targetPos'] : the desired position (if joint is dynamic, or when sim.setJointTargetPosition was called) # inData['targetVel'] : the desired velocity (if joint is dynamic, or when sim.setJointTargetVelocity was called) # inData['initVel'] : the desired initial velocity (if joint is kinematic and when sim.setJointTargetVelocity # was called with a 4th argument) # inData['error'] : targetPos-currentPos (with revolute cyclic joints, the shortest cyclic distance) # inData['maxVel'] : a maximum velocity # inData['maxAccel'] : a maximum acceleration # inData['maxJerk'] : a maximum jerk # inData['first'] : whether this is the first call from the physics engine, since the joint # was initialized (or re-initialized) in it. # inData['passCnt'] : the current dynamics calculation pass. 1-10 by default # inData['rk4pass'] : if Runge-Kutta 4 solver is selected, will loop from 1 to 4 for each inData['passCnt'] # inData['totalPasses'] : the number of dynamics calculation passes for each "regular" simulation pass. # inData['effort'] : the last force or torque that acted on this joint along/around its axis. With Bullet, # torques from joint limits are not taken into account # inData['force'] : the joint force/torque, as set via sim.setJointTargetForce if inData['mode'] == sim.jointmode_dynamic: # Simplest position controller example: ctrl = inData['error'] * 20 max_velocity = ctrl if max_velocity > inData['maxVel']: max_velocity = inData['maxVel'] if max_velocity < -inData['maxVel']: max_velocity = -inData['maxVel'] force_or_torque_to_apply = inData['maxForce'] # Following data must be returned to CoppeliaSim: outData = {'vel': max_velocity, 'force': force_or_torque_to_apply} return outData # Expected return data: # For kinematic joints: # outData = {'pos': pos, 'vel': vel, 'immobile': False} # # For dynamic joints: # outData = {'force': f, 'vel': vel} --lua function sysCall_joint(inData) -- inData.mode : sim.jointmode_kinematic or sim.jointmode_dynamic -- -- inData.handle : the handle of the joint to control -- inData.revolute : whether the joint is revolute or prismatic -- inData.cyclic : whether the joint is cyclic or not -- inData.lowLimit : the lower limit of the joint (if the joint is not cyclic) -- inData.highLimit : the higher limit of the joint (if the joint is not cyclic) -- inData.dt : the step size used for the calculations -- inData.pos : the current position -- inData.vel : the current velocity -- inData.targetPos : the desired position (if joint is dynamic, or when sim.setJointTargetPosition was called) -- inData.targetVel : the desired velocity (if joint is dynamic, or when sim.setJointTargetVelocity was called) -- inData.initVel : the desired initial velocity (if joint is kinematic and when sim.setJointTargetVelocity -- was called with a 4th argument) -- inData.error : targetPos-currentPos (with revolute cyclic joints, the shortest cyclic distance) -- inData.maxVel : a maximum velocity -- inData.maxAccel : a maximum acceleration -- inData.maxJerk : a maximum jerk -- inData.first : whether this is the first call from the physics engine, since the joint -- was initialized (or re-initialized) in it. -- inData.passCnt : the current dynamics calculation pass. 1-10 by default -- inData.rk4pass : if Runge-Kutta 4 solver is selected, will loop from 1 to 4 for each inData.passCnt -- inData.totalPasses : the number of dynamics calculation passes for each "regular" simulation pass. -- inData.effort : the last force or torque that acted on this joint along/around its axis. With Bullet, -- torques from joint limits are not taken into account -- inData.force : the joint force/torque, as set via sim.setJointTargetForce if inData.mode == sim.jointmode_dynamic then -- Simplest position controller example: local ctrl = inData.error * 20 local maxVelocity = ctrl if maxVelocity > inData.maxVel then maxVelocity = inData.maxVel end if maxVelocity < -inData.maxVel then maxVelocity = -inData.maxVel end local forceOrTorqueToApply = inData.maxForce -- Following data must be returned to CoppeliaSim: local outData = {vel = maxVelocity, force = forceOrTorqueToApply} return outData end -- Expected return data: -- For kinematic joints: -- outData = {pos = pos, vel = vel, immobile = false} -- -- For dynamic joints: -- outData = {force = f, vel = vel} end

    A joint callback call is applied to all scripts located in the upward hierarchy of the joint, and interrupted as soon as a script handles the call, i.e. returns data:

    [Script execution precedence with a joint callback]