Definition
movejx(pos, vel, acc, time, radius, ref, mod, ra, sol, velx)
Features
The robot moves to the target position (pos) within the joint space.
Since the target position is inputted as a posx form in the task space, it moves in the same way as movel. However, since this robot motion is performed in the joint space, it does not guarantee a linear path to the target position. In addition, one of 8 types of joint combination (robot configurations) corresponding to the task space coordinate system (posx) must be specified in sol (solution space). When DR_SOL_AUTO(255) is entered into sol, it moves to robot configuration that is the closest to the current configuration, (the smallest L2 norm in the joint space of axes 2-5) among the eight joint combination types.
Note
From SW version V3.2, movejx is only supported as 2.x compatible form, and the functionality for the new posx type is supported in movej.
Parameters
|
Parameter Name |
Data Type |
Default Value |
Description |
|---|---|---|---|
|
pos |
posx |
- |
posx or position list |
|
list (float[6]) |
|||
|
vel (v) |
float |
None |
velocity (same to all axes) or velocity (to an axis) |
|
list (float[6]) |
None |
||
|
acc (a) |
float |
None |
acceleration (same to all axes) or acceleration (acceleration to an axis) |
|
list (float[6]) |
None |
||
|
time (t) |
float |
None |
Reach time [sec] |
|
radius (r) |
float |
None |
Radius for blending |
|
ref |
int |
None |
Reference coordinate
|
|
mod |
int |
DR_MV_MOD_ABS |
Movement basis
|
|
ra |
int |
DR_MV_RA_DUPLICATE |
Reactive motion mode
|
|
sol |
int |
0 |
Solution space
|
|
velx |
float |
None |
TCP speed limiting |
Note
-
Abbreviated parameter names are supported. (v:vel, a:acc, t:time, r:radius)
-
_global_velj is applied if vel is None. (The initial value of _global_velj is 0.0 and can be set by set_velj.)
-
_global_accj is applied if acc is None. (The initial value of _global_accj is 0.0 and can be set by set_accj.)
-
If the time is specified, values are processed based on time, ignoring vel and acc.
-
If the time is None, it is set to 0.
-
If the radius is None, it is set to the blending radius in the blending section and 0 otherwise.
-
_g_coord is applied if the ref is None. (The initial value of _g_coord is DR_BASE, and it can be set by the set_ref_coord command.)
-
Using the blending in the preceding motion generates an error in the case of input with relative motion (mod=DR_MV_MOD_REL), and it is recommended to blend using movej() or movel().
-
Refer to the description of movej() and movel() for blending according to option ra and vel/acc.
-
_global_velx is applied if velx is None and clamp is DR_ON in set_velx. (The initial value of _global_velx is 0.0 and can be set by set_velx.)
Caution
-
In versions below SW V2.8, if the blending radius exceeds 1/2 of the total moving distance, the motion is not operated because it affects the motion after blending, and the running task program is terminated when a blending error occurs
-
In SW V2.8 or later, if the blending radius exceeds 1/2 of the total moving distance, the blending radius size is automatically changed to 1/2 of the total moving distance, and the change history can be checked in the information log message.
Robot configuration (shape 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 |
|
DR_SOL_AUTO(255) |
Auto Calculation (the smallest L2 norm in the joint space of axes 2-5) |
|||
Return
|
Value |
Description |
|---|---|
|
0 |
Success |
|
Negative value |
Error |
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
P0 = posj(0,0,90,0,90,0)
movej(P0, v=30, a=30)
P1 = posx(400,500,800,0,180,0)
P2 = posx(400,500,500,0,180,0)
movel(P2, vel=100, acc=200) # Linear movement to P2
X_tmp, sol_init = get_current_posx() # Obtains the current solution space from the P2 position
movejx(P1, vel=30, acc=60, sol=sol_init)
# Moves to the joint angle with a velocity and acceleration of 30(deg/sec) and 60(deg/sec2), respectively,
# when the TCP edge is the P1 position (maintaining the solution space in the last P2 position)
movejx(P2, time=5, sol=2)
# Moves to the joint angle with a reach time of 5 sec when the TCP edge is at the P2 position
# (forcefully sets a solution space to 2)
movejx(P1, vel=[10, 20, 30, 40, 50, 60], acc=[20, 20, 30, 30, 40, 40], radius=100, sol=2)
# Moves the robot to the joint angle when the TCP edge is at the P1 position,
# and the next motion is executed when the distance from the P2 position is 100mm.
movejx(P2, v=30, a=60, ra= DR_MV_RA_OVERRIDE, sol=2)
# Immediately terminates the last motion and blends it to move to the joint angle
# when the TCP edge is at the P2 position.
movejx(P1, v=60, a=60, sol=255, velx=100)
# Adjust the TCP speed so that it does not exceed 100 mm/s, and move to the joint angle
# when the TCP edge is at the P1 position.