Motion

All motion commands, except for move_until, do not wait for the motion to complete. If you need to wait for the motion to complete, please use sync()

Start Recording Motion Trajectory 3.1.11

start_record_trajectory(time)
  • Parameters
    • time: Sampling period, minimum 0.01s, default 0.1s

End Recording Motion Trajectory 3.1.11

end_record_trajectory(name)

End recording motion trajectory and store the trajectory in name

Playback Motion Trajectory 3.1.11

motion_id = move_trajectory(name)

Enter Teaching Mode

teach_mode()

When the robot is in Idle state, calling this command can enter teaching (free-drive) mode. In teaching mode, each joint of the robot can be freely dragged, hence it's also called free-drive mode. The end load configuration will affect the teaching effect. If the set value is larger than the actual load, the robot will exert force upwards, and vice versa. Please check carefully.

The command has no return value.

WARNING

When the robot is not in idle state, calling this command will produce an error 1000: The robot can only be taught when it is idle.

Exit Teaching Mode

end_teach_mode()

When the robot is in Teaching state, i.e., teaching (free-drive) mode, calling this command can exit teaching mode and return to Idle state. Calling in other modes does not produce an error.

The command has no return value.

Pause Motion 3.1.24

Pause all motions. Does not affect task running status.

pause_move()

Resume Motion 3.1.24

Resume all motions. Does not affect task running status.

resume_move()

Stop Motion

Stop all motions, but cannot cancel subsequent new motion commands. This command is the internal implementation mechanism of the move_until series of commands.

stop_move()
Example Program

You can use the following code to implement the move_until functionality

disable_auto_sync()

motion_id = movej({j1 = 0, j2 = 1.57, j3 = -1.57, j4 = 0, j5 = 3.14, j6 = 3.14}, 1.0, 0.2, 0, 0)
function wait_io()
  while get_tcp_dio(1) != 1
  do
    wait(10)
  end
  stop_move()
end
task_wait_move = async_task(wait_move, motion_id)
task_wait_io = async_task(wait_io)
wait_any(task_wait_move, task_wait_io) -- Wait for any task to complete

Wait for Motion to Complete 3.1.23

wait_move(motion_id)
  • Parameters
    • motion_id: motion_id returned by move_xxx. Optional, default is 0 for all motions

Joint Motion

motion_id = movej(p, a, v, t, r)

Execute linear motion in joint space. To use this command, the robot must be in a stationary state or the previous command is movej or movel with blending.

This call will return immediately and will not wait for the motion to complete. You can query the status until idle using get_robot_mode, or call the sync instruction to make the robot synchronously wait for all current instructions to complete.

  • Parameters
    • p: Joint position, or coordinate position (which will be converted to joint position through inverse kinematics).
      • If it's {j1 = 0.1, j2 = 0.2, j3 = 0.2, j4 = 0.3, j5 = 0.1, j6 = 0.2}, it represents joint position.
      • If it's {x, y, z, Rz, Ry, Rx}, it represents coordinate position.
    • a: Joint acceleration of the main axis (rad/s2), maximum can be set to the maximum acceleration in safety settings.
    • v: Joint speed of the main axis (rad/s), maximum can be set to the maximum speed in safety settings.
    • t: Motion time (s).
      • When t > 0, the speed parameter v and acceleration a are invalid. 2.1
      • Due to the influence of maximum acceleration and maximum speed in safety settings, the motion time will be automatically extended.
    • r: Blending radius (m). Used to specify the smoothness of the path.
      • 0 indicates turning off smooth motion.
      • r > 0 indicates enabling smooth motion (maximum blending radius is 1 m), during transition it may not pass through the target position.

Joint Motion Until auto_sync

movej_until(p, a, v, t, fn)

Execute motion command. If you need to stop the current motion when a certain condition occurs during the motion, use the move until series of commands.

Compared to Joint Motion, the setting of blending radius r is cancelled and replaced with a callback function fn. The effect of this callback function is that when the motion command is executed, the system will call this function once every cycle (about 10ms). If this function returns true, it will automatically call the Stop Motion command to stop the current motion. If this function never returns true, the robot will eventually move to p. If this function cannot be completed within 10ms, it will cause skipping of judgment for several subsequent cycles.

Example Program

In Lua syntax, functions can be anonymous.

movej_until({j1 = 0, j2 = 1.57, j3 = -1.57, j4 = 0, j5 = 3.14, j6 = 3.14}, 1.2, 0.2, 0, function()
  return get_aio(2) > 10
end)

Linear Motion

motion_id = movel(p, a, v, t, r)

Execute linear motion path in tool space. To use this command, the robot must be in a stationary state or the previous command is movej or movel with blending.

  • Parameters are basically the same as Joint Motion:
    • p: Coordinate position, or joint position (which will be converted to coordinate position through forward kinematics).
    • a: Tool space acceleration (m/s2).
    • v: Tool space speed (m/s). Note that the speed and acceleration here refer to the description in tool space.
Example Program
movel({0.2, 0.5, 0.4, 0, 0, 1.57}, 1.0, 0.2, 0, 0)
movel({j1 = 0, j2 = 1.57, j3 = -1.57, j4 = 0, j5 = 3.14, j6 = 3.14}, 1.0, 0.2, 0, 0)

Linear Motion Until auto_sync

movel_until(p, a, v, t, fn)

Execute linear motion path in tool space, i.e., linear motion, and stop when the specified condition is met.

Refer to the explanations of Linear Motion and Joint Motion Until.

Example Program
movel_until({0.2, 0.5, 0.4, 0, 0, 1.57}, 1.0, 0.2, 0, function()
  return get_tcp_dio(1) == 0
end)

Hybrid Motion

Linear motion. Unlike movel, it will automatically switch to joint motion when encountering singular positions.

motion_id = move_hybrid(p, a, v, t, r)
  • Parameters are basically the same as Joint Motion:
    • p: Coordinate position, or joint position (which will be converted to coordinate position through forward kinematics).
    • a: Tool space acceleration (m/s2).
    • v: Tool space speed (m/s). Note that the speed and acceleration here refer to the description in tool space.
Example Program
move_hybrid({0.2, 0.5, 0.4, 0, 0, 1.57}, 1.0, 0.2, 0, 0)
move_hybrid({j1 = 0, j2 = 1.57, j3 = -1.57, j4 = 0, j5 = 3.14, j6 = 3.14}, 1.0, 0.2, 0, 0)

Arc Motion

motion_id = movec(via, p, rad, a, v, t, r)

Perform arc motion in tool space, the path is the unique circle composed of the current position, via and p. If the three points are on a straight line and cannot draw a circle, or if the distance between points is too small resulting in a circle that is too large or too small, the command will fail to execute. The robot's posture after completing the arc motion is consistent with p, regardless of rad.

  • For detailed explanation of parameters, please refer to Joint Motion.
    • via: Via position. Coordinate position, or joint position (which will be converted to coordinate position).
    • p: Target position. Coordinate position, or joint position (which will be converted to coordinate position).
    • rad: Arc radian of the path (rad). Used to specify the radian size of the arc motion.
      • Specially and by default, when rad = 0, it means moving to p as the end point.
      • If rad > 0, it means moving along an arc motion trajectory, passing through via and p, and rotating the corresponding rad.
      • If rad < 0, it means moving along the arc motion trajectory in the opposite direction, via and p may not necessarily be passed through in this mode.
    • a: Tool space acceleration (m/s2)
    • v: Tool space speed (m/s)
    • t: Motion time (s)
    • r: Blending radius (m)
Example Program
movec({0.2, 0.5, 0.4, 0, 0, 1.57}, {j1 = 0.1, j2 = 0.2, j3 = 0.2, j4 = 0.3, j5 = 0.1, j6 = 0.2}, 0.0, 1.0, 0.2, 0)

Arc Motion Until auto_sync

movec_until(via, p, rad, a, v, t, fn)

Perform arc motion in tool space and stop when the specified condition is met.

Refer to the explanations of Arc Motion and Joint Motion Until.

Example Program
movec_until({0.2, 0.5, 0.4, 0, 0, 1.57}, {j1 = 0.1, j2 = 0.2, j3 = 0.2, j4 = 0.3, j5 = 0.1, j6 = 0.2}, 0.0, 1.0, 0.2, 0, function()
  return get_tcp_dio(1) == 0
end)

move_pvat 2.3.5

move_pvat(p, v, a, t)

Specify the velocity and acceleration of each joint to make the robot perform continuous servo motion.

WARNING

  • The minimum time that can be set is 0.01 (10ms), path points less than this value will be skipped.
  • The sending interval between 2 adjacent points must be less than t, exceeding t will cause the robot to automatically slow down and stop.
  • Parameters
    • p: Joint position
    • v: Velocity of each joint (rad/s)
    • a: Acceleration of each joint (rad/s2)
    • t: Motion time (s)
Example Program
move_pvat({j1=0.279099,j2=0.0499054,j3=0.320451,j4=0.172128,j5=1.67471,j6=0.427222}, {0.00141239,0.017133,0.015709,0.0477418,0.0037477,0.0504095}, 0, 0.01)

move_pvat({-0.490491,-0.257047,-0.0192966,-1.60649,-0.311108,2.14048}, 0.1, 0, 0.01)

move_pvt 2.3.5

move_pvt(p, v, t)

Same as move_pvat, the robot automatically estimates the acceleration of each joint

  • Parameters
    • p: Joint position
    • v: Velocity of each joint (rad/s)
    • t: Motion time (s)
Example Program
move_pvt({j1=0.279099,j2=0.0499054,j3=0.320451,j4=0.172128,j5=1.67471,j6=0.427222}, {0.00141239,0.017133,0.015709,0.0477418,0.0037477,0.0504095}, 0.01)

move_pvt({-0.490491,-0.257047,-0.0192966,-1.60649,-0.311108,2.14048}, 0.1, 0.01)

move_pt 2.3.5

move_pt(p, t)

Same as move_pvat, the robot automatically estimates the velocity and acceleration of each joint

  • Parameters
    • p: Joint position
    • t: Motion time (s)
Example Program
move_pt({j1=0.279099,j2=0.0499054,j3=0.320451,j4=0.172128,j5=1.67471,j6=0.427222}, 0.01)

Example

local v = 0.06
local a = 0.1

function draw☆(base, r)
  movej(base, 0.4, 1, 0, 1)

  local b = pose_times(base, {-r * math.sin(math.rad(18)), -r * math.cos(math.rad(18)), 0, 0, 0, 0})
  movel(b, v, a, 0, 0)

  local c = pose_times(base, {r / 2, -r / 2 * math.cos(math.rad(36)), 0 , 0, 0, 0})
  movel(c, v, a, 0, 0)

  local d = pose_times(base, {-r / 2, -r / 2 * math.cos(math.rad(36)), 0, 0, 0, 0})
  movel(d, v, a, 0, 0)

  local e = pose_times(base, {r * math.sin(math.rad(18)), -r * math.cos(math.rad(18)), 0, 0, 0, 0})
  movel(e, v, a, 0, 0)

  movel(base, v, a, 0, 0)
  sync()
end

local base = get_actual_tcp_pose()
draw☆(base, 0.1)

This example demonstrates how to use various motion commands to draw a star shape with the robot. Here's a breakdown of what the code does:

  1. It defines a speed v and acceleration a for the movements.
  2. The draw☆ function takes a base position and a radius r as parameters.
  3. It uses movej to move to the initial position.
  4. It then uses a series of movel commands to draw the star shape, calculating each point relative to the base position.
  5. The pose_times function is used to calculate new positions relative to the base position.
  6. After drawing the star, it moves back to the base position.
  7. The sync() command is called to ensure all movements are completed before the function ends.
  8. Finally, it gets the current TCP (Tool Center Point) pose as the base and calls the draw☆ function with a radius of 0.1.

This example showcases how to combine different motion commands and mathematical calculations to create complex movement patterns with the robot.