Search Results for

    Show / Hide Table of Contents

    Class MechanismBuilder

    Inheritance
    object
    MechanismBuilder
    Namespace: ABB.Robotics.RobotStudio.Stations
    Assembly: ABB.Robotics.RobotStudio.Stations.dll
    Syntax
    public sealed class MechanismBuilder
    Examples

    Build a mechanism.

    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();
            }</code></pre>
    

    Constructors

    View Source

    MechanismBuilder(MechanismType)

    Declaration
    public MechanismBuilder(MechanismType mechanismType)
    Parameters
    Type Name Description
    MechanismType mechanismType
    View Source

    MechanismBuilder(MechanismType, KinematicsFlags)

    Declaration
    public MechanismBuilder(MechanismType mechanismType, KinematicsFlags kinFlags)
    Parameters
    Type Name Description
    MechanismType mechanismType
    KinematicsFlags kinFlags

    Properties

    View Source

    BaseFrame

    Declaration
    public Matrix4 BaseFrame { get; set; }
    Property Value
    Type Description
    Matrix4
    View Source

    BaseLink

    Gets or sets the base link. This is where the "calculation chain" starts.

    Declaration
    public string BaseLink { get; set; }
    Property Value
    Type Description
    string

    Name of the base link.

    Remarks

    Link must be added with AddLink before setting it as base link.

    View Source

    DefaultControllerName

    Declaration
    [Obsolete("Not used")]
    [ExcludeFromCodeCoverage]
    public string DefaultControllerName { get; set; }
    Property Value
    Type Description
    string
    View Source

    DefaultControllerVersion

    Declaration
    [Obsolete("Not used")]
    [ExcludeFromCodeCoverage]
    public string DefaultControllerVersion { get; set; }
    Property Value
    Type Description
    string
    View Source

    KinematicBaseFrame

    Declaration
    public Matrix4 KinematicBaseFrame { get; set; }
    Property Value
    Type Description
    Matrix4
    View Source

    KinematicsFlags

    Specifies the kinematics type and additional properties for a robot mechanism.

    Declaration
    public KinematicsFlags KinematicsFlags { get; set; }
    Property Value
    Type Description
    KinematicsFlags
    View Source

    Mass

    Declaration
    [Obsolete("Use SetLoadData() to specify load")]
    public double Mass { get; set; }
    Property Value
    Type Description
    double
    View Source

    MechanismType

    Declaration
    public MechanismType MechanismType { get; }
    Property Value
    Type Description
    MechanismType
    View Source

    ModelName

    Gets or sets the model name.

    Declaration
    public string ModelName { get; set; }
    Property Value
    Type Description
    string

    Name of model.

    View Source

    Name

    Gets or sets the name of mechanism.

    Declaration
    public string Name { get; set; }
    Property Value
    Type Description
    string

    Name of mechanism.

    Methods

    View Source

    AddFlange(string, string, Matrix4, bool)

    Declaration
    public void AddFlange(string flangeName, string linkName, Matrix4 offset, bool local)
    Parameters
    Type Name Description
    string flangeName
    string linkName
    Matrix4 offset
    bool local
    View Source

    AddFrame(string, Matrix4, FrameType)

    Declaration
    public void AddFrame(string frameName, Matrix4 offset, FrameType type)
    Parameters
    Type Name Description
    string frameName
    Matrix4 offset
    FrameType type
    View Source

    AddJoint(string, string, string, Vector3, Vector3, JointType, bool)

    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.

    Declaration
    public void AddJoint(string jointName, string parentLinkName, string childLinkName, Vector3 axis1, Vector3 axis2, JointType jointType, bool isActive)
    Parameters
    Type Name Description
    string jointName

    The name must be unique for this mechanism.

    string parentLinkName

    The name of the parent link in the chain.

    string childLinkName

    The name of the child link in the chain.

    Vector3 axis1

    The first point of the joint axis.

    Vector3 axis2

    The second point of the joint axis.

    JointType jointType

    Prismatic for motion along an axis, Rotational for rotation around an axis.

    bool isActive

    Set to true to add an active joint that controls the movement of the child link. Set to false to add a passive joint that simply follws the movement of the parent and child link. In forward kinematics you can specify a value of an active joint, you can think of it as if it has a motor which can move it, whereas the passive joint has no motor and you cannot specify which joint value it should have.

    View Source

    AddJoint(string, string, string, Vector3, Vector3, JointType, bool, double?)

    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.

    Declaration
    public void AddJoint(string jointName, string parentLinkName, string childLinkName, Vector3 axis1, Vector3 axis2, JointType jointType, bool isActive, double? modelOffset)
    Parameters
    Type Name Description
    string jointName

    The name must be unique for this mechanism.

    string parentLinkName

    The name of the parent link in the chain.

    string childLinkName

    The name of the child link in the chain.

    Vector3 axis1

    The first point of the joint axis.

    Vector3 axis2

    The second point of the joint axis.

    JointType jointType

    Prismatic for motion along an axis, Rotational for rotation around an axis.

    bool isActive

    Set to true to add an active joint that controls the movement of the child link. Set to false to add a passive joint that simply follws the movement of the parent and child link. In forward kinematics you can specify a value of an active joint, you can think of it as if it has a motor which can move it, whereas the passive joint has no motor and you cannot specify which joint value it should have.

    double? modelOffset

    Offset between the joint value in the model and in the controller, see SetJointModelOffset(int, double). This is overridden when the mechanism is connected to a controller.

    View Source

    AddLink(string, GraphicComponent)

    Adds a link to be a member of the mechanism.

    Declaration
    public void AddLink(string linkName, GraphicComponent linkPart)
    Parameters
    Type Name Description
    string linkName

    A name to identify the link.

    GraphicComponent linkPart

    A component which will become a link.

    View Source

    AddToolData(string, string, Matrix4)

    Declaration
    public void AddToolData(string toolDataName, string linkName, Matrix4 offset)
    Parameters
    Type Name Description
    string toolDataName
    string linkName
    Matrix4 offset
    View Source

    AddToolData(string, string, Matrix4, Vector3, Vector3)

    Declaration
    [Obsolete("Use SetLoadData() to specify load")]
    [ExcludeFromCodeCoverage]
    public void AddToolData(string toolDataName, string linkName, Matrix4 offset, Vector3 centerOfGravity, Vector3 centerOfInertia)
    Parameters
    Type Name Description
    string toolDataName
    string linkName
    Matrix4 offset
    Vector3 centerOfGravity
    Vector3 centerOfInertia
    View Source

    CompileMechanism()

    When all data, Links, Joints etc. are set to the modeler call CompileMechanism.

    Declaration
    public Mechanism CompileMechanism()
    Returns
    Type Description
    Mechanism

    The mechanism instance.

    Examples

    Build a mechanism.

    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();
            }</code></pre>
    
    View Source

    InternalSetConveyorJointLimits(double, double)

    Declaration
    public void InternalSetConveyorJointLimits(double minLimit, double maxLimit)
    Parameters
    Type Name Description
    double minLimit
    double maxLimit
    View Source

    SetAttachmentPoints(Matrix4[])

    Sets an array of matrices that will become the frames used for attaching parts and workobjects on a conveyor tracking mecahnism.

    Declaration
    [Obsolete("Use AddFrame() instead")]
    public void SetAttachmentPoints(Matrix4[] attachmentPoints)
    Parameters
    Type Name Description
    Matrix4[] attachmentPoints

    An array of Matrix4 representing the positions of the attachment points of the conveyor mechanism.

    View Source

    SetCalibrationPosition(Matrix4[])

    Declaration
    public void SetCalibrationPosition(Matrix4[] calibrationPoints)
    Parameters
    Type Name Description
    Matrix4[] calibrationPoints
    View Source

    SetDependency(string, string)

    Sets an expression to calculate a joints value that depend on other joint values.

    Declaration
    public void SetDependency(string jointName, string expression)
    Parameters
    Type Name Description
    string jointName

    A name to identify the joint.

    string expression

    A string containig an expression.

    View Source

    SetDependency(string, string, double)

    Declaration
    public void SetDependency(string jointName, string leadJoint, double factor)
    Parameters
    Type Name Description
    string jointName
    string leadJoint
    double factor
    View Source

    SetJointLimit(string, double, double)

    Declaration
    public void SetJointLimit(string jointName, double minLimit, double maxLimit)
    Parameters
    Type Name Description
    string jointName
    double minLimit
    double maxLimit
    View Source

    SetJointLimit(string, double, double, double[])

    Declaration
    public void SetJointLimit(string jointName, double minLimit, double maxLimit, double[] points)
    Parameters
    Type Name Description
    string jointName
    double minLimit
    double maxLimit
    double[] points
    View Source

    SetJointMask(int[])

    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 at least 6. 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.

    Declaration
    public void SetJointMask(int[] maskValues)
    Parameters
    Type Name Description
    int[] maskValues

    An array of integers with mask values that specifies if a joint with the same number as the position in the array is used or not.

    Exceptions
    Type Condition
    ArgumentException
    ArgumentNullException
    See Also
    SetJointMask(int[])
    GetActiveJoints()
    GetJointValues()
    View Source

    SetLoadData(double, Vector3, Quaternion, Vector3)

    Declaration
    public void SetLoadData(double mass, Vector3 centerOfGravity, Quaternion axesOfMoment, Vector3 inertia)
    Parameters
    Type Name Description
    double mass
    Vector3 centerOfGravity
    Quaternion axesOfMoment
    Vector3 inertia
    View Source

    SetSyncJointPosition(double[])

    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.

    Declaration
    public void SetSyncJointPosition(double[] jointValues)
    Parameters
    Type Name Description
    double[] jointValues
    View Source

    SetWorkRange(Vector3, Vector3)

    Declaration
    [Obsolete("Not used")]
    public void SetWorkRange(Vector3 minRange, Vector3 maxRange)
    Parameters
    Type Name Description
    Vector3 minRange
    Vector3 maxRange
    View Source

    ValidateDependencyExpression(string[], string)

    Declaration
    public bool ValidateDependencyExpression(string[] jointNames, string expression)
    Parameters
    Type Name Description
    string[] jointNames
    string expression
    Returns
    Type Description
    bool
    • View Source
    In this article
    Back to top Copyright © 2026 ABB Robotics