ikin_norm

This function performs inverse kinematics with normalization applied to the resulting joint angles. It calculates the joint position corresponding to the given TCP pose (fSourcePos) and adjusts the output to remain within normalized joint limits, ensuring consistent solutions across different configurations.

Definition
DRFLEx.h within class CDRFLEx, public section (line 669)

LPINVERSE_KINEMATIC_RESPONSE ikin_norm(
    float fSourcePos[NUM_TASK],
    unsigned char iSolutionSpace,
    COORDINATE_SYSTEM eTargetRef,
    unsigned char iRefPosOpt
) {
    return _ikin_norm(_rbtCtrl, fSourcePos, iSolutionSpace, eTargetRef, iRefPosOpt);
};

Parameter

Parameter Name

Data Type

Default Value

Description

fSourcePos

float[6]

Target TCP position in task space (x, y, z, Rx, Ry, Rz).

iSolutionSpace

unsigned char

Solution space index (0-7) selecting one of eight valid IK configurations.
(shoulder left/right, elbow above/below, wrist flip/no-flip).

eTargetRef

COORDINATE_SYSTEM

COORDINATE_SYSTEM_BASE

Reference coordinate system for the TCP.

iRefPosOpt

unsigned char

Reference joint position option used when selecting among multiple IK solutions.
0: Selects the solution closest to posj(0,0,0,0,0,0)
1: Selects the solution closest to the current joint angles.

Return

Value

Description

LPINVERSE_KINEMATIC_RESPONSE

Normalized inverse-kinematics response structure containing
the calculated and normalized joint positions.
Refer to the definition of the structure in the Structures section.

Example

float tcp_pose[6] = { 500.0f, 400.0f, 300.0f, 180.0f, 0.0f, 90.0f };

LPINVERSE_KINEMATIC_RESPONSE res =
    drfl.ikin_norm(tcp_pose, 1, COORDINATE_SYSTEM_BASE, 1);

if (res && res->status == 0)
{
    // Use the joint solution returned by ikin_norm.
    // (Member name may differ by version; use the joint array provided in the response.)
    float q[6] = {0};
    for (int i = 0; i < 6; ++i)
        q[i] = res->posj[i];

    drfl.movej(q, 50, 20);
}
else
{
    // status:
    // 0: Valid joint solution returned
    // 1: Target pose is outside the robot workspace
    // 2: Wrist-axis singularity detected
}

In this example, the target TCP pose tcp_pose is solved for solution space 1 in the BASE frame. The resulting joint angles are normalized (e.g., within ±π range) to prevent discontinuities. This is useful when performing continuous path motions or calibration that require consistent joint states.