Moves the robot's tool tip in a circular arc defined by three Location values.
Move.Arc (location_1, location_2, profile_1)
Prerequisites
Parameters
location_1
A required Location Object or an expression that evaluates to a Location Object value. Can be either a Cartesian or an Angles type value.
location_2
A required Location Object or an expression that evaluates to a Location Object value. Can be either a Cartesian or an Angles type value.
profile_1
A required Profile Object or an expression that evaluates to a Profile Object value. The Straight property that specifies a Cartesian straight-line or a joint interpolated motion is ignored since the motion is always performed in Cartesian coordinates.
Remarks
This method simultaneously moves all of the axes of a robot in a coordinated, position controlled motion such that the robot's tool tip follows a circular arc path. The arc is defined by the XYZ values of the final position of the previous motion and location_1 and location_2. The performance parameters for the motion are defined by the Profile Object, profile_1 (e.g. Speed, Accel, Decel, AccelRamp, DecelRamp).
![]()
The circular arc begins at the final "total XYZ position" of the previous motion, goes through the "total" XYZ position of location_1 and terminates at the "total" XYZ position of location_2. The "total position" of location_1 and location_2 are computed as the results of evaluating each Location'sPosWrtRef value relative to the “total position” of their respective reference frames, if any. If a Location is specified as an Angles type, its XYZ position is computed using the kinematic model for the attached robot.
If profile_1 has its InRange property set to zero or a positive value, the system will bring the robot to a stop at location_2. If this property is negative and the next motion statement is executed before this motion reaches its destination, GPL will attempt to blend the two motions together into a “continuous path”. Circular interpolated motions can be blended with any of the motion types, i.e. Cartesian straight-line, joint interpolated or other circular interpolated motions.
If the previous motion is still in process when the Move.Arc instruction is executed, the Move.Arc instruction will temporarily suspend execution of its thread. At the conclusion of the previous motion or as soon as the new Arc motion starts to be blended with the previous motion, the thread will automatically continue execution at the next instruction in the GPL procedure.
The following are special notes regarding the use of the Arc method.
- The circular arc can be defined in any arbitrary orientation and need not lie in an cardinal plane.
- The XYZ value of location_1 need not be halfway between the starting and ending positions of the arc although values closer to the mid point will more accurately define the plane of the arc.
- If the three XYZ points that define the arc lie in a straight-line, the Arc method is automatically converted to a Cartesian straight-line motion to location_2.
- When blending two Arc motions, the s-curve AccelRamp and DecelRamp should be set to 0 and the Accel and Decel properties should be set high to ensure that the path tracks the circular path as closely as possible.
- As with straight-line motions, the orientation of the tool of the robot is smoothly rotated from the final orientation of the previous motion to the orientation of the final position, location_2. The specific rotation method is a function of the kinematic module being utilized.
Examples
Dim p0 As New Location ' Create location objects
Dim p1 As New Location
Dim p2 As New Location
Dim p3 As New Location
Dim p4 As New Location
p0.XYZ(100,200,-100,0,180,0) ' Define two semi-circles
p1.XYZ(200,100,-100,0,180,0) ' that form an "S"
p2.XYZ(300,200,-100,0,180,0)
p3.XYZ(400,300,-100,0,180,0)
p4.XYZ(500,200,-100,0,180,0)
Move.Loc(p0,pf_start) ' Move to start position
Move.Arc(p1,p2,pf_on_path) ' Follow first semi-circle
Move.Arc(p3,p4,pf_on_path) ' Follow second semi-circle
Move.WaitForEOM ' Pause thread until motion done
See Also
Location Class | Move Class | Move.Circle | Move.Loc | Profile Class