Class ScriptBuilder

ScriptBuilder provides methods to easily generate well indented UR script programmatically. This class manages indentation automatically as the script is built step by step. But,it does not guarantee perfect formatting as there is a possibility to pass badly formatted expressions, statements or scripts.

Hierarchy

  • ScriptBuilder

Constructors

  • Creates a new ScriptBuilder

    Parameters

    • Optional script: string

      If a script is specified, the new ScriptBuilder will be preloaded with that script

    • Optional initialIndent: number

      If an indent is specified, the ScriptBuilder will be initialized with that indent

    Returns ScriptBuilder

Properties

currentIndent: any
decreaseIndent: any

Decrease the indent.

increaseIndent: any

Increase the indent.

script: any
type: "$$ScriptBuilder" = "$$ScriptBuilder"
SINGLE_INDENT: " " = " "
SINGLE_INDENT_LEVEL: 1 = 1

Methods

  • Add a frame with the name 'name' initialized at the specified pose expressed in the refFrame coordinate frame. This command only adds a frame to the world, it does not attach it to the ref_frame coordinate frame. Use attach_frame() to attach the newly added frame to ref_frame if desired.

    Parameters

    • name: string

      name of the frame to be added. The name must not be the same as any existing world model object (frame, axis, or axis group), otherwise an exception is thrown

    • pose: Pose

      initial pose of the new object

    • Optional refFrame: string

      name of the world model object whose coordinate frame the pose is expressed in. If nothing is provided here, the default is the robot "base" frame.

    Returns ScriptBuilder

  • Add raw script code. As this method takes raw script code that may not be indented and appends it without indenting it, it may violate the overall indentation.

    Returns

    this object.

    Parameters

    • script: string

      The script to be appended

    Returns ScriptBuilder

  • Add a block of statements to the builder.

    Returns

    this object.

    Parameters

    • statements: string

      A block of statements as a String.

    Returns ScriptBuilder

  • Add a statement that assigns an expression to a variable.

    Returns

    this object.

    Parameters

    • name: string

      The name of the variable.

    • expression: string

      The expression to be assigned to the variable.

    Returns ScriptBuilder

  • Attaches the child frame to the parent world model object. The relative transform between the parent and child will be set such that the child does not move in the world when the attachment occurs. The child cannot be "world", "tcp", or the same as parent. This will fail if child or parent is not an existing frame, or this makes the attachments form a closed chain.

    Parameters

    • child: string

      name of the frame to be attached. The name must not be "world" or "tcp".

    • parent: string

      name of the object that the child frame will be attached to.

    Returns ScriptBuilder

  • Add a while statement with a given expression. This is unbalanced, it has to be balanced by a call to #end() at the appropriate time.

    Returns

    this object.

    Parameters

    • expression: string

      The string representation of an expression.

    Returns ScriptBuilder

  • Add a while not statement with a given expression. This is unbalanced, it has to be balanced by a call to #end() at the appropriate time.

    Returns

    this object.

    Parameters

    • expression: string

      The string representation of an expression.

    Returns ScriptBuilder

  • Add a while statement that loops forever. This is unbalanced, it has to be balanced by a call to #end() at the appropriate time.

    Returns

    this object.

    Returns ScriptBuilder

  • Description

    Insert a break statement.

    Returns

    this object.

    Returns ScriptBuilder

  • Add a comment in the script.

    Returns

    this object.

    Parameters

    • text: string

      The comment text.

    Returns ScriptBuilder

  • Add a function definition with the given name and parameters. This is unbalanced, it has to be balanced by a call to #end() at the appropriate time.

    Returns

    this object.

    Parameters

    • name: string

      The name of the function.

    • Rest ...params: string[]

      The parameters of the function.

    Returns ScriptBuilder

  • Add a thread definition with given the threadName. This is unbalanced, it has to be balanced by a call to #end() at the appropriate time.

    Returns

    this object.

    Parameters

    • threadName: string

      The threadName of the thread.

    Returns ScriptBuilder

  • Delete the frame named frame from the world model. The "world", "base", and "tcp" frames cannot be deleted. Any frames that are attached to the deleted frame will be attached to the "world" frame with new frame offsets set such that the detached frame does not move in the world. This command will fail if the frame does not exist.

    Parameters

    • name: string

      name of the frame to be deleted

    Returns ScriptBuilder

  • Add an else statement. This is unbalanced, it has to be balanced by a call to #end() at the appropriate time.

    Returns

    this object.

    Returns ScriptBuilder

  • Add an else if statement with a given expression. This is unbalanced, it has to be balanced by a call to #elseIfCondition(String) or #elseIfCondition(Script) or #else() or #end() at the appropriate time.

    Returns

    this object.

    Parameters

    • expression: string

      The expression that the else if statement branches on.

    Returns ScriptBuilder

  • Add the end keyword that balances/terminates the declaration of functions, branch and loop statements.

    Returns

    this object.

    Returns ScriptBuilder

  • End a block, without an end statement Used by if and elseif

    Returns

    this object.

    Returns ScriptBuilder

  • Get the current indention level of this ScriptBuilder.

    Returns

    the indention level as a number.

    Returns number

  • The terminal operation that generates the as string containing the UR Script.

    Returns

    the string that contains the UR Script.

    Returns string

  • Add a statement that declares a global variable and assigns it an initial value.

    Returns

    this object.

    Parameters

    • name: string

      The name of the global variable.

    • value: string

      An expression which is the initial value of the global variable.

    Returns ScriptBuilder

  • Add a halt statement.

    Returns

    this object.

    Returns ScriptBuilder

  • Add an if statement with a given expression. This is unbalanced, it has to be balanced by a call to #elseIfCondition(String) or #else() or #end() at the appropriate time.

    Returns

    this object.

    Parameters

    • expression: string

      The expression that the if statement branches on.

    Returns ScriptBuilder

  • Add a statement that increments a variable with the given name.

    Returns

    this object.

    Parameters

    • name: string

      The name of the variable.

    Returns ScriptBuilder

  • Deprecated

    Use break

    Description

    Insert a break statement.

    Returns

    this object.

    Returns ScriptBuilder

  • Add a statement to kill a thread.

    Returns

    this object.

    Parameters

    • threadHandle: string

      The thread threadHandle.

    Returns ScriptBuilder

  • Add a statement that declares a local variable and assigns it an initial value.

    Returns

    this object.

    Parameters

    • name: string

      The name of the local variable.

    • value: string

      An expression which is the initial value of the local variable.

    Returns ScriptBuilder

  • Changes the placement of the coordinate frame named name to the new placement given by pose that is defined in the refFrame coordinate frame. This will fail if name is “world”, "tcp", or if the frame does not exist. Note: to move the "tcp" frame, use the set_tcp() command instead. If being used with the part positioner product, the ref_name argument can be the name of an external axis or axis group.

    Parameters

    • name: string

      the name of the frame to move

    • pose: Pose

      the new placement

    • Optional refFrame: string

      the coordinate frame that pose is expressed in. The default value is the robot's "base" frame.

    Returns ScriptBuilder

  • Add a call to the function that will Move to position (linear in joint-space).

    Returns

    this object.

    Parameters

    • q: string | number[]

      joint positions (q can also be specified as a pose, then inverse kinematics is used to calculate the corresponding joint positions) as a string or number array.

    • Optional acc: string | number

      joint acceleration of leading axis in rad/s2 as a string or number.

    • Optional speed: string | number

      joint speed of leading axis in rad/s as a string or number (optional).

    • Optional time: string | number

      time in seconds as a string or number (optional).

    • Optional blendRadius: string | number

      blend radius in m as a string or number (optional).

    Returns ScriptBuilder

  • Add a call to the function that will Move to position (linear in tool-space).

    Returns

    this object.

    Parameters

    • pose: string

      target pose (pose can also be specified as joint positions, then forward kinematics is used to calculate the corresponding pose) as a string.

    • acc: string | number

      tool acceleration m/s2 as a string or number.

    • Optional speed: string | number

      tool speed in m/s as a string or number (optional).

    • Optional time: string | number

      time in seconds as a string or number (optional).

    • Optional blendRadius: string | number

      blend radius in m as a string or number (optional).

    Returns ScriptBuilder

  • Add a popup with the given parameters.

    Returns

    this object.

    Parameters

    • message: string

      The popup message.

    • title: string

      The popup title.

    • level: PopupLevel

      The popup level.

    • isBlocking: boolean

      true if its a blocking popup and false otherwise.

    Returns ScriptBuilder

  • Request a value with the given parameters.

    Returns

    this object.

    Parameters

    • variableName: string

      The variable name to assign the value to

    • message: string

      The request message.

    • valueType: RequestValueType

      The type: integer, float, boolean, or string

    Returns ScriptBuilder

  • Add a return statement.

    Returns

    this object.

    Returns ScriptBuilder

  • Add a statement to run a thread with the given name and assign the thread handle to a variable.

    Returns

    this object.

    Parameters

    • threadHandle: string

      The variable that gets assigned the thread handle .

    • threadName: string

      The name of the thread to be started.

    Returns ScriptBuilder

  • Set the direction of the acceleration experienced by the robot.

    Parameters

    • x: string | number

      x m/s^2

    • y: string | number

      y m/s^2

    • z: string | number

      z m/s^2

    Returns ScriptBuilder

  • Deprecated

    use setTargetPayload

    Description

    Add a call to the function that sets the mass.

    Returns

    this object.

    Parameters

    • mass: string | number

      mass in kilograms as a Script.

    Returns ScriptBuilder

  • Deprecated

    use setTargetPayload

    Description

    Add a call to the function that sets the mass and CoG.

    Returns

    this object.

    Parameters

    • mass: string | number

      mass in kilograms as a Script.

    • cx: string | number

      CoG x offset in meters

    • cy: string | number

      CoG y offset in meters

    • cz: string | number

      CoG z offset in meters

    • Optional inertia: [number, number, number, number, number, number]

      The payload inertia matrix in kg*m^2, elements lxx,lyy lzz, lxy, lxz, lyz

    Returns ScriptBuilder

  • Description

    Add a call to the function that sets the mass and CoG.

    Returns

    this object.

    Parameters

    • mass: string | number

      mass in kilograms as a Script.

    • cx: string | number

      CoG x offset in meters

    • cy: string | number

      CoG y offset in meters

    • cz: string | number

      CoG z offset in meters

    • Optional inertia: [number, number, number, number, number, number]

      The payload inertia matrix in kg*m^2, elements lxx,lyy lzz, lxy, lxz, lyz

    Returns ScriptBuilder

  • Description

    Add a call function which specifies the desired TCP

    Parameters

    • x: string | number

      x length

    • y: string | number

      y length

    • z: string | number

      z length

    • rx: string | number

      rx angle

    • ry: string | number

      ry angle

    • rz: string | number

      rz angle

    • Optional name: string

      Name of the TCP

    Returns ScriptBuilder

  • Add a sleep command.

    Returns

    this object.

    Parameters

    • seconds: string | number

      The amount of time in seconds.

    Returns ScriptBuilder

  • Add a call to the function that will accelerate linearly in joint space and continue with constant joint speed.

    Returns

    this object.

    Parameters

    • qd: number[] | string[]

      array of joint speeds in rad/s.

    • jointAcceleration: string | number

      joint acceleration in rad/s2 (of leading axis)

    • time: string | number

      time in seconds before the function returns.

    Returns ScriptBuilder

  • Add a call to the function that will accelerate linearly in Cartesian space and continue with constant tool speed.

    Returns

    this object.

    Parameters

    • xd: number[] | string[]

      array of tool speeds in m/s (spatial vector).

    • cartesianAcceleration: string | number

      tool position acceleration m/s2.

    • time: string | number

      time in seconds before the function returns.

    • Optional refFrameName: string

      name of reference frame

    Returns ScriptBuilder

  • Add a stopj command. It decelerates joint speeds to zero.

    Returns

    this object.

    Parameters

    • jointAcceleration: string | number

      The joint acceleration in rad/s2.

    Returns ScriptBuilder

  • Add a stopl command. It decelerates tool speed to zero.

    Returns

    this object.

    Parameters

    • toolAcceleration: string | number

      The tool acceleration in m/s2.

    Returns ScriptBuilder

  • Add a sync command that uses up the remaining "physical" time a thread has in the current frame.

    Returns

    this object.

    Returns ScriptBuilder

  • Create a ScriptBuilder preloaded with the incognito program definition. This is unbalanced, it has to be balanced by a call to #end() before calling #getScript().

    Returns

    new ScriptBuilder.

    Returns ScriptBuilder

  • Create a ScriptBuilder preloaded with a secondary program definition. This is unbalanced, it has to be balanced by a call to #end() before calling #getScript().

    Returns

    new ScriptBuilder.

    Parameters

    • name: string

      The name of the secondary program.

    Returns ScriptBuilder

  • Return a String representation of the input array.

    Returns

    String representation of the input array.

    Parameters

    • input: number[] | string[] | boolean[]

      the input array.

    Returns string

  • Generate the String representation of a boolean.

    Returns

    The String representation of the input

    Parameters

    • b: boolean

      The input boolean

    Returns string

  • Parameters

    • expression: string

      The expression to be negated

    Returns string

Generated using TypeDoc