Exemplo n.º 1
0
    def __init__(self, N=10, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        a = 1 / N

        links = []
        for i in range(N):
            links.append(RevoluteDH(a=a, alpha=5 * pi / N))

        super().__init__(links,
                         name="Hyper" + str(N),
                         keywords=('symbolic', ),
                         symbolic=symbolic)

        # zero angles, straight
        self.addconfiguration("qz", np.zeros((N, )))

        # folded, helix with ~5.5 turns
        self.addconfiguration("qf", np.ones((N, )) * 10 * pi / N)
Exemplo n.º 2
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        mm = 1e-3

        # kinematic parameters
        a = np.r_[81, 0, 0, 0, 0, 0, 0] * mm
        d = np.r_[317, 192.5, 400, 168.5, 400, 136.3, 133.75] * mm
        alpha = [-pi / 2, -pi / 2, -pi / 2, -pi / 2, -pi / 2, -pi / 2, 0]

        links = []

        for j in range(6):
            link = RevoluteDH(d=d[j], a=a[j], alpha=alpha[j])
            links.append(link)

        super().__init__(links,
                         name="Sawyer",
                         manufacturer="Rethink Robotics",
                         keywords=(
                             'redundant',
                             'symbolic',
                         ),
                         symbolic=symbolic)

        # zero angles
        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
Exemplo n.º 3
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        # robot length values (metres)
        D1 = 0.2755
        D2 = 0.2900
        D3 = 0.1233
        D4 = 0.0741
        D5 = 0.0741
        D6 = 0.1600
        e2 = 0.0070

        # alternate parameters
        aa = 30 * deg
        ca = cos(aa)
        sa = sin(aa)
        c2a = cos(2 * aa)
        s2a = sin(2 * aa)
        d4b = D3 + sa / s2a * D4
        d5b = sa / s2a * D4 + sa / s2a * D5
        d6b = sa / s2a * D5 + D6

        # and build a serial link manipulator

        # offsets from the table on page 4, "Mico" angles are the passed joint
        # angles.  "DH Algo" are the result after adding the joint angle offset.

        super().__init__([
            RevoluteDH(alpha=pi / 2, a=0, d=D1, flip=True),
            RevoluteDH(alpha=pi, a=D2, d=0, offset=-pi / 2),
            RevoluteDH(alpha=pi / 2, a=0, d=-e2, offset=pi / 2),
            RevoluteDH(alpha=2 * aa, a=0, d=-d4b),
            RevoluteDH(alpha=2 * aa, a=0, d=-d5b, offset=-pi),
            RevoluteDH(alpha=pi, a=0, d=-d6b, offset=100 * deg)
        ],
                         name='Mico',
                         manufacturer='Kinova',
                         keywords=('symbolic', ))

        self.addconfiguration('qz', np.r_[0, 0, 0, 0, 0, 0])  # zero angles
        self.addconfiguration('qr', np.r_[270, 180, 180, 0, 0, 0] *
                              deg)  # vertical pose as per Fig 2
Exemplo n.º 4
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        inch = 0.0254

        # robot length values (metres)
        a = [0, -0.42500, -0.39225, 0, 0, 0]
        d = [0.089459, 0, 0, 0.10915, 0.09465, 0.0823]

        alpha = [pi / 2, zero, zero, pi / 2, -pi / 2, zero]

        # mass data, no inertia available
        mass = [3.7000, 8.3930, 2.33, 1.2190, 1.2190, 0.1897]
        center_of_mass = [[0, -0.02561, 0.00193], [0.2125, 0, 0.11336],
                          [0.15, 0, 0.0265], [0, -0.0018, 0.01634],
                          [0, -0.0018, 0.01634], [0, 0, -0.001159]]
        links = []

        for j in range(6):
            link = RevoluteDH(d=d[j],
                              a=a[j],
                              alpha=alpha[j],
                              m=mass[j],
                              r=center_of_mass[j],
                              G=1)
            links.append(link)

        super().__init__(links,
                         name="UR5",
                         manufacturer="Universal Robotics",
                         keywords=('dynamics', 'symbolic'),
                         symbolic=symbolic)

        # zero angles
        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
        # horizontal along the x-axis
        self.addconfiguration("qr", np.r_[180, 0, 0, 0, 90, 0] * deg)
Exemplo n.º 5
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        inch = 0.0254

        # robot length values (metres)
        a = [0, -0.612, -0.5723, 0, 0, 0]
        d = [0.1273, 0, 0, 0.163941, 0.1157, 0.0922]

        alpha = [pi / 2, zero, zero, pi / 2, -pi / 2, zero]

        # mass data, no inertia available
        mass = [7.1, 12.7, 4.27, 2.000, 2.000, 0.365]
        center_of_mass = [[0.021, 0, 0.027], [0.38, 0, 0.158],
                          [0.24, 0, 0.068], [0.0, 0.007, 0.018],
                          [0.0, 0.007, 0.018], [0, 0, -0.026]]
        links = []

        for j in range(6):
            link = RevoluteDH(d=d[j],
                              a=a[j],
                              alpha=alpha[j],
                              m=mass[j],
                              r=center_of_mass[j],
                              G=1)
            links.append(link)

        super().__init__(links,
                         name="UR10",
                         manufacturer="Universal Robotics",
                         keywords=('dynamics', 'symbolic'),
                         symbolic=symbolic)

        # zero angles
        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
        # horizontal along the x-axis
        self.addconfiguration("qr", np.r_[180, 0, 0, 0, 90, 0] * deg)
Exemplo n.º 6
0
    def __init__(self, symbolic=False):
        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
        deg = pi / 180

        super().__init__( [
                RevoluteDH(d=0.16977, alpha=-pi / 2, a=0.0642),
                RevoluteDH(d=0, alpha=0, a=0.305),
                RevoluteDH(d=0, alpha=pi / 2, a=0),
                RevoluteDH(d=-0.22263, alpha=-pi / 2, a=0),
                RevoluteDH(d=0, alpha=pi / 2, a=0),
                RevoluteDH(d=-0.03625, alpha=0, a=0),

            ], name="AR3",manufacturer="AR3 ",)
Exemplo n.º 7
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        inch = 0.0254

        # robot length values (metres)
        a = [0, -0.24365, -0.21325, 0, 0, 0]
        d = [0.1519, 0, 0, 0.11235, 0.08535, 0.0819]

        alpha = [pi / 2, zero, zero, pi / 2, -pi / 2, zero]

        # mass data, no inertia available
        mass = [2, 3.42, 1.26, 0.8, 0.8, 0.35]
        center_of_mass = [[0, -0.02, 0], [0.13, 0, 0.1157], [0.05, 0, 0.0238],
                          [0, 0, 0.01], [0, 0, 0.01], [0, 0, -0.02]]
        links = []

        for j in range(6):
            link = RevoluteDH(d=d[j],
                              a=a[j],
                              alpha=alpha[j],
                              m=mass[j],
                              r=center_of_mass[j],
                              G=1)
            links.append(link)

        super().__init__(links,
                         name="UR3",
                         manufacturer="Universal Robotics",
                         keywords=('dynamics', 'symbolic'),
                         symbolic=symbolic)

        # zero angles
        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
        # horizontal along the x-axis
        self.addconfiguration("qr", np.r_[180, 0, 0, 0, 90, 0] * deg)
Exemplo n.º 8
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
            a1, a2 = sym.symbol('a1 a2')
        else:
            from math import pi
            zero = 0.0
            a1 = 1
            a2 = 1

        L = [RevoluteDH(a=a1, alpha=zero), RevoluteDH(a=a2, alpha=zero)]

        super().__init__(L, name='Planar 2 link', keywords=('planar', ))
        self.addconfiguration("qz", [0, 0])
        self.addconfiguration("q1", [0, pi / 2])
        self.addconfiguration("q2", [pi / 2, -pi / 2])
Exemplo n.º 9
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
            a1, a2 = sym.symbol('a1 a2')
            m1, m2 = sym.symbol('m1 m2')
            c1, c2 = sym.symbol('c1 c2')
            g = sym.symbol('g')
        else:
            from math import pi
            zero = 0.0
            a1 = 1
            a2 = 1
            m1 = 1
            m2 = 1
            c1 = -0.5
            c2 = -0.5
            g = 9.8

        links = [
            RevoluteDH(a=a1, alpha=zero, m=m1, r=[c1, 0, 0]),
            RevoluteDH(a=a2, alpha=zero, m=m2, r=[c2, 0, 0])
        ]

        super().__init__(links,
                         symbolic=symbolic,
                         name='2 link',
                         keywords=('planar', 'dynamics'))
        self.addconfiguration("qz", [0, 0])
        self.addconfiguration("q1", [0, pi / 2])
        self.addconfiguration("q2", [pi / 2, -pi / 2])
        self.addconfiguration("qn", [pi / 6, -pi / 6])

        self.base = SE3.Rx(pi / 2)
        self.gravity = [0, 0, g]
Exemplo n.º 10
0
    def __init__(self, N=10, a=None, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        if a is None:
            a = 1 / N

        links = []
        for i in range(N):
            links.append(RevoluteDH(a=a, alpha=pi / 2))

        super().__init__(links,
                         name="Hyper3d" + str(N),
                         keywords=('symbolic', ),
                         symbolic=symbolic)

        # zero angles, straight
        self.addconfiguration("qz", np.zeros((N, )))
Exemplo n.º 11
0
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        inch = 0.0254

        base = 26.45 * inch  # from mounting surface to shoulder axis

        L = [
            RevoluteDH(
                d=base,  # link length (Dennavit-Hartenberg notation)
                a=0,  # link offset (Dennavit-Hartenberg notation)
                alpha=pi / 2,  # link twist (Dennavit-Hartenberg notation)
                I=[0, 0.35, 0, 0, 0, 0],
                # inertia tensor of link with respect to
                # center of mass I = [L_xx, L_yy, L_zz,
                # L_xy, L_yz, L_xz]
                r=[0, 0, 0],
                # distance of ith origin to center of mass [x,y,z]
                # in link reference frame
                m=0,  # mass of link
                Jm=200e-6,  # actuator inertia
                G=-62.6111,  # gear ratio
                B=1.48e-3,  # actuator viscous friction coefficient (measured
                # at the motor)
                Tc=[0.395, -0.435],
                # actuator Coulomb friction coefficient for
                # direction [-,+] (measured at the motor)
                qlim=[-160 * deg, 160 * deg]  # minimum and maximum joint angle
            ),
            RevoluteDH(
                d=0,
                a=0.4318,
                alpha=zero,
                I=[0.13, 0.524, 0.539, 0, 0, 0],
                r=[-0.3638, 0.006, 0.2275],
                m=17.4,
                Jm=200e-6,
                G=107.815,
                B=.817e-3,
                Tc=[0.126, -0.071],
                qlim=[-110 * deg, 110 * deg],  # qlim=[-45*deg, 225*deg]
            ),
            RevoluteDH(
                d=0.15005,
                a=0.0203,
                alpha=-pi / 2,
                I=[0.066, 0.086, 0.0125, 0, 0, 0],
                r=[-0.0203, -0.0141, 0.070],
                m=4.8,
                Jm=200e-6,
                G=-53.7063,
                B=1.38e-3,
                Tc=[0.132, -0.105],
                qlim=[-135 * deg, 135 * deg]  # qlim=[-225*deg, 45*deg]
            ),
            RevoluteDH(
                d=0.4318,
                a=0,
                alpha=pi / 2,
                I=[1.8e-3, 1.3e-3, 1.8e-3, 0, 0, 0],
                r=[0, 0.019, 0],
                m=0.82,
                Jm=33e-6,
                G=76.0364,
                B=71.2e-6,
                Tc=[11.2e-3, -16.9e-3],
                qlim=[-266 * deg, 266 * deg]  # qlim=[-110*deg, 170*deg]
            ),
            RevoluteDH(d=0,
                       a=0,
                       alpha=-pi / 2,
                       I=[0.3e-3, 0.4e-3, 0.3e-3, 0, 0, 0],
                       r=[0, 0, 0],
                       m=0.34,
                       Jm=33e-6,
                       G=71.923,
                       B=82.6e-6,
                       Tc=[9.26e-3, -14.5e-3],
                       qlim=[-100 * deg, 100 * deg]),
            RevoluteDH(d=0,
                       a=0,
                       alpha=zero,
                       I=[0.15e-3, 0.15e-3, 0.04e-3, 0, 0, 0],
                       r=[0, 0, 0.032],
                       m=0.09,
                       Jm=33e-6,
                       G=76.686,
                       B=36.7e-6,
                       Tc=[3.96e-3, -10.5e-3],
                       qlim=[-266 * deg, 266 * deg])
        ]

        super().__init__(L,
                         name="Puma 560",
                         manufacturer="Unimation",
                         keywords=('dynamics', 'symbolic', 'mesh'),
                         symbolic=symbolic,
                         meshdir="meshes/UNIMATE/puma560")

        # zero angles, L shaped pose
        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))

        # ready pose, arm up
        self.addconfiguration("qr", np.array([0, pi / 2, -pi / 2, 0, 0, 0]))

        # straight and horizontal
        self.addconfiguration("qs", np.array([0, 0, -pi / 2, 0, 0, 0]))

        # nominal table top picking pose
        self.addconfiguration("qn", np.array([0, pi / 4, pi, 0, pi / 4, 0]))
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        inch = 0.0254

        L = [
            rtb.RevoluteDH(
                d=0.495,
                a=0.175,
                alpha=-pi/2,
                qlim=[-pi, pi]
            ),
            rtb.RevoluteDH(
                d=0,
                a=0.9,
                alpha=0,
                offset=-pi/2,
                qlim=[-pi/2, 150.0*deg]
            ),
            rtb.RevoluteDH(
                d=0,
                a=0.175,
                alpha=-pi/2,
                qlim=[-pi, 75*deg]
            ),
            rtb.RevoluteDH(
                d=0.960,
                a=0,
                alpha=pi/2,
                qlim=[-400*deg, 400*deg]
            ),
            rtb.RevoluteDH(
                d=0,
                a=0,
                alpha=pi/2,
                offset=pi,
                qlim=[-125*deg, 120*deg]
            ),
            rtb.RevoluteDH(
                d=0.135,
                a=0,
                alpha=0,
                qlim=[-400*deg, 400*deg]
            )
        ]

        super().__init__(
            L,
            name='IRB4600-40',
            manufacturer='ABB'
        )

        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
        self.addconfiguration("qd", np.array([0, -90 * deg, 180 * deg, 0, 0, -90 * deg]))
        self.addconfiguration("qr", np.array([90 * deg, -108 * deg, 75 * deg, 0*deg, 135*deg, 0]))
    def __init__(self, symbolic=False):

        if symbolic:
            import spatialmath.base.symbolic as sym
            zero = sym.zero()
            pi = sym.pi()
        else:
            from math import pi
            zero = 0.0

        deg = pi / 180
        inch = 0.0254

        L = [
            rtb.RevoluteDH(
                d=0.1625,
                a=0,
                alpha=pi/2,
                qlim=[-2*pi, 2*pi]
            ),
            rtb.RevoluteDH(
                d=0,
                a=-0.425,
                alpha=0,
                qlim=[-2*pi, 2*pi]
            ),
            rtb.RevoluteDH(
                d=0,
                a=-0.3922,
                alpha=0,
                qlim=[-pi, pi]
            ),
            rtb.RevoluteDH(
                d=0.1333,
                a=0,
                alpha=pi/2,
                qlim=[-2*pi, 2*pi]
            ),
            rtb.RevoluteDH(
                d=0.0997,
                a=0,
                alpha=-pi/2,
                qlim=[-2*pi, 2*pi]
            ),
            rtb.RevoluteDH(
                d=0.0996,
                a=0,
                alpha=0,
                qlim=[-2*pi, 2*pi]
            )
        ]

        super().__init__(
            L,
            name='UR10',
            manufacturer='Universal Robotics'
        )

        self.addconfiguration(
            "qz", np.array([0, 0, 0, 0, 0, 0]))
        self.addconfiguration(
            "qr", np.array([np.pi, 0, 0, 0, np.pi / 2, 0]))