Coppelia Kinematics Routines, API reference

All units, unless otherwise indicated, are specified in meters and radians.

ikAddIkElement
ikComputeJacobian
ikCreateEnvironment
ikCreateDummy
ikCreateIkGroup
ikCreateJoint
ikDoesObjectExist
ikDoesIkGroupExist
ikDuplicateEnvironment
ikEraseEnvironment
ikEraseObject
ikFindConfig
ikGetIkElementBase
ikGetIkElementConstraints
ikGetIkElementFlags
ikGetIkElementPrecision
ikGetIkElementWeights
ikGetIkGroupCalculation
ikGetIkGroupFlags
ikGetIkGroupHandle
ikGetJacobian
ikGetJointDependency
ikGetJointIkWeight
ikGetJointInterval
ikGetJointMatrix
ikGetJointMaxStepSize
ikGetJointMode
ikGetJointPosition
ikGetJointScrewPitch
ikGetJointTransformation
ikGetJointType
ikGetLastError
ikGetLinkedDummy
ikGetManipulability
ikGetObjectHandle
ikGetObjectMatrix
ikGetObjectParent
ikGetObjects
ikGetObjectTransformation
ikHandleIkGroup
ikLoad
ikReleaseBuffer
ikSave
ikSetIkElementBase
ikSetIkElementConstraints
ikSetIkElementFlags
ikSetIkElementPrecision
ikSetIkElementWeights
ikSetIkGroupCalculation
ikSetIkGroupFlags
ikSetJointDependency
ikSetJointIkWeight
ikSetJointInterval
ikSetJointMaxStepSize
ikSetJointMode
ikSetJointPosition
ikSetJointScrewPitch
ikSetLinkedDummy
ikSetObjectMatrix
ikSetObjectParent
ikSetObjectTransformation
ikSetSphericalJointMatrix
ikSetSphericalJointQuaternion
ikSwitchEnvironment

Environment functions and helpers

ikCreateEnvironment
ikEraseEnvironment
ikDuplicateEnvironment
ikSave
ikLoad
ikSwitchEnvironment
ikGetLastError
ikReleaseBuffer

Objects

ikGetObjects
ikGetObjectHandle
ikDoesObjectExist
ikEraseObject
ikGetObjectParent
ikSetObjectParent
ikGetObjectTransformation
ikSetObjectTransformation
ikGetObjectMatrix
ikSetObjectMatrix

Dummies

ikCreateDummy
ikEraseObject
ikGetLinkedDummy
ikSetLinkedDummy

Joints

ikCreateJoint
ikEraseObject
ikGetJointPosition
ikSetJointPosition
ikGetJointMode
ikSetJointMode
ikGetJointInterval
ikSetJointInterval
ikGetJointDependency
ikSetJointDependency
ikGetJointIkWeight
ikSetJointIkWeight
ikGetJointMaxStepSize
ikSetJointMaxStepSize
ikGetJointScrewPitch
ikSetJointScrewPitch
ikGetJointTransformation
ikSetSphericalJointQuaternion
ikGetJointType
ikGetJointMatrix
ikSetSphericalJointMatrix

IK groups

ikCreateIkGroup
ikGetIkGroupHandle
ikDoesIkGroupExist
ikGetIkGroupFlags
ikSetIkGroupFlags
ikGetIkGroupCalculation
ikSetIkGroupCalculation

IK elements

ikAddIkElement
ikGetIkElementFlags
ikSetIkElementFlags
ikGetIkElementConstraints
ikSetIkElementConstraints
ikGetIkElementBase
ikSetIkElementBase
ikGetIkElementPrecision
ikSetIkElementPrecision
ikGetIkElementWeights
ikSetIkElementWeights

IK calculation

ikHandleIkGroup
ikFindConfig
ikComputeJacobian
ikGetJacobian
ikGetManipulability

ikAddIkElement

Description Adds a new IK element to an IK group.
Synopsis bool ikAddIkElement(int ikGroupHandle,int tipHandle,int* ikElementHandle)
Arguments
ikGroupHandle: the handle of the IK group.
tipHandle: the handle of the dummy object that should act as the tip in the IK element.
ikElementHandle: the IK element handle in the IK group, in return.
Return value true in case of success.
See also ikGetIkGroupHandle, ikGetObjectHandle

ikComputeJacobian

Description Computes the Jacobian for an IK group.
Synopsis bool ikComputeJacobian(int ikGroupHandle,int options,bool* success=nullptr)
Arguments
ikGroupHandle: the handle of the IK group.
options: options flag, bit-coded. bit0 set (i.e. 1): takes joint weights into account.
success: whether the Jacobian could successfully be computed, in return.
Return value true in case of success.
See also ikGetJacobian, ikGetManipulability

ikCreateEnvironment

Description Creates an new IK environment, and switches to it.
Synopsis bool ikCreateEnvironment(int* environmentHandle=nullptr,bool protectedEnvironment=false)
Arguments
environmentHandle: the handle of the newly created environment.
protectedEnvironment: set to false.
Return value true in case of success.
See also ikEraseEnvironment, ikSwitchEnvironment, ikDuplicateEnvironment, ikLoad

ikCreateDummy

Description Creates a dummy object.
Synopsis bool ikCreateDummy(const char* dummyName/*=nullptr*/,int* dummyHandle)
Arguments
dummyName: the name of the dummy.
dummyHandle: the handle of the dummy, in return.
Return value true in case of success.
See also ikDoesObjectExist, ikCreateJoint, ikEraseObject

ikCreateIkGroup

Description Creates an IK group.
Synopsis bool ikCreateIkGroup(const char* ikGroupName/*=nullptr*/,int* ikGroupHandle)
Arguments
ikGroupName: the name of the IK group.
ikGroupHandle: the handle of the IK group, in return.
Return value true in case of success.
See also ikDoesIkGroupExist

ikCreateJoint

Description Creates a joint object.
Synopsis bool ikCreateJoint(const char* jointName/*=nullptr*/,int jointType,int* jointHandle)
Arguments
jointName: the name of the joint.
jointType: the type of the joint. supported types are ik_jointtype_revolute, ik_jointtype_prismatic and ik_jointtype_spherical.
jointHandle: the handle of the joint, in return.
Return value true in case of success.
See also ikDoesObjectExist, ikCreateDummy, ikEraseObject

ikDoesObjectExist

Description Checks whether an object exists, based on its name.
Synopsis bool ikDoesObjectExist(const char* objectName)
Arguments
objectName: the name of the object.
Return value true if the object exists.
See also ikGetObjectHandle

ikDoesIkGroupExist

Description Checks whether an IK group exists, based on its name.
Synopsis bool ikDoesIkGroupExist(const char* ikGroupName)
Arguments
ikGroupName: the name of the IK group.
Return value true if the IK group exists.
See also ikGetIkGroupHandle

ikDuplicateEnvironment

Description Duplicate current IK environment. Can be used to operate on an environment without modifying the original environment
Synopsis bool ikDuplicateEnvironment(int* newEnvironmentHandle)
Arguments
newEnvironmentHandle: the handle of the newly created environment.
Return value true in case of success.
See also ikEraseEnvironment, ikSwitchEnvironment, ikDuplicateEnvironment, ikCreateEnvironment

ikEraseEnvironment

Description Erases an IK environment, and switches to another environment, if available.
Synopsis bool ikEraseEnvironment(int* switchedEnvironmentHandle=nullptr)
Arguments
switchedEnvironmentHandle: the handle of the environment that was switched to, or -1 if there is no environment left.
Return value true in case of success.
See also ikCreateEnvironment, ikSwitchEnvironment

ikEraseObject

Description Erases an object.
Synopsis bool ikEraseObject(int objectHandle)
Arguments
objectHandle: handle of the object.
Return value true in case of success.
See also ikGetObjectHandle, ikCreateDummy, ikCreateJoint

ikFindConfig

Description Searches for a manipulator configuration that matches a given end-effector position/orientation in space. Search is randomized.
Synopsis int ikFindConfig(int ikGroupHandle,size_t jointCnt,const int* jointHandles,simReal thresholdDist,int maxSearchTimeInMs,simReal* retConfig,const simReal* metric=nullptr,bool(*validationCallback)(simReal*)=nullptr)
Arguments
ikGroupHandle: the handle of the IK group.
jointCnt: the number of joint handles provided in the jointHandles array.
jointHandles: 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 (see metric argument below).
maxSearchTimeInMs: the maximum time in milliseconds before this function returns.
retConfig: an array with jointCnt entries, that will receive the IK calculated joint values, as specified by the jointHandles array.
metric: 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).
validationCallback: a callback function taking as input argument the proposed joint values (i.e. a configuration), and as return value whether the configuration is valid (e.g. is not colliding).
Return value -1 in case of an error, 0 if no valid configuration was found, 1 otherwise.
See also ikComputeJacobian, ikGetJacobian, ikDuplicateEnvironment

ikGetConfigForTipPose

Description Deprecated. Use ikFindConfig instead.
Synopsis int ikGetConfigForTipPose(int ikGroupHandle,size_t jointCnt,const int* jointHandles,simReal thresholdDist,int maxIterations,simReal* retConfig,const simReal* metric=nullptr,bool(*validationCallback)(simReal*)=nullptr,const int* jointOptions=nullptr,const simReal* lowLimits=nullptr,const simReal* ranges=nullptr)
Arguments
ikGroupHandle: the handle of the IK group.
jointCnt: the number of joint handles provided in the jointHandles array.
jointHandles: 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 (see metric argument below).
maxIterations: the maximum number of iterations before this function returns. Alternatively, one can specify an upper time limit, in milliseconds, after which the function returns with maxIterations=-timeLimitInMs.
retConfig: an array with jointCnt entries, that will receive the IK calculated joint values, as specified by the jointHandles array.
metric: 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).
validationCallback: a callback function taking as input argument the proposed joint values (i.e. a configuration), and as return value whether the configuration is valid (e.g. is not colliding).
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.
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.
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. 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 linear/angular position, with an extent of (-range).
Return value -1 in case of an error, 0 if no valid configuration was found, 1 otherwise.
See also ikComputeJacobian, ikGetJacobian, ikDuplicateEnvironment

ikGetIkElementBase

Description Retrieves the base object of an IK element.
Synopsis bool ikGetIkElementBase(int ikGroupHandle,int ikElementHandle,int* baseHandle,int* constraintsBaseHandle)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
baseHandle: the handle of the base object, in return, or -1 if the world is the base.
constraintsBaseHandle: the handle of the constraints base object, in return, relative to which the constraints are specified. Returns -1 if the constraints are relative to the base object.
Return value true in case of success.
See also ikSetIkElementBase, ikGetIkGroupHandle, ikGetObjectHandle

ikGetIkElementConstraints

Description Retrieves the constraints of an IK element.
Synopsis bool ikGetIkElementConstraints(int ikGroupHandle,int ikElementHandle,int* constraints)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
constraints: the constraints, in return. A combination of following is possible: ik_constraint_x, ik_constraint_y, ik_constraint_z, ik_constraint_alpha_beta, ik_constraint_gamma. For convenience we also have ik_constraint_position=ik_constraint_x|ik_constraint_y|ik_constraint_z, ik_constraint_orientation=ik_constraint_alpha_beta|ik_constraint_gamma, and ik_constraint_pose=ik_constraint_position|ik_constraint_orientation.
Return value true in case of success.
See also ikSetIkElementConstraints, ikGetIkGroupHandle, ikGetObjectHandle

ikGetIkElementFlags

Description Retrieves various flags of an IK element.
Synopsis bool ikGetIkElementFlags(int ikGroupHandle,int ikElementHandle,int* flags)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
flags: bit-coded flags, in return: bit0 set (1): the enabled state of the ik element.
Return value true in case of success.
See also ikSetIkElementFlags, ikGetIkGroupHandle, ikGetObjectHandle

ikGetIkElementPrecision

Description Retrieves the precision settings of an IK element.
Synopsis bool ikGetIkElementPrecision(int ikGroupHandle,int ikElementHandle,simReal* linearPrecision,simReal* angularPrecision)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
linearPrecision: the required linear precision, in return.
angularPrecision: the required angular precision, in return.
Return value true in case of success.
See also ikSetIkElementPrecision, ikGetIkGroupHandle, ikGetObjectHandle

ikGetIkElementWeights

Description Retrieves the desired linear and angular resolution weights of an IK element.
Synopsis bool ikGetIkElementWeights(int ikGroupHandle,int ikElementHandle,simReal* linearWeight,simReal* angularWeight)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
linearWeight: the linear resolution weight, in return.
angularWeight: the angular resolution weight, in return.
Return value true in case of success.
See also ikSetIkElementWeights, ikGetIkGroupHandle, ikGetObjectHandle

ikGetIkGroupCalculation

Description Retrieves calculation properties for an IK group.
Synopsis bool ikGetIkGroupCalculation(int ikGroupHandle,int* method,simReal* damping,int* maxIterations)
Arguments
ikGroupHandle: the handle of the IK group.
method: the resolution method, in return. Possible values are ik_method_pseudo_inverse (features a tiny bit of hard-coded damping), ik_method_undamped_pseudo_inverse, ik_method_damped_least_squares and ik_method_jacobian_transpose.
damping: the damping, in case the resolution method is ik_method_damped_least_squares, in return.
maxIterations: the maximum number of iterations, in return.
Return value true in case of success.
See also ikSetIkGroupCalculation, ikGetIkGroupHandle

ikGetIkGroupFlags

Description Retrieves flags of an IK group.
Synopsis bool ikGetIkGroupFlags(int ikGroupHandle,int* flags)
Arguments
ikGroupHandle: the handle of the IK group.
flags: the flags of the IK group, in return. bit0 set (i.e. 1)=group is enabled, bit1 set (i.e. 2)=max. step sizes are ignored, bit2 set (i.e. 4)=restore joints if target position not reached, bit3 set (i.e. 8)=restore joints if target orientation not reached.
Return value true in case of success.
See also ikSetIkGroupFlags, ikGetIkGroupHandle

ikGetIkGroupHandle

Description Retrieves the handle of an IK group based on its name.
Synopsis bool ikGetIkGroupHandle(const char* ikGroupName,int* ikGroupHandle)
Arguments
ikGroupName: the name of the IK group.
ikGroupHandle: the returned IK group handle.
Return value true in case of success.
See also ikDoesIkGroupExist, ikCreateIkGroup

ikGetJacobian

Description Retrieves the Jacobian previously computed via ikComputeJacobian.
Synopsis simReal* ikGetJacobian(int ikGroupHandle,size_t* matrixSize)
Arguments
ikGroupHandle: the handle of the IK group.
matrixSize: a pointer to two values for the size (row count (i.e. number of DoFs) and column count) of the Jacobian matrix, in return.
Return value a pointer to the matrix. Use ikReleaseBuffer to release the memory when done.
See also ikComputeJacobian, ikGetManipulability

ikGetJointDependency

Description Retrieves information about a possible joint dependency.
Synopsis bool ikGetJointDependency(int jointHandle,int* dependencyJointHandle,simReal* offset,simReal* mult)
Arguments
jointHandle: the handle of the joint.
dependencyJointHandle: the handle of the dependency joint, in return.
offset: the offset, in return. We have joint linear/angular position = dependency joint linear/angular position * mult + offset.
mult: the multiplication factor, in return. We have joint linear/angular position = dependency joint linear/angular position * mult + offset.
Return value true in case of success.
See also ikSetJointDependency, ikGetObjectHandle

ikGetJointIkWeight

Description Retrieves the IK weight of a joint, i.e. the weight it has during IK resolution.
Synopsis bool ikGetJointIkWeight(int jointHandle,simReal* ikWeight)
Arguments
jointHandle: the handle of the joint.
ikWeight: the IK weight, in return.
Return value true in case of success.
See also ikSetJointIkWeight, ikGetObjectHandle

ikGetJointInterval

Description Retrieves the joint limits.
Synopsis bool ikGetJointInterval(int jointHandle,bool* cyclic,simReal* intervalMinAndRange)
Arguments
jointHandle: the handle of the joint.
cyclic: whether the joint is cyclic (has no limits).
intervalMinAndRange: a pointer to two values: the joint lower limit, and the joint range (i.e. joint upper limit = joint lower limit + joint range)
Return value true in case of success.
See also ikSetJointInterval, ikGetObjectHandle

ikGetJointMatrix

Description Retrieves the intrinsic transformation matrix of a joint.
Synopsis bool ikGetJointMatrix(int jointHandle,C4X4Matrix* matrix)
Arguments
jointHandle: the handle of the joint.
matrix: the transformation matrix, in return.
Return value true in case of success.
See also ikSetSphericalJointMatrix, ikGetJointPosition, ikGetJointTransformation, ikGetObjectHandle

ikGetJointMaxStepSize

Description Retrieves the maximum step size of a joint.
Synopsis bool ikGetJointMaxStepSize(int jointHandle,simReal* maxStepSize)
Arguments
jointHandle: the handle of the joint.
maxStepSize: the maximum step size, in return.
Return value true in case of success.
See also ikSetJointMaxStepSize, ikGetObjectHandle

ikGetJointMode

Description Retrieves the joint mode.
Synopsis bool ikGetJointMode(int jointHandle,int* mode)
Arguments
jointHandle: the handle of the joint.
mode: the joint mode, in return. Possible values are: ik_jointmode_passive, ik_jointmode_ik, ik_jointmode_dependent
Return value true in case of success.
See also ikSetJointMode, ikGetObjectHandle

ikGetJointPosition

Description Retrieves the position (linear or angular) of a joint.
Synopsis bool ikGetJointPosition(int jointHandle,simReal* position)
Arguments
jointHandle: the handle of the joint.
position: the position, in return.
Return value true in case of success.
See also ikSetJointPosition, ikGetJointMatrix, ikGetJointTransformation, ikGetObjectHandle

ikGetJointScrewPitch

Description Retrieves the screw pitch of a revolute joint.
Synopsis bool ikGetJointScrewPitch(int jointHandle,simReal* pitch)
Arguments
jointHandle: the handle of the joint.
pitch: the screw pitch of the joint, in return. A pitch value of zero represents a revolute joint, a value different from zero represents a screw.
Return value true in case of success.
See also ikSetJointScrewPitch, ikGetObjectHandle

ikGetJointTransformation

Description Retrieves the intrinsic transformation of a joint.
Synopsis bool ikGetJointTransformation(int jointHandle,C7Vector* transf)
Arguments
jointHandle: the handle of the joint.
transf: the transformation, in return.
Return value true in case of success.
See also ikSetSphericalJointQuaternion, ikGetJointPosition, ikGetJointMatrix, ikGetObjectHandle

ikGetJointType

Description Retrieves the joint type.
Synopsis bool ikGetJointType(int jointHandle,int* jointType)
Arguments
jointHandle: the handle of the joint.
jointType: the joint type, in return. Possible values are: ik_jointtype_revolute, ik_jointtype_prismatic and ik_jointtype_spherical.
Return value true in case of success.
See also ikCreateJoint

ikGetLastError

Description Retrieves and clears the last error string.
Synopsis std::string ikGetLastError()
Arguments
Return value The error string.
See also

ikGetLinkedDummy

Description Retrieves the handle of a dummy linked to this one.
Synopsis bool ikGetLinkedDummy(int dummyHandle,int* linkedDummyHandle)
Arguments
dummyHandle: the handle of the dummy object.
linkedDummyHandle: the handle of the linked dummy object, in return. Is -1 if no dummy object is linked to this one.
Return value true in case of success.
See also ikSetLinkedDummy, ikGetObjectHandle

ikGetManipulability

Description Retrieves the manipulability value ( sqrt(det(J*JT)) ) of the Jacobian previously computed via ikComputeJacobian.
Synopsis bool ikGetManipulability(int ikGroupHandle,simReal* manip)
Arguments
ikGroupHandle: the handle of the IK group.
manip: the manipulability value, in return.
Return value true in case of success.
See also ikComputeJacobian, ikGetJacobian

ikGetObjectHandle

Description Retrieves the handle of an object based on its name.
Synopsis bool ikGetObjectHandle(const char* objectName,int* objectHandle)
Arguments
objectName: the name of the object.
objectHandle: the returned object handle.
Return value true in case of success.
See also ikDoesObjectExist, ikCreateDummy, ikCreateJoint

ikGetObjectMatrix

Description Retrieves the transformation matrix of an object. If the object is a joint object, the matrix does not include the joint's intrinsic transformation.
Synopsis bool ikGetObjectMatrix(int objectHandle,int relativeToObjectHandle,C4X4Matrix* matrix)
Arguments
objectHandle: the handle of the object.
relativeToObjectHandle: the handle of an object relative to which we want the matrix expressed. Otherwise, specify ik_handle_world if you want the absolute matrix, or ik_handle_parent if you want the matrix relative to the parent object.
matrix: a pointer to 12 values representing the transformation matrix (the last row of the 4x4 matrix (0,0,0,1) is omitted)
Return value true in case of success.
See also ikSetObjectMatrix, ikGetObjectTransformation, ikGetJointTransformation, ikGetObjectHandle

ikGetObjectParent

Description Retrieves an object's parent handle.
Synopsis bool ikGetObjectParent(int objectHandle,int* parentObjectHandle)
Arguments
objectHandle: the handle of the object.
parentObjectHandle: the returned handle of the parent, or -1 if the object has no parent.
Return value true in case of success.
See also ikSetObjectParent, ikGetObjectHandle

ikGetObjects

Description Allows to loop through all objects in the environment.
Synopsis bool ikGetObjects(size_t index,int* objectHandle=nullptr,std::string* objectName=nullptr,bool* isJoint=nullptr,int* jointType=nullptr)
Arguments
index: the zero-based index. Start at 0, and increment until the return value is false, in order to loop through all objects in the environment.
objectHandle: the handle of the object, in return.
objectName: the name of the object, in return.
isJoint: whether the object is a joint, in return.
jointType: the type of joint, in return, if the object at the specified index is a joint. Possible values are ik_jointtype_revolute, ik_jointtype_prismatic or ik_jointtype_spherical.
Return value false in case of an error, or if no object exists at the specified index.
See also ikGetObjectHandle, ikDoesObjectExist

ikGetObjectTransformation

Description Retrieves the transformation (position and quaternion) of an object. If the object is a joint object, the transformation does not include the joint's intrinsic transformation.
Synopsis bool ikGetObjectTransformation(int objectHandle,int relativeToObjectHandle,C7Vector* transf)
Arguments
objectHandle: the handle of the object.
relativeToObjectHandle: the handle of an object relative to which we want the transformation expressed. Otherwise, specify ik_handle_world if you want the absolute transformation, or ik_handle_parent if you want the transformation relative to the parent object.
transf: a pointer to the transformation that will be returned.
Return value true in case of success.
See also ikSetObjectTransformation, ikGetObjectMatrix, ikGetJointTransformation, ikGetObjectHandle

ikHandleIkGroup

Description Handles (i.e. computes/resolves) an IK group.
Synopsis bool ikHandleIkGroup(int ikGroupHandle=ik_handle_all,int* result=nullptr)
Arguments
ikGroupHandle: the handle of the IK group (in that case make sure the IK group is flagged as explicit handling (default when creating a new IK group)), or ik_handle_all to handle all IK groups.
result: the resolution result, in return. Possible values are ik_result_not_performed, ik_result_success, ik_result_fail
Return value true in case of success.
See also ikComputeJacobian, ikFindConfig

ikLoad

Description Loads kinematic content previously exported with ikSave. Make sure that the environment is empty before calling this function.
Synopsis bool ikLoad(const unsigned char* data,size_t dataLength)
Arguments
data: a pointer to a buffer with the kinematic content.
dataLength: the size of the kinematic content buffer.
Return value true in case of success.
See also ikSave, ikCreateEnvironment, ikEraseEnvironment

ikReleaseBuffer

Description Releases a buffer allocated by the specific API functions.
Synopsis void ikReleaseBuffer(void* buffer)
Arguments
buffer: the buffer to release.
Return value
See also

ikSave

Description Saves the kinematic content in the current environment.
Synopsis unsigned char* ikSave(size_t* dataLength)
Arguments
dataLength: the size of the kinematic content buffer.
Return value a pointer to a buffer with the kinematic content. The user is in charge of releasing the buffer with ikReleaseBuffer
See also ikLoad

ikSetIkElementBase

Description Sets the base object of an IK element.
Synopsis bool ikSetIkElementBase(int ikGroupHandle,int ikElementHandle,int baseHandle,int constraintsBaseHandle=-1)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
baseHandle: the handle of the base object, or -1 if the world is the base.
constraintsBaseHandle: the handle of the constraints base object, relative to which the constraints are specified. Set to -1 to have the constraints relative to the base object.
Return value true in case of success.
See also ikGetIkElementBase, ikGetIkGroupHandle, ikGetObjectHandle

ikSetIkElementConstraints

Description Sets the constraints of an IK element.
Synopsis bool ikSetIkElementConstraints(int ikGroupHandle,int ikElementHandle,int constraints)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
constraints: the constraints. Combine following: ik_constraint_x, ik_constraint_y, ik_constraint_z, ik_constraint_alpha_beta, ik_constraint_gamma (ik_constraint_gamma should only be set if ik_constraint_alpha_beta is also set). For convenience we also have ik_constraint_position=ik_constraint_x|ik_constraint_y|ik_constraint_z, ik_constraint_orientation=ik_constraint_alpha_beta|ik_constraint_gamma, and ik_constraint_pose=ik_constraint_position|ik_constraint_orientation.
Return value true in case of success.
See also ikGetIkElementConstraints, ikGetIkGroupHandle, ikGetObjectHandle

ikSetIkElementFlags

Description Sets various flags for an IK element.
Synopsis bool ikSetIkElementFlags(int ikGroupHandle,int ikElementHandle,int flags)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
flags: bit-coded flags: bit0 set (1): the enabled state of the ik element.
Return value true in case of success.
See also ikGetIkElementFlags, ikGetIkGroupHandle, ikGetObjectHandle

ikSetIkElementPrecision

Description Sets the desired precision of an IK element.
Synopsis bool ikSetIkElementPrecision(int ikGroupHandle,int ikElementHandle,simReal linearPrecision,simReal angularPrecision)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
linearPrecision: the required linear precision.
angularPrecision: the required angular precision.
Return value true in case of success.
See also ikGetIkElementPrecision, ikGetIkGroupHandle, ikGetObjectHandle

ikSetIkElementWeights

Description Sets the desired linear and angular resolution weights of an IK element.
Synopsis bool ikSetIkElementWeights(int ikGroupHandle,int ikElementHandle,simReal linearWeight,simReal angularWeight)
Arguments
ikGroupHandle: the handle of the IK group.
ikElementHandle: the IK element handle, or X, where X=handleOfTipDummy|ik_handleflag_tipdummy (if several IK elements with the same tip dummy exist, then the first encountered will be selected).
linearWeight: the desired linear resolution weight.
angularWeight: the desired angular resolution weight.
Return value true in case of success.
See also ikGetIkElementWeights, ikGetIkGroupHandle, ikGetObjectHandle

ikSetIkGroupCalculation

Description Sets calculation properties for an IK group.
Synopsis bool ikSetIkGroupCalculation(int ikGroupHandle,int method,simReal damping,int maxIterations)
Arguments
ikGroupHandle: the handle of the IK group.
method: the resolution method. Possible values are ik_method_pseudo_inverse (features a tiny bit of hard-coded damping), ik_method_undamped_pseudo_inverse, ik_method_damped_least_squares and ik_method_jacobian_transpose.
damping: the damping, in case the resolution method is ik_method_damped_least_squares.
maxIterations: the maximum number of iterations.
Return value true in case of success.
See also ikGetIkGroupCalculation, ikGetIkGroupHandle

ikSetIkGroupFlags

Description Sets flags of an IK group.
Synopsis bool ikSetIkGroupFlags(int ikGroupHandle,int flags)
Arguments
ikGroupHandle: the handle of the IK group.
flags: the flags of the IK group. bit0 set (i.e. 1)=group is enabled, bit1 set (i.e. 2)=max. step sizes are ignored, bit2 set (i.e. 4)=restore joints if target position not reached, bit3 set (i.e. 8)=restore joints if target orientation not reached.
Return value true in case of success.
See also ikGetIkGroupFlags, ikGetIkGroupHandle

ikSetJointDependency

Description Sets information about a possible dependent joint.
Synopsis bool ikSetJointDependency(int jointHandle,int dependencyJointHandle,simReal offset=0.0,simReal mult=1.0)
Arguments
jointHandle: the handle of the joint.
dependencyJointHandle: the handle of the joint, this joint is dependent of. -1 to disable.
offset: the offset. We have joint linear/angular position = dependency joint linear/angular position * mult + offset
mult: the multiplication factor. We have joint linear/angular position = dependency joint linear/angular position * mult + offset
Return value true in case of success.
See also ikGetJointDependency, ikGetObjectHandle

ikSetJointIkWeight

Description Sets the IK weight of a joint, i.e. the weight it has during IK resolution.
Synopsis bool ikSetJointIkWeight(int jointHandle,simReal ikWeight)
Arguments
jointHandle: the handle of the joint.
ikWeight: the IK weight.
Return value true in case of success.
See also ikGetJointIkWeight, ikGetObjectHandle

ikSetJointInterval

Description Sets the joint limits.
Synopsis bool ikSetJointInterval(int jointHandle,bool cyclic,const simReal* intervalMinAndRange=nullptr)
Arguments
jointHandle: the handle of the joint.
cyclic: whether the joint is cyclic (has no limits). Only revolute joints can be cyclic.
intervalMinAndRange: a pointer to two values: the joint lower limit, and the joint range (i.e. joint upper limit = joint lower limit + joint range)
Return value true in case of success.
See also ikGetJointInterval, ikGetObjectHandle

ikSetJointMaxStepSize

Description Sets the maximum step size of a joint.
Synopsis bool ikSetJointMaxStepSize(int jointHandle,simReal maxStepSize)
Arguments
jointHandle: the handle of the joint.
maxStepSize: the maximum step size.
Return value true in case of success.
See also ikGetJointMaxStepSize, ikGetObjectHandle

ikSetJointMode

Description Sets the joint mode.
Synopsis bool ikSetJointMode(int jointHandle,int jointMode)
Arguments
jointHandle: the handle of the joint.
jointMode: the joint mode. Allowed values are: ik_jointmode_passive, ik_jointmode_ik, ik_jointmode_dependent
Return value true in case of success.
See also ikGetJointMode, ikGetObjectHandle

ikSetJointPosition

Description Sets the position (linear or angular) of a joint.
Synopsis bool ikSetJointPosition(int jointHandle,simReal position)
Arguments
jointHandle: the handle of the joint.
position: the position.
Return value true in case of success.
See also ikGetJointPosition, ikSetSphericalJointMatrix, ikSetSphericalJointQuaternion, ikGetObjectHandle

ikSetJointScrewPitch

Description Sets the screw pitch, in case of a revolute joint.
Synopsis bool ikSetJointScrewPitch(int jointHandle,simReal pitch)
Arguments
jointHandle: the handle of the joint.
pitch: the screw pitch of the joint. A pitch value of zero represents a revolute joint, a value different from zero represents a screw.
Return value true in case of success.
See also ikGetJointScrewPitch, ikGetObjectHandle

ikSetLinkedDummy

Description Links this dummy object to another dummy object, or detaches it from another dummy object.
Synopsis bool ikSetLinkedDummy(int dummyHandle,int linkedDummyHandle)
Arguments
dummyHandle: the handle of the dummy object.
linkedDummyHandle: the handle of the dummy object to be linked, or -1 to detach this dummy object from a linked dummy object.
Return value true in case of success.
See also ikGetLinkedDummy, ikGetObjectHandle

ikSetObjectMatrix

Description Sets the transformation matrix of an object. If the object is a joint object, the matrix does not include the joint's intrinsic transformation.
Synopsis bool ikSetObjectMatrix(int objectHandle,int relativeToObjectHandle,const C4X4Matrix* matrix)
Arguments
objectHandle: the handle of the object.
relativeToObjectHandle: the handle of an object relative to which the matrix is expressed. Otherwise, specify ik_handle_world if you specify the absolute matrix, or ik_handle_parent if you specify the matrix relative to the parent object.
matrix: the transformation matrix
Return value true in case of success.
See also ikGetObjectMatrix, ikSetObjectTransformation, ikSetJointPosition, ikGetObjectHandle

ikSetObjectParent

Description Sets the parent of an object.
Synopsis bool ikSetObjectParent(int objectHandle,int parentObjectHandle,bool keepInPlace)
Arguments
objectHandle: the handle of the object.
parentObjectHandle: the desired parent object, Set -1 for no parent.
keepInPlace: if true, the object will stay in place, otherwise, it will keep its local transformation.
Return value true in case of success.
See also ikGetObjectParent, ikGetObjectHandle

ikSetObjectTransformation

Description Sets the transformation (position and quaternion) of an object. If the object is a joint object, the transformation does not include the joint's intrinsic transformation.
Synopsis bool ikSetObjectTransformation(int objectHandle,int relativeToObjectHandle,const C7Vector* transf)
Arguments
objectHandle: the handle of the object.
relativeToObjectHandle: the handle of an object relative to which the transformation is expressed. Otherwise, specify ik_handle_world if you specify the absolute transformation, or ik_handle_parent if you specify the transformation relative to the parent object.
transf: the transformation.
Return value true in case of success.
See also ikGetObjectTransformation, ikSetObjectMatrix, ikSetJointPosition, ikGetObjectHandle

ikSetSphericalJointMatrix

Description Sets the rotation transformation matrix of a spherical joint.
Synopsis bool ikSetSphericalJointMatrix(int jointHandle,const C3X3Matrix* rotMatrix)
Arguments
jointHandle: the handle of the joint.
rotMatrix: the rotation transformation matrix to apply.
Return value true in case of success.
See also ikGetJointMatrix, ikSetJointPosition, ikSetSphericalJointQuaternion, ikGetObjectHandle

ikSetSphericalJointQuaternion

Description Sets the rotation transformation of a spherical joint.
Synopsis bool ikSetSphericalJointQuaternion(int jointHandle,const C4Vector* quaternion)
Arguments
jointHandle: the handle of the joint.
quaternion: the rotation transformation to apply.
Return value true in case of success.
See also ikGetJointTransformation, ikSetSphericalJointMatrix, ikSetJointPosition, ikGetObjectHandle

ikSwitchEnvironment

Description Switches to another environment and all function calls will be directed to that environment.
Synopsis bool ikSwitchEnvironment(int handle,bool allowAlsoProtectedEnvironment=false)
Arguments
handle: handle of the environment to switch to.
allowAlsoProtectedEnvironment: set to false.
Return value true in case of success.
See also ikCreateEnvironment, ikEraseEnvironment