MechanismBuilder Class |
Namespace: ABB.Robotics.RobotStudio.Stations
public sealed class MechanismBuilder
The MechanismBuilder type exposes the following members.
Name | Description | |
---|---|---|
MechanismBuilder | Initializes a new instance of the MechanismBuilder class |
Name | Description | |
---|---|---|
BaseFrame | ||
BaseLink |
Gets or sets the base link. This is where the "calculation chain" starts.
| |
DefaultControllerName | Obsolete. | |
DefaultControllerVersion | Obsolete. | |
KinematicBaseFrame | ||
Mass | Obsolete. | |
MechanismType | ||
ModelName |
Gets or sets the model name.
| |
Name |
Gets or sets the name of mechanism.
|
Name | Description | |
---|---|---|
AddFlange | ||
AddFrame | ||
AddJoint(String, String, String, Vector3, Vector3, JointType, Boolean) |
Adds a rotational or linear joint specified as an axis between two vectors to a mechanism
A joint connects two links, as a parent and child, in a kinematic chain.
| |
AddJoint(String, String, String, Vector3, Vector3, JointType, Boolean, NullableDouble) |
Adds a rotational or linear joint specified as an axis between two vectors to a mechanism
A joint connects two links, as a parent and child, in a kinematic chain.
| |
AddLink |
Adds a link to be a member of the mechanism.
| |
AddToolData(String, String, Matrix4) | ||
AddToolData(String, String, Matrix4, Vector3, Vector3) | Obsolete. | |
CompileMechanism |
When all data, Links, Joints etc. are set to the modeler call CompileMechanism.
| |
Equals | (Inherited from Object.) | |
GetHashCode | (Inherited from Object.) | |
GetType | (Inherited from Object.) | |
InternalSetConveyorJointLimits | ||
SetAttachmentPoints | Obsolete.
Sets an array of matrices that will become the frames used for attaching parts and workobjects on a conveyor tracking mecahnism.
| |
SetCalibrationPosition | ||
SetDependency(String, String) |
Sets an expression to calculate a joints value that depend on other joint values.
| |
SetDependency(String, String, Double) | ||
SetJointMask |
This method sets a mask that defines which joints that are used for mechanism being built. The mask is specified as an array of integers.
The length of the array must be between 6 and 12. Each element specifies if the corresponding axis is used or not. The value 0 means not used and the value 1 means used.
For example the array {1,1,1,1,0,1} means that all axis except axis 5 are used.
| |
SetLoadData | ||
SetSyncJointPosition |
Sets the defined sync position in form of a collection of values. The
number of values are 0-6 depending on the number of joints used for the
mechanism beeing built.
| |
SetWorkRange | Obsolete. | |
ToString | (Inherited from Object.) | |
ValidateDependencyExpression |
Project.UndoContext.BeginUndoStep("Build IRB140"); try { // Create the different parts of the robot. Part Base = new Part(); Part Link1 = new Part(); Part Link2 = new Part(); Part Link3 = new Part(); Part Link4 = new Part(); Part Link5 = new Part(); Part Link6 = new Part(); // Start the mechanism builder to build a robot. MechanismBuilder mb = new MechanismBuilder(MechanismType.Robot); // Set the name of the robot. mb.ModelName = "IRB140_M2000"; // Add the links to the mechanism. mb.AddLink("Base", Base); mb.AddLink("Link1", Link1); mb.AddLink("Link2", Link2); mb.AddLink("Link3", Link3); mb.AddLink("Link4", Link4); mb.AddLink("Link5", Link5); mb.AddLink("Link6", Link6); // Set the base link. mb.BaseLink = "Base"; // Add joints to the mechanism (connects the parts with each other). mb.AddJoint("J1", "Base", "Link1", new Vector3(0, 0, 0), new Vector3(0, 0, 0.117), JointType.Rotational, true); mb.AddJoint("J2", "Link1", "Link2", new Vector3(0.070, -0.109, 0.352), new Vector3(0.070, -0.108, 0.352), JointType.Rotational, true); mb.AddJoint("J3", "Link2", "Link3", new Vector3(0.070, -0.073, 0.712), new Vector3(0.070, -0.072, 0.712), JointType.Rotational, true); mb.AddJoint("J4", "Link3", "Link4", new Vector3(0.3075, 0, 0.712), new Vector3(0.3085, 0, 0.712), JointType.Rotational, true); mb.AddJoint("J5", "Link4", "Link5", new Vector3(0.450, 0.030, 0.712), new Vector3(0.450, 0.031, 0.712), JointType.Rotational, true); mb.AddJoint("J6", "Link5", "Link6", new Vector3(0.515, 0, 0.712), new Vector3(0.516, 0, 0.712), JointType.Rotational, true); // Set the limits of the joints (in radians). mb.SetJointLimit("J1", -180 * System.Math.PI / 180, 180 * System.Math.PI / 180); mb.SetJointLimit("J2", -90 * System.Math.PI / 180, 110 * System.Math.PI / 180); mb.SetJointLimit("J3", -230 * System.Math.PI / 180, 50 * System.Math.PI / 180); mb.SetJointLimit("J4", -200 * System.Math.PI / 180, 200 * System.Math.PI / 180); mb.SetJointLimit("J5", -120 * System.Math.PI / 180, 120 * System.Math.PI / 180); mb.SetJointLimit("J6", -400 * System.Math.PI / 180, 400 * System.Math.PI / 180); // Add flange. Matrix4 flangeOffset = new Matrix4(new Vector3(0, 0, -1), new Vector3(0, 1, 0), new Vector3(1, 0, 0), new Vector3(0.515, 0, 0.712)); mb.AddFlange("wrist", "Link6", flangeOffset, false); // Set the base frame. mb.BaseFrame = Matrix4.Identity; // Set the home position. double[] homeJointsPos = { 0, 0, 0, 0, 30 * System.Math.PI / 180, 0 }; mb.SetSyncJointPosition(homeJointsPos); // Set the calibration position. Matrix4[] calibPos = { Matrix4.Identity }; mb.SetCalibrationPosition(calibPos); // Set the joint mask (the active joints). int[] jointMask = { 1, 1, 1, 1, 1, 1 }; mb.SetJointMask(jointMask); // Create the mechanism (compile it), and set its name. Mechanism mech = mb.CompileMechanism(); mech.Name = "MyIRB140"; // Add it to the station. Station station = Station.ActiveStation; station.GraphicComponents.Add(mech); } catch { Project.UndoContext.CancelUndoStep(CancelUndoStepType.Rollback); throw; } finally { Project.UndoContext.EndUndoStep(); }