ikin_norm(pos, sol_space, ref, ref_pos_opt)
Features
This function returns the joint position corresponding to sol_space, which is equivalent to the robot pose in the operating space, among 8 joint shapes. Joint position is returned according to closest joint position depend on option(ref_pos_opt). Through status of return value, you can check whether current robot pose is in wrist singularity or out of operating region.
Note
- After SW version V2.9, It is possible to correct robot DH parameters for improving accuracy. Robots after SW version V2.10.1 are released with calibrated DH parameters for improving accuracy.
- This function returns inverse kinematics solution related to each robot model's well known nominal DH parameters before calibrated DH parameters.
- Refer to ikin() command to find the inverse kinematics solution related to calibrated DH parameters.
Parameters
Parameter Name | Data Type | Default Value | Description |
pos | posx | - | posx or position list |
list (float[6]) | |||
sol_space | int | - | solution space |
ref | int | DR_BASE | reference coordinate
|
ref_pos_opt | int | 0 | Determine closest joint position depend on option among multi turn solutions
|
Robot configuration vs. solution space
Solution space | Binary | Shoulder | Elbow | Wrist |
0 | 000 | Lefty | Below | No Flip |
1 | 001 | Lefty | Below | Flip |
2 | 010 | Lefty | Above | No Flip |
3 | 011 | Lefty | Above | Flip |
4 | 100 | Righty | Below | No Flip |
5 | 101 | Righty | Below | Flip |
6 | 110 | Righty | Above | No Flip |
7 | 111 | Righty | Above | Flip |
Return
Value | Description |
---|---|
posj | Joint space point |
status |
|
Exception
Exception | Description |
---|---|
DR_Error (DR_ERROR_TYPE) | Parameter data type error occurred |
DR_Error (DR_ERROR_VALUE) | Parameter value is invalid |
DR_Error (DR_ERROR_RUNTIME) | C extension module error occurred |
DR_Error (DR_ERROR_STOP) | Program terminated forcefully |
Example
x1 = posx(370.9, 719.7, 651.5, 90, -180, 0)
q1, status = ikin(x1, 2, DR_BASE, ref_pos_opt=0) # Joint angle q1 where the coordinate of the robot edge is x1 (second of 8 cases), reference joint position : posj(0,0,0,0,0,0)
# q1=posj(60.3, 81.0, -60.4, -0.0, 159.4, -29.7) (M1013, tcp=(0,0,0))
movej(q1,v=10,a=20)