Regular API function

sim.getAlternateConfigs

Description Generates alternative manipulator configurations, for a same end-effector pose, for a manipulator that has revolute joints with a range larger than 360 degrees. The original submitted configuration will be part of the returned configurations.
C synopsis
C parameters
C return value
Lua synopsis table[] configurations=sim.getAlternateConfigs(table[] jointHandles,table[] inputConfig,int tipHandle=-1,table[] lowLimits=nil,table[] ranges=nil)
Lua parameters
jointHandles: a table with the handles of the manipulator joints.
inputConfig: the manipulator configuration (i.e. joint values).
tipHandle: the handle of the object acting as end-effector or tip of the kinematic chain, used to make sure the additional configurations have the same end-effector pose (e.g. in case some joints are dependent on others). Can be set to -1 if there are no joint dependencies involved.
lowLimits: an optional table containing the low limit values for each specified joint. This can be useful when you wish to explore a sub-set of the joint's intervals.
ranges: an optional table containing the range values for each specified joint. This can be useful when you wish to explore a sub-set of the joint's intervals. If the range value is 0, then the lowLimit and range values are taken from the joint's properties. If the range value is negative, then the search interval will be centered around the current joint position, with an extent of (-range).
Lua return values
configurations: a table containing configurations that are equivalent to the specified inputConfig, in terms of end-effector pose.