Coppelia kinematics routines (auxiliary API)

This collection of functions allows to perform the same kinematic calculations as you are able to do from within CoppeliaSim.

The idea is to normally build your kinematic tasks inside CoppeliaSim, then to export the kinematic content of a scene, which can then directly be used with the embeddable functions below. The required source code is located here. Make sure to include all files into your project, and include ik.h in the files where you need access to the functions. Make also sure you know how to use the kinematics functionality from within CoppeliaSim first! If you have access to the regular API, then you won't need this auxiliary API, since all following functions have their regular API equivalent.

The Coppelia kinematics routines source code is not directly part of CoppeliaSim, and carries separate licensing conditions. Refer to the source code for details.

Follow the method below to perform kinematic calculations from within your own external application:

  • Build your kinematic tasks within CoppeliaSim. Test them.
  • Export the kinematic content of the scene with [Menu bar --> File --> Export --> Kinematics content...]
  • Include the Coppelia kinematics routines in your own application.
  • Call ikLaunch at application start-up, and ikShutDown at application end.
  • Call ikStart to import the previously exported file. ikStart may be called as often as desired to reset the kinematic scene. A kinematic scene is similar to a scene in CoppeliaSim, except that it is stripped of everything non-kinematic.
  • Call various functions to shift / rotate the target dummies (e.g. with ikSetObjectTransformation), or to move non-active joints, i.e. joints that are not in IK mode (e.g. with ikSetJointPosition).
  • Call ikHandleIkGroup to perform one calculation pass (i.e. effectively bringing dummy tips onto their targets). In case you are searching for a specific robot configuration, or need to instantaneously jump to a new end-effector pose, then call ikGetConfigForTipPose.
  • Repeat above last 2 steps as often as required. Make sure to check for return values to detect errors.
  • If you have several instances of a same robot, then you can call ikLaunch several times to initialize several instances of the embedded kinematics. You can then switch from one instance to another with ikSwitch.
  • Refer also to the following examples: standAloneKinematicsDemo1, standAloneKinematicsDemo2, standAloneKinematicsDemo3. Those demo applications use the Coppelia kinematics routines described here, combined with the remote API functionality to control two different robots in inverse/forward kinematics mode. The demo scenes standAloneKinematicsDemo1.ttt, standAloneKinematicsDemo2.ttt and standAloneKinematicsDemo3.ttt launch the standAloneKinematicsDemo1, standAloneKinematicsDemo2 and respectively standAloneKinematicsDemo3 applications automatically.

    ikEulerAnglesToQuaternion
    ikGetConfigForTipPose
    ikGetIkGroupHandle
    ikGetJointInterval
    ikGetJointPosition
    ikGetJointTransformation
    ikGetJointMatrix
    ikGetObjectHandle
    ikGetObjectParent
    ikGetObjectTransformation
    ikGetObjectMatrix
    ikGetRotationAxis
    ikGetRotationAxis_matrix
    ikHandleIkGroup
    ikInterpolateTransformations
    ikInterpolateMatrices
    ikInvertTransformation
    ikInvertMatrix
    ikLaunch
    ikMatrixToTransformation
    ikMultiplyTransformations
    ikMultiplyMatrices
    ikMultTransformationWithVector
    ikMultMatrixWithVector
    ikQuaternionToEulerAngles
    ikRotateAroundAxis
    ikRotateAroundAxis_matrix
    ikSetIkElementProperties
    ikSetIkGroupExplicitHandling
    ikSetIkGroupProperties
    ikSetJointInterval
    ikSetJointMode
    ikSetJointPosition
    ikSetObjectParent
    ikSetObjectTransformation
    ikSetObjectMatrix
    ikSetSphericalJointQuaternion
    ikSetSphericalJointMatrix
    ikShutDown
    ikStart
    ikSwitch
    ikTransformationToMatrix
    



    ikEulerAnglesToQuaternion (regular API equivalent: sim.getEulerAnglesFromMatrix)

    Description Retrieves a quaternion based on Euler angles. See also ikQuaternionToEulerAngles and ikTransformationToMatrix.
    C++ synopsis int ikEulerAnglesToQuaternion(const real* euler,real* quaternion)
    parameters
    euler (input): the 3 Euler angles (alpha, beta, gamma)
    quaternion (output): the 4 values of a quaternion (x, y, z, w)
    return value
    -1 if operation failed

    ikGetConfigForTipPose (regular API equivalent: sim.getConfigForTipPose)

    Description Searches for a manipulator configuration that matches a given end-effector position/orientation in space. Search is randomized.
    C++ synopsis int ikGetConfigForTipPose(int ikGroupHandle,int jointCnt,const int* jointHandles,real thresholdDist,int maxIterations,real* retConfig,const real* metric,const int* jointOptions,void* reserved)
    parameters
    ikGroupHandle (input): 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
    jointCnt (input): 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 (input): 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
    maxIterations (input): the maximum number of calculation iterations before the function returns
    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 NULL for a default metric of {1.0,1.0,1.0,0.1}
    jointOptions (input): 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 NULL.
    reserved (input/output): reserved for future extensions. Set to NULL
    return value
    -1 in case of an error, 0 if no result was found, otherwise 1.

    ikGetIkGroupHandle (regular API equivalent: sim.getIkGroupHandle)

    Description Retrieves the handle of an IK group based on its name. Specify the full IK group name, including suffixes.
    C++ synopsis int ikGetIkGroupHandle(const char* ikGroupName)
    parameters
    ikGroupName (input): the name of the IK group
    return value
    -1 if operation failed, otherwise the handle of the IK group.

    ikGetJointInterval (regular API equivalent: sim.getJointInterval)

    Description Retrieves the limits of a joint. See also ikSetJointInterval
    C++ synopsis int ikGetJointInterval(int jointHandle,real* interval)
    parameters
    jointHandle (input): handle of the joint
    interval (output): pointer to 2 values: the low limit, and the range (i.e. highLimit = lowLimit + range). If the joint is cyclic, then the interval has no meaning.
    return value
    -1 if operation failed, 0 if the limits are valid, or 1 if the joint is cyclic.

    ikGetJointPosition (regular API equivalent: sim.getJointPosition)

    Description Retrieves the intrinsic position of a joint. This function cannot be used with spherical joints (use ikGetJointTransformation instead). See also ikSetJointPosition
    C++ synopsis int ikGetJointPosition(int jointHandle,real* position)
    parameters
    jointHandle (input): handle of the joint
    position (output): intrinsic position of the joint. This is a one-dimensional value: if the joint is revolute, the rotation angle is returned, if the joint is prismatic, the translation amount is returned, etc.
    return value
    -1 if operation failed

    ikGetJointMatrix (regular API equivalent: sim.getJointMatrix)

    Description Retrieves the intrinsic matrix of a joint (the transformation matrix caused by the joint movement). See also ikSetSphericalJointMatrix and ikGetJointTransformation.
    C++ synopsis int ikGetJointMatrix(int jointHandle,real* matrix)
    parameters
    jointHandle (input): handle of the joint
    matrix (output): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikGetJointTransformation (regular API equivalent: sim.getJointMatrix)

    Description Retrieves the intrinsic transformation of a joint (the transformation caused by the joint movement). See also ikSetSphericalJointQuaternion and ikGetJointMatrix.
    C++ synopsis int ikGetJointTransformation(int jointHandle,real* position,real* quaternion)
    parameters
    jointHandle (input): handle of the joint
    position (output): the position component of the transformation (x, y, z)
    quaternion (output): the orientation component of the transformation (x, y, z, w)
    return value
    -1 if operation failed

    ikGetObjectHandle (regular API equivalent: sim.getObjectHandle)

    Description Retrieves an object handle based on its name. Specify the full object name, including suffixes.
    C++ synopsis int ikGetObjectHandle(const char* objectName)
    parameters
    objectName (input): name of the object
    return value
    -1 if operation failed, otherwise the handle of the object

    ikGetObjectParent (regular API equivalent: sim.getObjectParent)

    Description Retrieves the handle of an object's parent object. See also ikSetObjectParent.
    C++ synopsis int ikGetObjectParent(int objectHandle)
    parameters
    objectHandle (input): handle of the object
    return value
    -1 if operation failed, otherwise the handle of the parent object

    ikGetObjectMatrix (regular API equivalent: sim.getObjectMatrix)

    Description Retrieves the matrix of an object. See also ikSetObjectMatrix and ikGetObjectTransformation.
    C++ synopsis int ikGetObjectMatrix(int objectHandle,int relativeToObjectHandle,real* matrix)
    parameters
    objectHandle (input): handle of the object
    relativeToObjectHandle (input): indicates relative to which reference frame we want the transformation. Specify -1 to retrieve the absolute transformation, sim_handle_parent to retrieve the transformation relative to the object's parent, or an object handle relative to whose reference frame we want the transformation.
    matrix (output): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikGetObjectTransformation (regular API equivalent: sim.getObjectMatrix)

    Description Retrieves the transformation (position / orientation) of an object. See also ikSetObjectTransformation and ikGetObjectMatrix.
    C++ synopsis int ikGetObjectTransformation(int objectHandle,int relativeToObjectHandle,real* position,real* quaternion)
    parameters
    objectHandle (input): handle of the object
    relativeToObjectHandle (input): indicates relative to which reference frame we want the transformation. Specify -1 to retrieve the absolute transformation, sim_handle_parent to retrieve the transformation relative to the object's parent, or an object handle relative to whose reference frame we want the transformation.
    position (output): the position component of the transformation (x, y, z)
    quaternion (output): the orientation component of the transformation (x, y, z, w)
    return value
    -1 if operation failed

    ikGetRotationAxis_matrix (regular API equivalent: sim.getRotationAxis)

    Description Retrieves an axis and rotation angle that brings one matrix onto another one. The translation part of the matrix is ignored. This function, when used in combination with ikRotateAroundAxis_matrix, can be used to build interpolations between matrices. See also ikGetRotationAxis.
    C++ synopsis int ikGetRotationAxis_matrix(const real* matrixStart,const real* matrixGoal,real* axis,real* angle)
    parameters
    matrixStart (input): the first matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    matrixGoal (input): the second matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    axis (output): the rotation axis (x, y, z vector)
    angle (output): the rotation angle
    return value
    -1 if operation failed

    ikGetRotationAxis (regular API equivalent: sim.getRotationAxis)

    Description Retrieves an axis and rotation angle that brings one transformation onto another one. The translation part of the transformations is ignored. This function, when used in combination with ikRotateAroundAxis, can be used to build interpolations between transformations. See also ikGetRotationAxis_matrix.
    C++ synopsis int ikGetRotationAxis(const real* positionStart,const real* quaternionStart,const real* positionGoal,const real* quaternionGoal,real* axis,real* angle)
    parameters
    positionStart (input): the position component of the first transformation (x, y, z)
    quaternionStart (input): the orientation component of the first transformation (x, y, z, w)
    positionGoal (input): the position component of the second transformation (x, y, z)
    quaternionGoal (input): the orientation component of the second transformation (x, y, z, w)
    axis (output): the rotation axis (x, y, z vector)
    angle (output): the rotation angle
    return value
    -1 if operation failed

    ikHandleIkGroup (regular API equivalent: sim.handleIkGroup)

    Description Handles (i.e. solves) an IK group (i.e. by trying to respect the given constraints).
    C++ synopsis int ikHandleIkGroup(int ikGroupHandle)
    parameters
    ikGroupHandle (input): handle of the IK group or sim_handle_all or sim_handle_all_except_explicit. (sim_handle_all will handle all IK groups, while sim_handle_all_except_explicit will only handle those that are not marked as "explicit handling")
    return value
    number of performed calculations (i.e. when IK group calculation results are different from sim_ikresult_not_performed) if no specific IK group was specified, or a value of type IK result if a specific IK group was specified, -1 in case of an error (a failed IK group calculation is not considered as an error)

    ikInterpolateMatrices (regular API equivalent: sim.interpolateMatrices)

    Description Computes the interpolated matrix between 2 matrices. See also ikInterpolateTransformations.
    C++ synopsis int ikInterpolateMatrices(const real* matrix1,const real* matrix2,real interpolFactor,real* matrixOut)
    parameters
    matrix1 (input): the first matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    matrix2 (input): the second matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    interpolFactor (input): the interpolation factor, a value between 0.0 and 1.0 (0.0--> transformationOut=transformationIn1, 1.0--> transformationOut=transformationIn2)
    matrixOut (output): the interpolated matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikInterpolateTransformations (regular API equivalent: sim.interpolateMatrices)

    Description Computes the interpolated transformation between 2 transformations. See also ikInterpolateMatrices.
    C++ synopsis int ikInterpolateTransformations(const real* position1,const real* quaternion1,const real* position2,const real* quaternion2,real interpolFactor,real* positionOut,real* quaternionOut)
    parameters
    position1 (input): the position component of the first transformation (x, y, z)
    quaternion1 (input): the orientation component of the first transformation (x, y, z, w)
    position2 (input): the position component of the second transformation (x, y, z)
    quaternion2 (input): the orientation component of the second transformation (x, y, z, w)
    interpolFactor (input): the interpolation factor, a value between 0.0 and 1.0 (0.0--> transformationOut=transformationIn1, 1.0--> transformationOut=transformationIn2)
    positionOut (output): the position component of the interpolated transformation (x, y, z)
    quaternionOut (output): the orientation component of the interpolated transformation (x, y, z, w)
    return value
    -1 if operation failed

    ikInvertMatrix (regular API equivalent: sim.invertMatrix)

    Description Inverts a transformation matrix. See also ikInvertTransformation.
    C++ synopsis int ikInvertMatrix(real* matrix)
    parameters
    matrix (input/output): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikInvertTransformation (regular API equivalent: sim.invertMatrix)

    Description Inverts a transformation. See also ikInvertMatrix.
    C++ synopsis int ikInvertTransformation(real* position,real* quaternion)
    parameters
    position (input/output): the position component of the transformation (x, y, z)
    quaternion (input/output): the orientation component of the transformation (x, y, z, w)
    return value
    -1 if operation failed

    ikLaunch

    Description Initializes a new instance of the Coppelia kinematics routines. Should be the very first function called. See also ikShutDown and ikSwitch.
    C++ synopsis int ikLaunch()
    parameters
    none
    return value
    A value <1 if operation failed, otherwise the handle of the created instance. Several instances can be created, but only one instance will be active at a given time. You can switch from one to another instance with ikSwitch.

    ikMatrixToTransformation

    Description Retrieves a position and a quaternion from a matrix. See also ikTransformationToMatrix and ikQuaternionToEulerAngles.
    C++ synopsis int ikMatrixToTransformation(const real* matrix,real* position,real* quaternion)
    parameters
    matrix (input): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted)
    position (output): the 3 values of a position (x, y, z)
    quaternion (output): the 4 values of a quaternion (x, y, z, w)
    return value
    -1 if operation failed

    ikMultiplyMatrices (regular API equivalent: sim.multiplyMatrices)

    Description Multiplies two matrices. See also ikMultiplyTransformations.
    C++ synopsis int ikMultiplyMatrices(const real* matrix1,const real* matrix2,real* matrixOut)
    parameters
    matrix1 (input): the first matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    matrix2 (input): the second matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    matrixOut (output): the resulting matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikMultiplyTransformations (regular API equivalent: sim.multiplyMatrices)

    Description Multiplies two transformation. See also ikMultiplyMatrices.
    C++ synopsis int ikMultiplyTransformations(const real* position1,const real* quaternion1,const real* position2,const real* quaternion2,real* positionOut,real* quaternionOut)
    parameters
    position1 (input): the position component of the first transformation (x, y, z)
    quaternion1 (input): the orientation component of the first transformation (x, y, z, w)
    position2 (input): the position component of the second transformation (x, y, z)
    quaternion2 (input): the orientation component of the second transformation (x, y, z, w)
    positionOut (output): the position component of the multiplication (x, y, z)
    quaternionOut (output): the orientation component of the multiplication (x, y, z, w)
    return value
    -1 if operation failed

    ikMultMatrixWithVector (regular API equivalent: sim.transformVector)

    Description Multiplies a vector with a matrix (v=m*v). See also ikMultTransformationWithVector.
    C++ synopsis int ikMultMatrixWithVector(const real* matrix,real* vect)
    parameters
    matrix (input): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    vect (input/output): the vector to transform (x, y, z)
    return value
    -1 if operation failed

    ikMultTransformationWithVector (regular API equivalent: sim.transformVector)

    Description Multiplies a vector with a transformation (v=tr*v). See also ikMultMatrixWithVector.
    C++ synopsis int ikMultTransformationWithVector(const real* position,const real* quaternion,real* vect)
    parameters
    position (input): the position component of the transformation (x, y, z)
    quaternion (input): the orientation component of the transformation (x, y, z, w)
    vect (input/output): the vector to transform (x, y, z)
    return value
    -1 if operation failed

    ikQuaternionToEulerAngles (regular API equivalent: sim.getQuaternionFromMatrix)

    Description Retrieves Euler angles based on a quaternion. See also ikEulerAnglesToQuaternion and ikMatrixToTransformation.
    C++ synopsis int ikQuaternionToEulerAngles(const real* quaternion,real* euler)
    parameters
    quaternion (input): the 4 values of a quaternion (x, y, z, w)
    euler (output): the 3 Euler angles (alpha, beta, gamma)
    return value
    -1 if operation failed

    ikRotateAroundAxis_matrix (regular API equivalent: sim.rotateAroundAxis)

    Description Rotates a matrix around a specific axis in space. This function, when used in combination with ikGetRotationAxis_matrix, can be used to build interpolations between matrices. See also ikRotateAroundAxis.
    C++ synopsis int ikRotateAroundAxis_matrix(const real* matrixIn,const real* axisVector,const real* axisPosition,real angle,real* matrixOut)
    parameters
    matrixIn (input): the input matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    axisVector (input): the axis vector (x, y, z)
    axisPosition (input): the axis position (x, y, z)
    angle (input): the desired rotation angle
    matrixOut (output): the output matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikRotateAroundAxis (regular API equivalent: sim.rotateAroundAxis)

    Description Rotates a transformation around a specific axis in space. This function, when used in combination with ikGetRotationAxis, can be used to build interpolations between transformations. See also ikRotateAroundAxis_matrix.
    C++ synopsis int ikRotateAroundAxis(const real* positionIn,const real* quaternionIn,const real* axisVector,const real* axisPosition,real angle,real* positionOut,real* quaternionOut)
    parameters
    positionIn (input): the position component of a transformation (x, y, z)
    quaternionIn (input): the orientation component of a transformation (x, y, z, w)
    axisVector (input): the axis vector (x, y, z)
    axisPosition (input): the axis position (x, y, z)
    angle (input): the desired rotation angle
    positionOut (output): the position component of the rotated transformation (x, y, z)
    quaternionOut (output): the orientation component of the rotated transformation (x, y, z, w)
    return value
    -1 if operation failed

    ikSetIkElementProperties (regular API equivalent: sim.setIkElementProperties)

    Description Sets properties of a specific IK element. See also ikSetIkGroupProperties and ikGetIkGroupHandle.
    C++ synopsis int ikSetIkElementProperties(int ikGroupHandle,int tipDummyHandle,int constraints,const real* precision,const real* weight)
    parameters
    ikGroupHandle (input): handle of the IK group
    tipDummyHandle (input): handle of the tip dummy object of the IK element
    constraints (input): the constraints of the ik element. sim_ik_avoidance_constraint is not allowed
    precision (input): an array of two values where the first represents the linear precision, and the second the angular precision. Can be NULL to keep current settings.
    weight (input): an array of two values that represent the linear and angular resolution weights. Can be NULL to keep current settings
    return value
    -1 if operation failed

    ikSetIkGroupExplicitHandling (regular API equivalent: sim.setExplicitHandling)

    Description Sets the explicit handling flags for an IK group. An IK group flagged as "explicit handling" will only be handled or solved when called explicitely with ikHandleIkGroup(ikGroupHandle) or ikHandleIkGroup(sim_handle_all).
    C++ synopsis int ikSetIkGroupExplicitHandling(int ikGroupHandle,bool explicitHandling)
    parameters
    ikGroupHandle (input): handle of the IK group
    explicitHandling (input): the desired explicit handling state
    return value
    -1 if operation failed

    ikSetIkGroupProperties (regular API equivalent: sim.setIkGroupProperties)

    Description Sets properties of an IK group. See also ikSetIkElementProperties
    C++ synopsis int ikSetIkGroupProperties(int ikGroupHandle,int resolutionMethod,int maxIterations,real damping)
    parameters
    ikGroupHandle (input): handle of the IK group
    resolutionMethod (input): the IK resolution method
    maxIterations (input): the maximum number of iterations for the calculations
    damping (input): the DLS damping factor
    return value
    -1 if operation failed

    ikSetJointInterval (regular API equivalent: sim.setJointInterval)

    Description Sets the limits of a joint. See also ikGetJointInterval
    C++ synopsis int ikSetJointInterval(int jointHandle,int cyclic,real* interval)
    parameters
    jointHandle (input): handle of the joint
    cyclic (input): 1 if the joint should be cyclic (i.e. without limits), 0 otherwise.
    interval (input): pointer to 2 values: the low limit, and the range (i.e. highLimit = lowLimit + range).
    return value
    -1 if operation failed.

    ikSetJointMode (regular API equivalent: sim.setJointMode)

    Description Sets the operation mode of a joint. Might have as side-effect the change of additional properties of the joint.
    C++ synopsis int ikSetJointMode(int jointHandle,int jointMode)
    parameters
    jointHandle (input): handle of the joint
    jointMode (input): a joint mode value
    return value
    -1 if operation failed

    ikSetJointPosition (regular API equivalent: sim.setJointPosition)

    Description Sets the intrinsic position of a joint. This function cannot be used with spherical joints (use ikSetSphericalJointQuaternion instead). See also ikGetJointPosition
    C++ synopsis int ikSetJointPosition(int jointHandle,real position)
    parameters
    jointHandle (input): handle of the joint
    position (input): position of the joint (angular or linear value depending on the joint type)
    return value
    -1 if operation failed

    ikSetObjectParent (regular API equivalent: sim.setObjectParent)

    Description Sets an object's parent object. See also ikGetObjectParent.
    C++ synopsis int ikSetObjectParent(int objectHandle,int parentObjectHandle,bool keepInPlace)
    parameters
    objectHandle (input): handle of the object that will become child of the parent object
    parentObjectHandle (input): handle of the object that will become parent, or -1 if the object should become parentless
    keepInPlace (input): indicates whether the object's absolute position and orientation should stay same
    return value
    -1 if operation failed

    ikSetObjectMatrix (regular API equivalent: sim.setObjectMatrix)

    Description Sets the matrix of an object. See also ikGetObjectMatrix and ikSetObjectTransformation.
    C++ synopsis int ikSetObjectMatrix(int objectHandle,int relativeToObjectHandle,const real* matrix)
    parameters
    objectHandle (input): handle of the object
    relativeToObjectHandle (input): indicates relative to which reference frame the transformation is specified. Specify -1 to set the absolute transformation, sim_handle_parent to set the transformation relative to the object's parent, or an object handle relative to whose reference frame the transformation is specified.
    matrix (input): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikSetObjectTransformation (regular API equivalent: sim.setObjectMatrix)

    Description Sets the transformation (position / orientation) of an object. See also ikGetObjectTransformation and ikSetObjectMatrix.
    C++ synopsis int ikSetObjectTransformation(int objectHandle,int relativeToObjectHandle,const real* position,const real* quaternion)
    parameters
    objectHandle (input): handle of the object
    relativeToObjectHandle (input): indicates relative to which reference frame the transformation is specified. Specify -1 to set the absolute transformation, sim_handle_parent to set the transformation relative to the object's parent, or an object handle relative to whose reference frame the transformation is specified.
    position (input): the position component of the transformation (x, y, z)
    quaternion (input): the orientation component of the transformation (x, y, z, w)
    return value
    -1 if operation failed

    ikSetSphericalJointMatrix (regular API equivalent: sim.setSphericalJointMatrix )

    Description Sets the intrinsic matrix of a spherical joint object. This function cannot be used with non-spherical joints (use ikSetJointPosition instead). See also ikGetJointMatrix and ikSetSphericalJointQuaternion.
    C++ synopsis int ikSetSphericalJointMatrix(int jointHandle,const real* matrix)
    parameters
    jointHandle (input): handle of the joint
    matrix (input): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted))
    return value
    -1 if operation failed

    ikSetSphericalJointQuaternion (regular API equivalent: sim.setSphericalJointMatrix )

    Description Sets the intrinsic quaternion of a spherical joint object. This function cannot be used with non-spherical joints (use ikSetJointPosition instead). See also ikGetJointTransformation and ikSetSphericalJointMatrix.
    C++ synopsis int ikSetSphericalJointQuaternion(int jointHandle,const real* quaternion)
    parameters
    jointHandle (input): handle of the joint
    quaternion (input): the quaternion (x, y, z, w)
    return value
    -1 if operation failed

    ikShutDown

    Description Deinitializes the active instance of the Coppelia kinematics routines. Should be the very last function called. See also ikLaunch and ikSwitch.
    C++ synopsis int ikShutDown()
    parameters
    none
    return value
    -1 if operation failed, otherwise the handle of the newly active instance (or 0 if there is no active instance left).

    ikStart

    Description Imports a previously exported kinematic scene content. Can be called at any time to reset the object/joint configurations.
    C++ synopsis int ikStart(unsigned char* data,int dataLength)
    parameters
    data (input): pointer to the data to import
    dataLength (input): the size of the data to import
    return value
    -1 if operation failed, otherwise the number of imported objects

    ikSwitch

    Description Switches to another instance of an exported kinematic scene content. See also ikLaunch.
    C++ synopsis bool ikSwitch(int instanceHandle)
    parameters
    instanceHandle (input): the handle of a kinematic scene content instance, previously returned from ikLaunch.
    return value
    false if operation failed.

    ikTransformationToMatrix

    Description Retrieves a matrix from a position and a quaternion. See also ikMatrixToTransformation and ikEulerAnglesToQuaternion.
    C++ synopsis int ikTransformationToMatrix(const real* position,const real* quaternion,real* matrix)
    parameters
    position (input): the 3 values of a position (x, y, z)
    quaternion (input): the 4 values of a quaternion (x, y, z, w)
    matrix (output): the matrix (Xx, Yx, Zx, Px, Xy, Yy, Zy, Py, Xz, Yz, Zz, Pz. (last row, i.e. 0, 0, 0, 1 is omitted)
    return value
    -1 if operation failed