-
-
Notifications
You must be signed in to change notification settings - Fork 127
Parameters
A target defines a robot pose, how to reach it and what to do when it gets there. A tool path is made from list of targets. Besides the pose, targets have following attributes: tool, speed, zone, frame, external axes, and commands.
There are two types of targets, joint targets and Cartesian targets:
The pose of the robot is defined by 6 rotation values corresponding to the 6 axes. This is the only way to unambiguously define a pose. The first target of a robot program should be a joint target.
The pose of the robot is defined by a plane that corresponds to the desired position and orientation of the TCP. Cartesian targets can produce singularities, the most common being wrist singularities. This happens when the desired position and orientation requires the 4th and 6th joints to be parallel to each other.
Cartesian targets contain two optional attributes, configuration and motion type:
Industrial robots have 8 different joint configurations to reach the same TCP position and orientation. By default, the configuration in which the joints have to rotate the least is selected. This is determined using the least squares method, which is also the closest distance between targets in joint space. All joints are weighted equally. You can explicitly define a configuration by assigning a value (from 0 to 7) to the Configuration variable. Forcing a configuration doesn't define a pose unambiguously since the joints might rotate clockwise or counter-clockwise depending on the previous target.
A robot can move towards a Cartesian target following either a joint motion or a linear motion:
- Joint: This is the default motion type. In a joint motion, the controller calculates the joint rotation values on the target using inverse kinematics and moves all the joints at proportional but fixed speeds so that they will stop at the same time at the desired target. The motion is linear in joint space, but the TCP will follow a curved path in world space. It's useful if the path that the TCP follows is not critical, like in pick and place operations. Since inverse kinematics only needs to be calculated at the end of the path, it's also useful to avoid singularities.
- Linear: The robot moves towards the target in a straight line in world space. This is useful if the path that the TCP follows is critical, like while milling or extruding material. If the path goes through a singularity at any point, it will not be able to continue. If it moves close to a singularity it might slow down below the programmed speed.
- A string containing 6 numbers separated by commas will create a joint target with default attribute values.
- A plane will create a Cartesian target with default attribute values.
This parameter defines a tool or end effector mounted to the flange of the robot. In most cases a single tool will be used throughout the tool path, but each target can have a different tool assigned. You might want to change tool if your end effector has more than one TCP, or due to load changes during pick and place. Contains the following attributes:
- Name: Name of the tool (should not contain spaces or special characters). The name is used to identify the tool in the pendant and create variable names in post processing.
- TCP: Stand for "tool center point". Represents the position and orientation of the tip of the end effector in relation to the flange. The default value is the world XY plane (the center of the flange).
- Weight: The weight of the end effector in kilograms. The default value is 0 kg.
- Mesh: Single mesh representing the geometry of the tool. Used for visualization and collision detection.
Defines a speed to move towards a target. It's made from multiple variables. The robot will move at the speed of the variable which is the limiting factor.
- Translation speed: Speed in which the TCP will move world space. For joint motions, an angular speed is approximated from the translation speed. The default value is 100 mm/s.
- Rotation speed: Speed in which the TCP rotates around its normal and speed at which the normal can change angle (swivel). The default value is PI/2 rad/s.
- Translation external: Translation speed used on external axes. The default value is 5000 mm/s².
- Rotation external: Rotation speed used on external axes. The default value is PI*6 rad/s².
- Translation acceleration: Acceleration of the TCP. Can only be set through scripting. Currently only used in UR robots. The default value is 1000 mm/s².
- Axis acceleration: Acceleration of the joint. Can only be set through scripting. Currently only used in UR robots. The default value is PI rad/s².
- A number, integer or string containing a single number will create a speed instance with the value of the number as the translation speed. All other speed variables will be set to their default values.
- A string containing two numbers separated by a comma will create a speed instance with the first number being the translation speed and the second number being the rotation speed. All other variables will be set to their default values.
- A string containing two numbers separated by a comma will create a speed instance with the first number being the translation speed, the second number being the rotation speed and the third number being the axis speed. All other variables will be set to their default values.
IMPORTANT If multiple targets use the same speed, first use a string or number to cast into a speed parameter, then assign the parameter to the different targets. Don't assign a string or number directly as a speed to multiple targets, as different speed instances will be created (even if they have the same value) and will create unnecessary duplication in the robot code.
Defines an approximation zone for a target. Two variables make up a zone, a distance (in mm) and a rotation (in radians). The default value is 0 mm.
Targets can be stop points or way points:
- Stop points have a distance and rotation value of 0. All axis will completely stop before moving to the next target. Commands associated with this target will run just after the TCP reaches the target.
- Way points have a distance or rotation value greater than 0. Once the TCP position is within the distance value to the target, it will start moving towards the next target. One the TCP orientation is within the rotation value, it will start orienting towards the next target. This is useful to create a continuous path and avoid the robot stopping (decelerating and accelerating) at the cost of precision. Commands associated with this target will usually run a bit before the TCP enters the zone area.
IMPORTANT If multiple targets use the same zone, first use a string or number to cast into a zone parameter, then assign the parameter to the different targets. Don't assign a string or number directly as a zone to multiple targets, as different zone instances will be created (even if they have the same value) and will create unnecessary duplication in the robot code.
- A number, integer or string containing a single number will create a zone instance with the value of the number as the distance. A proportional rotation value is approximated.
Defines a reference frame for the targets relative to the frame origin. The frame can be moved by an external axis or an additional coordinated robot (kinematic coupling). The default value is a static frame in the world origin.
The position of the targets must be placed as if the frame was the world origin. For example, a target with a coordinate of (0,0,100) and a frame located at (100,100,100) will be placed in the world coordinate (100,100,200).
To create a kinematically coupled frame in Grasshopper use the 'Create frame' component. Assign the mechanical group and the mechanism that moves the frame. For example, as cell that only contains a robot with a positioner should have the values 'mechanical group: 0', 'mechanism: 0'. A cell containing two coordinated robots where the second robot moves the frame should have the values 'mechanical group: 1', 'mechanism: -1'.
- Any plane will create a static frame with the plane as the frames position and orientation
Targets can contain one or more commands that will be run after the robot reaches the target. Currently the following commands are supported:
- Custom command: Allows the user to write his own command in the native robot language.
- Group command: Allows to group a sequence of commands into one.
- Message: Sends a text message to the pendant.
- Pulse DO: Sends a pulse to a specific digital output: The default value for the pulse is 200 ms. A digital output is selected using an index value. The order of the digital output names in robotsData.xml correspond to the index values.
- Set AO: Sets an analogue output. The value should be normalized (from -1 to 1). It's then mapped to a nominal voltage value by the controller.
- Set DO: Sets a digital output. Changes the state of a digital output to be TRUE or FALSE.
- Stop program: Pauses a program until an operator resumes the program from the pendant.
- Wait: The robot waits at the target for a given amount of time.
- Wait DI: The robot waits at the target until a given digital input is set to TRUE.
Represents a specific robot cell. It's used to calculate the forward and inverse kinematics for Cartesian targets, to check for possible errors and warnings on a program, for collision detection and simulation. If your robot model is not included in the assembly, check the wiki on how to add your own custom models.
You can use the robot parameter to connect to the robot controller through a network. Currently this is only supported on ABB and UR robots.
A program defines a complete toolpath and creates the necessary robot code to run it. To create a program, you need a list of targets and a robot model.
When a program is created, the following post processing is done:
- It will clean up and fix common mistakes.
- It will run through the sequence of targets checking for kinematic or other errors.
- It will return warnings for unexpected behavior.
- It will generate a simulation to preview the toolpath.
- It calculates an approximate duration of the program.
- If there are no errors, it will generate the necessary code in the robot's native language.
After the first error is found, it will stop and output a program ending in the error. Most errors are due to kinematics (the TCP not being able to position itself on the target). There are other errors, like exceeding the maximum payload. To identify the error, preview simulation of the program at the last target. Programs that contain errors won't create native code.
The program will also inform of any warnings to consider. Warnings may include changes in configuration, maximum joint speed reached, targets with unassigned values, first target not set as a joint target. Programs that contain warnings will create native code and might be safe to run if the warnings are believed to not cause any issues.
To run the program, a code has to be generated in the specific language used by the manufacturer (RAPID for ABB robots, KRL for KUKA robots and URScript for UR robots). If necessary, this code can then be edited manually. A program containing edited code will not check for warnings or errors and can't be simulated.
The program contains a simulation of the tool path. The simulation currently doesn't consider acceleration, deceleration or approximation zones. It simulates both linear and joint motions, actual robot speed, including slowdowns when moving close to singularities and wait times.