ikGroupHandle: the handle of an IK group that is in charge of bringing the manipulator's tip onto a target. The IK group can also be marked as explicit handling if needed. See also simGetIkGroupHandle.
jointCnt: the number of joint handles provided in the jointHandles array.
jointHandles (input): an array with jointCnt entries, that specifies the joint handles for the joints we wish to retrieve the values calculated by the IK.
thresholdDist: a distance indicating when IK should be computed in order to try to bring the tip onto the target: since the search algorithm proceeds by generating random configurations, many of them produce a tip pose that is too far from the target pose to run IK successfully. Choosing a large value will result in slow calculations, choosing a small value might produce a smaller subset of solutions. Distance between two poses is calculated using a metric.
maxTimeInMs: a maximum time in ms after which the search is aborted.
retConfig (output): an array with jointCnt entries, that will receive the IK calculated joint values, as specified by the jointHandles array.
metric (input): an array to 4 values indicating a metric used to compute pose-pose distances: distance=sqrt((dx*metric[0])^2+(dy*metric[1])^2+(dz*metric[2])^2+(angle*metric[3])^2). Can be nullptr for a default metric of {1.0,1.0,1.0,0.1}.
collisionPairCnt: the number of collision pairs. Can be 0 if collision checking is not required.
collisionPairs: an array containing 2 entity handles for each collision pair. A collision pair is represented by a collider and a collidee, that will be tested against each other. The first pair could be used for robot self-collision testing, and a second pair could be used for robot-environment collision testing. The collider can be an object or a collection handle. The collidee can be an object or collection handle, or sim.handle_all, in which case the collider will be checked agains all other collidable objects in the scene. Can be nullptr if collision checking is not required.
jointOptions: a bit-coded value corresponding to each specified joint handle. Bit 0 (i.e. 1) indicates the corresponding joint is dependent of another joint. Can be nullptr.
lowLimits: an optional array pointing to different low limit values for each specified joint. This can be useful when you wish to explore a sub-set of the joint's intervals. Can be nullptr for the default joint's low limit values. If not nullptr, then ranges should also not be nullptr.
ranges: an optional array pointing to different range values for each specified joint. This can be useful when you wish to explore a sub-set of the joint's intervals. Can be nullptr for the default joint's range values. If not nullptr, then lowLimits should also not be nullptr.
reserved: reserved for future extension. Set to nullptr.
|