Coordinated Motion with an Axis
Brief: An axis group with a single axis is created and we show how to accomplish full motion coordination (frame tracking and time synchronization) to follow a movep path in the axis frame.
URScript API functions used in this example:
axis_group_add
axis_group_add_axis
reset_world_model
add_frame
attach_frame
frame_tracking_disable
movep_with_axis_group
This is a basic example of motion coordination. An axis group called “groupA” is created with a single axis called “axis1”. A series of frames are added to the world model to define the desired path in the “axis1” frame. Frame tracking is turned on and then a series of movep_with_axis_group
commands is run with target axis positions for each waypoint.
NOTE: This example does not drive any EtherCAT hardware and the external axes move only in the world model.
Let’s go through the example in greater detail:
Setting up the World and Axis
This sets the TCP offset to be 0.05m in the z direction of the tool flange frame and resets the world model. It then adds a new group called “groupA” whose coordinate system is placed coincident with the robot base frame (the provided transform from the base to the group frame is the identity transform) and then adds a new axis with the specified pose relative to the base frame of the robot.
Define the Desired Path In Axis Coordinates
This adds eight frames to the world model that define waypoints on a box of length 2*len and with corners rounded off with radius defined by the variable “rad”. See add_frame
for more details on adding frames to the world model. It then attaches the first frame “wp1” to the axis frame “axis1” and the loop attaches each frame to it’s predecessor in the path. This is a trick that places an arrow between subsequent waypoint frames in rviz to make the path easier to visual. Note that this is not the only
way to encode a path that moves with an external axis. You can see another equally valid approach in this example.
Following the Programmed Path
This first sets up the velocity and blend radius used by the movep_with_axis_group
command. Frame tracking is then enabled so that the TCP follows the movep path in the “axis1” frame by calling frame_tracking_enable
. The sequence of movep_with_axis_group
commands is then executed. Note that the target axis position is provided to each movep_with_axis_group
call. In this sequence, the axis is desired to rotate to the 45 degree position at the time that the movep path reaches “wp3”, the axis is desired to rotate to the 90 degree position at the time that the movep path reaches “wp4”, and so on… The final call disables frame tracking.