get_current_solution_space
This is a function for checking information on the pose of the robot in the robot controller.
Definition
DRFLEx.h within class CDRFLEx, public section (line 713)
unsigned char get_current_solution_space() {
return _get_current_solution_space(_rbtCtrl);
};
Parameter
None
Return
Value |
Description |
|---|---|
unsigned char (0~7) |
Index value indicating the current solution space of the robot. |
Example
unsigned char iSolutionSpace = drfl.get_current_solution_space();
// Moves (MoveJ) if the robot maintains the current pose
float point[6] = { 10, 10, 10, 10, 10, 10 };
drfl.movejx(point, iSolutionSpace, 30, 30);
In this example, the function retrieves the robot’s current solution space ID and uses it as an argument for movejx(). This ensures that the robot maintains the same inverse-kinematic posture (elbow up/down, wrist flip, etc.) during subsequent motions. Solution spaces typically range from 0 to 7, corresponding to unique robot joint configurations.