optimovel(goal, a=0.3, v=0.3, r=0)

Move to the goal position (linear in Cartesian space).

OptiMove dynamically adapts speed and acceleration to perform smooth motions using jerk-limited speed profiles. The speed and acceleration parameters control the speed profile of the move. Setting speed and acceleration parameters to 1 causes the fastest cycle time the robot is capable of.

This command is similar to movel() but with smoother motions with less vibration.

Parameters

goal: (q, pose, struct{pose, frame}, string) target for the TCP motion can be defined in different ways:

  • (q) as robot joint positions. The target pose will be calculated by forward kinematics.

  • (pose) as a pose in robot base coordinate frame. The target joint positions will be calculated by inverse kinematics.

  • (struct{pose, frame}) as a pose and the name of a reference coordinate frame. The goal will be set to this pose in this reference coordinate frame.

  • (string) as the name of a world model object. The goal will be set to the object's pose.

a (optional): Tool acceleration as a fraction of what the robot is able to perform - a∈(0.0,1.0]

v (optional): Tool speed as a fraction of the maximum Cartesian velocity the robot can travel at during the trajectory, given the maximum joint speeds - v∈(0.0,1.0]

r (optional): Blend radius [m]

If a blend radius is set, the robot arm trajectory will be modified within the blend radius of the destination position.

Example command: optimovel(pose, a=0.4, v=0.6, r=0.0)

  • Example Parameters:
    • goal = p[0.2, 0.3, 0.5, 0, 0, 3.14] -> position in base frame of x = 200 mm, y = 300 mm, z =500 mm, rx = 0 deg, ry = 0 deg, rz = 180 deg.
    • a = 0.4 -> acceleration at either end of the motion is 40% of the acceleration the robot is capable of producing in the specific joint configuration.
    • v = 0.6 -> velocity during motion cruise phase is 60% of the velocity the joints can move at.
    • r = 0.0 -> the blend radius is zero meters, meaning the robot will stop at the waypoint.

Notes:

  • The absolute speed and acceleration of the robot depends on the joint configuration during the move. A value of e.g. 0.4 might therefore produce a faster speed/acceleration in one area of the robot's workspace and a slower speed/acceleration in another area of the robot's workspace (typically close to singularities). Values of 1.0 will always give the highest speed and acceleration that are possible for a given robot path.

  • To avoid high accelerations that can cause dropped items in e.g. suction cup grippers, consider using the command tool_wrench_limit_set() to limit the acceleration of the items held by the gripper.

  • It is possible to blend into this move type from movej/l and optimovej/l. When coming from other movement types the robot should be at standstill when starting the move.