Skip to main content
Skip table of contents

Move B Command

Overview

Move B Command is the motion command that can help the robot to move along the straight and circular path connected to multiple waypoints and destinations within the workspace.

This function takes a list that has one or more path segments (straight or circular) as arguments and moves at a constant velocity by blending each segment into the specified radius. Here, the radius can be set through posb.

Property

Annotation

You can insert text in the description, unique meaning, or nickname for each Parameter to differentiate with many DRL Components.

Parameters

In Parameter Panel, it will help you create or select your variable to define the parameter of the chosen command.

For detailed DRL description other than parameter, please refer to the following online manual link: https://manual.doosanrobotics.com/help/programming/2.9/publish/en_us/moveb-13682544.html.

Parameter Name

Data Type

Default Value

Description

pos_list

list (posb)

-

posb list

size (v)

float

None

velocity or

velocity1, velocity2

list (float[2])

acc (a)

float

None

acceleration or

acceleration1, acceleration2

list (float[2])

time (t)

float

None

Reach time [sec]

  • When specifying time, vel and acc are ignored and processed as time.

ref

int

None

reference coordinate

  • DR_BASE: base coordinate

  • DR_WORLD: world coordinate

  • DR_TOOL: tool coordinate

  • User coordinate: Custom

courage

int

DR_MV_MOD_ABS

Movement criteria

  • DR_MV_MOD_ABS: Never

  • DR_MV_MOD_REL: Opponent

app_type

int

DR_MV_APP_NONE

Application Integration Options

  • DR_MV_APP_NONE: No integration

  • DR_MV_APP_WELD: Welding interlocking

Example

DRL Code

PY
# Init Pose @ Jx1
Jx1 = posj(45,0,90,0,90,45)		     # initial joint position
X0 = posx(370, 420, 650, 0, 180, 0)   # initial task position

# CASE 1) ABSOLUTE
# Absolute Goal Poses
X1 =  posx(370, 670, 650, 0, 180, 0)
X1a = posx(370, 670, 400, 0, 180, 0)
X1a2= posx(370, 545, 400, 0, 180, 0)
X1b = posx(370, 595, 400, 0, 180, 0)
X1b2= posx(370, 670, 400, 0, 180, 0)
X1c = posx(370, 420, 150, 0, 180, 0)
X1c2= posx(370, 545, 150, 0, 180, 0)
X1d = posx(370, 670, 275, 0, 180, 0)
X1d2= posx(370, 795, 150, 0, 180, 0)

seg11 = posb(DR_LINE, X1, radius=20)
seg12 = posb(DR_CIRCLE, X1a, X1a2, radius=20)
seg14 = posb(DR_LINE, X1b2, radius=20)
seg15 = posb(DR_CIRCLE, X1c, X1c2, radius=20)
seg16 = posb(DR_CIRCLE, X1d, X1d2, radius=20)
b_list1 = [seg11, seg12, seg14, seg15, seg16] 
# The blending radius of the last waypoint (seg16) is ignored.

movej(Jx1, vel=30, acc=60, mod=DR_MV_MOD_ABS)  
# Joint motion to the initial angle (Jx1)
movel(X0, vel=150, acc=250, ref=DR_BASE, mod=DR_MV_MOD_ABS) 
# Line motion to the initial position (X0)
moveb(b_list1, vel=150, acc=250, ref=DR_BASE, mod=DR_MV_MOD_ABS)
	# Moves the robot from the current position through a trajectory consisting of seg11(LINE), seg12(CIRCLE), seg14(LINE), 
	# seg15(CIRCLE), and seg16(CIRCLE) with a constant velocity of 150(mm/sec) with the exception of accelerating and decelerating sections.
	# (The final point is X1d2.) Blending to the next segment begins
	# when the distance of 20mm from the end point (X1, X1a2, X1b2, X1c2, and X1d2) of each segment 
	# is reached.
	
	
# CASE 2) RELATIVE 
# Relative Goal Poses
dX1 =  posx(0, 250, 0, 0, 0, 0)
dX1a = posx(0, 0, -150, 0, 0, 0)
dX1a2= posx(0, -125, 0, 0, 0, 0)
dX1b = posx(0, 50, 0, 0, 0, 0)
dX1b2= posx(0, 75, 0, 0, 0, 0)
dX1c = posx(0, -250, -250, 0, 0, 0)
dX1c2= posx(0, 125, 0, 0, 0, 0)
dX1d = posx(0, 125, 125, 0, 0, 0)
dX1d2= posx(0, 125, -125, 0, 0, 0)

dseg11 = posb(DR_LINE, dX1, radius=20)
dseg12 = posb(DR_CIRCLE, dX1a, dX1a2, radius=20)
dseg14 = posb(DR_LINE, dX1b2, radius=20)
dseg15 = posb(DR_CIRCLE, dX1c, dX1c2, radius=20)
dseg16 = posb(DR_CIRCLE, dX1d, dX1d2, radius=20)
db_list1 = [dseg11, dseg12, dseg14, dseg15, dseg16] 
# The blending radius of the last waypoint (dseg16) is ignored.

movej(Jx1, vel=30, acc=60, mod=DR_MV_MOD_ABS)   
# Joint motion to the initial angle (Jx1)
movel(X0, vel=150, acc=250, ref=DR_BASE, mod=DR_MV_MOD_ABS) 
# Line motion to the initial position (X0)
moveb(b_list1, vel=150, acc=250, ref=DR_BASE, mod=DR_MV_MOD_ABS)
	# Moves the robot from the current position through a trajectory consisting of dseg11(LINE), dseg12(CIRCLE), dseg14(LINE),
	# dseg15(CIRCLE), and dseg16(CIRCLE) with a constant velocity of 150(mm/sec) with the exception of accelerating and decelerating sections. (The final point is X1d2.) 
	# Blending to the next segment begins when the distance of 20mm from the end point (X1, X1a2, X1b2, X1c2, and X1d2) of each segment is reached. (The path is the same as CASE#1.)
JavaScript errors detected

Please note, these errors can depend on your browser setup.

If this problem persists, please contact our support.