Motion
/<namespace>/motion/<motion_service>
move_joint
float64[6] pos # target joint angle list [degree] float64 vel # Velocity float64 acc # Acceleration float64 time #= 0.0 # Time [sec] float64 radius #=0.0 # Radius under blending mode int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 int8 blendType #= 0 # BLENDING_SPEED_TYPE_DUPLICATE=0, BLENDING_SPEED_TYPE_OVERRIDE=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_line
float64[6] pos # target float64[2] vel # Velocity float64[2] acc # Acceleration float64 time #= 0.0 # Time [sec] float64 radius #=0.0 # Radius under blending mode int8 ref #= 0 # MOVE_REFERENCE_BASE=0, MOVE_REFERENCE_TOOL=1 int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 int8 blendType #= 0 # BLENDING_SPEED_TYPE_DUPLICATE=0, BLENDING_SPEED_TYPE_OVERRIDE=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_jointx
float64[6] pos # target joint angle list [degree] float64 vel # Velocity float64 acc # Acceleration float64 time #= 0.0 # Time [sec] float64 radius #=0.0 # Radius under blending mode int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 int8 blendType #= 0 # BLENDING_SPEED_TYPE_DUPLICATE=0, BLENDING_SPEED_TYPE_OVERRIDE=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_circle
std_msgs/Float64MultiArray[] pos # target[2][6] float64[2] vel # Velocity float64[2] acc # Acceleration float64 time #= 0.0 # Time [sec] float64 radius #=0.0 # Radius under blending mode int8 ref #= 0 # MOVE_REFERENCE_BASE=0, MOVE_REFERENCE_TOOL=1 int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 float64 angle1 #= 0.0 # angle1 float64 angle2 #= 0.0 # angle2 int8 blendType #= 0 # BLENDING_SPEED_TYPE_DUPLICATE=0, BLENDING_SPEED_TYPE_OVERRIDE=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_spline_joint
std_msgs/Float64MultiArray[] pos # target [100][6] pos int8 posCnt # target cnt float64 vel # Velocity float64 acc # Acceleration float64 time #= 0.0 # Time [sec] int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_spline_task
std_msgs/Float64MultiArray[] pos # target int8 posCnt # target cnt float64[2] vel # Velocity float64[2] acc # Acceleration float64 time #= 0.0 # Time [sec] int8 ref #= 0 # MOVE_REFERENCE_BASE=0, MOVE_REFERENCE_TOOL=1 int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 int8 opt #= 0 # SPLINE_VELOCITY_OPTION_DEFAULT=0, SPLINE_VELOCITY_OPTION_CONST=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_blending
std_msgs/Float64MultiArray[] segment #50 x (pos1[6]:pos2[6]:type[1]:radius[1]) int8 posCnt # target cnt float64[2] vel # Velocity float64[2] acc # Acceleration float64 time #= 0.0 # Time [sec] int8 ref #= 0 # MOVE_REFERENCE_BASE=0, MOVE_REFERENCE_TOOL=1 int8 mode #= 0 # MOVE_MODE_ABSOLUTE=0, MOVE_MODE_RELATIVE=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_spiral
float64 revolution # Revolution float64 maxRadius # float64 maxLength # float64[2] vel # Velocity float64[2] acc # Acceleration float64 time #= 0.0 # Time [sec] int8 taskAxis # TASK_AXIS_X = 0, TASK_AXIS_Y = 1, TASK_AXIS_Z = 2 int8 ref #= 1 # MOVE_REFERENCE_BASE=0, MOVE_REFERENCE_TOOL=1 int8 syncType #=0 # SYNC = 0, ASYNC = 1
move_periodic
9
move_wait
10
GPIO
set_digital_output
get_digital_input
set_tool_digital_output
get_tool_digital-input
set_analog_output
get_analog_input
set_analog_output_type
get_analog_input_type
Modbus
set_modbus_output
get_modbus_input
config_create_modbus
config_delete_modbus
TCP
set_current_tcp
get_current_tcp
config_create_tcp
config_delete_tcp
Tool
set_current_tool
get_current_tool
config_create_tool
config_delete_tool
DRL
drl_pause
drl_resume
drl_start
drl_stop
Gripper
robotiq_2f_open
robotiq_2f_close
robotiq_2f_move
Serial
serial_open
not used
serial_close
not used