get_solution_space
This function calculates the solution space index (0–7) for a given joint position. Each solution space represents one of the eight possible robot configurations (elbow-up/down, wrist-flip, shoulder combinations, etc.). The result is primarily used when performing inverse kinematics via ikin.
Definition
DRFLEx.h within class CDRFLEx, public section (line 673)
unsigned char get_solution_space(
float fTargetPos[NUM_JOINT]
) {
return _get_solution_space(_rbtCtrl, fTargetPos);
};
Parameter
Parameter Name |
Data Type |
Default Value |
Description |
|---|---|---|---|
fTargetPos |
float[6] |
Target joint positions (J1–J6). |
Return
Value |
Description |
|---|---|
unsigned char (0–7) |
Identifier of the solution space that the current pose belongs to. |
Example
float q1[6] = { 0.f, 0.f, 0.f, 0.f, 0.f, 0.f };
unsigned char sol = drfl.get_solution_space(q1);
std::cout << "Current solution space: " << static_cast<int>(sol) << std::endl;
This example computes the solution space index for a given joint configuration q1. The returned value (sol) indicates one of the eight possible robot postures and can be used when performing inverse-kinematic operations such as ikin() or ikin_ex().