def __init__(self):

        L = [RevoluteDH(a=1), RevoluteDH(a=1)]

        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])
Beispiel #2
0
    def __init__(self):

        L = [
            RevoluteDH(a=1, jointtype='R'),
            RevoluteDH(a=1, jointtype='R'),
            RevoluteDH(a=1, jointtype='R')
        ]

        self._qz = [np.pi / 4, 0.1, 0.1]

        super(Threelink, self).__init__(L, name='Simple three link')
Beispiel #3
0
    def __init__(self):
        deg = pi/180

        L = [RevoluteDH(d=0.387, a=0.325, qlim=[-50*deg, 50*deg]),
             RevoluteDH(a=0.275, alpha=pi, qlim=[-88*deg, 88*deg]),
             PrismaticDH(qlim=[0, 0.210]),
             RevoluteDH()]

        super(Cobra600, self).__init__(L, name='Cobra600', manufacturer='Adept')

        self._qz = [0, 0, 0, 0]
Beispiel #4
0
    def __init__(self, base=None):

        mm = 1e-3
        deg = pi / 180

        # details from

        h = 53.0 * mm
        r = 30.309 * mm
        l2 = 170.384 * mm
        l3 = 136.307 * mm
        l4 = 86.00 * mm
        c = 40.0 * mm

        # tool_offset = l4 + c

        # Turret, Shoulder, Elbow, Wrist, Claw
        links = [
            RevoluteDH(d=h, a=0, alpha=90 * deg),  # Turret
            RevoluteDH(
                d=0,
                a=l2,
                alpha=0,  # Shoulder
                qlim=[10 * deg, 122.5 * deg]),
            RevoluteDH(
                d=0,
                a=-l3,
                alpha=0,  # Elbow
                qlim=[20 * deg, 340 * deg]),
            RevoluteDH(
                d=0,
                a=l4 + c,
                alpha=0,  # Wrist
                qlim=[45 * deg, 315 * deg])
        ]

        super().__init__(links,
                         name="Orion 5",
                         manufacturer="RAWR Robotics",
                         base=SE3(r, 0, 0),
                         tool=SE3.Ry(90, 'deg'))

        # zero angles, all folded up
        self.addconfiguration("qz", np.r_[0, 90, 180, 180] * deg)

        # stretched out vertically
        self.addconfiguration("qv", np.r_[0, 90, 180, 180] * deg)

        # arm horizontal, hand down
        self.addconfiguration("qh", np.r_[0, 0, 180, 90] * deg)
    def __init__(self):
        deg = pi / 180

        L = [
            RevoluteDH(d=0.387, a=0.325, qlim=[-50 * deg, 50 * deg]),
            RevoluteDH(a=0.275, alpha=pi, qlim=[-88 * deg, 88 * deg]),
            PrismaticDH(qlim=[0, 0.210]),
            RevoluteDH()
        ]

        super().__init__(L, name='Cobra600', manufacturer='Adept')

        # zero angles, L shaped pose
        self.addconfiguration("qz", np.array([0, 0, 0, 0]))
Beispiel #6
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)
Beispiel #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
        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]))
Beispiel #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])
    def __init__(self):
        deg = pi / 180

        # robot length values (metres)
        d1 = 0.352
        a1 = 0.070
        a2 = 0.360
        d4 = 0.380
        d6 = 0.065

        # Create Links

        L = [
            RevoluteDH(d=d1,
                       a=a1,
                       alpha=-pi / 2,
                       m=34655.36e-3,
                       r=np.array([27.87, 43.12, -89.03]) * 1e-3,
                       I=np.array([
                           512052539.74, 1361335.88, 51305020.72, 1361335.88,
                           464074688.59, 70335556.04, 51305020.72, 70335556.04,
                           462745526.12
                       ]) * 1e-9),
            RevoluteDH(d=0,
                       a=a2,
                       alpha=0,
                       m=15994.59e-3,
                       r=np.array([198.29, 9.73, 92.43]) * 1e03,
                       I=np.array([
                           94817914.40, -3859712.77, 37932017.01, -3859712.77,
                           328604163.24, -1088970.86, 37932017.01, -1088970.86,
                           277463004.88
                       ]) * 1e-9),
            RevoluteDH(
                d=0,
                a=0,
                alpha=pi / 2,
                m=20862.05e-3,
                r=np.array([-4.56, -79.96, -5.86]),
                I=np.array([
                    500060915.95, -1863252.17, 934875.78, -1863252.17,
                    75152670.69, -15204130.09, 934875.78, -15204130.09,
                    515424754.34
                ]) * 1e-9,
            ),
            RevoluteDH(d=d4, a=0, alpha=-pi / 2),
            RevoluteDH(d=0, a=0, alpha=pi / 2),
            RevoluteDH(d=d6, a=0, alpha=pi / 2)
        ]

        super().__init__(
            L,
            # basemesh="ABB/IRB140/link0.stl",
            name='IRB 140',
            manufacturer='ABB')

        self.addconfiguration("qz", [0, 0, 0, 0, 0, 0])
        self.addconfiguration("qd", [0, -90 * deg, 180 * deg, 0, 0, -90 * deg])
        self.addconfiguration("qr",
                              [0, -90 * deg, 90 * deg, 0, 90 * deg, -90 * deg])
    def __init__(self, N=10):

        links = []
        q1 = []

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

        # and build a serial link manipulator
        super(Ball, self).__init__(links, name='ball')

        # zero angles, ball pose
        self.addconfiguration("qz", np.zeros(N, ))
        self.addconfiguration("q1", [_fract(i) for i in range(N)])
    def __init__(self, N=None):

        links = []
        self._qz = []
        if not N:
            N = 10
        self.N = N

        for i in range(self.N):
            links.append(RevoluteDH(a=0.1, alpha=pi / 2))
            self._qz.append(self.fract(i + 1))

        # and build a serial link manipulator
        super(Ball, self).__init__(links, name='ball')
Beispiel #12
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]
Beispiel #13
0
    def __init__(self):

        # deg = np.pi/180
        mm = 1e-3
        tool_offset = (103) * mm

        flange = 0 * mm
        # d7 = (58.4)*mm

        # This Kuka model is defined using modified
        # Denavit-Hartenberg parameters

        L = [
            RevoluteDH(a=0.0,
                       d=0,
                       alpha=np.pi / 2,
                       qlim=np.array([-2.8973, 2.8973])),
            RevoluteDH(a=0.0,
                       d=0.0,
                       alpha=-np.pi / 2,
                       qlim=np.array([-1.7628, 1.7628])),
            RevoluteDH(a=0.0,
                       d=0.40,
                       alpha=-np.pi / 2,
                       qlim=np.array([-2.8973, 2.8973])),
            RevoluteDH(a=0.0,
                       d=0.0,
                       alpha=np.pi / 2,
                       qlim=np.array([-3.0718, -0.0698])),
            RevoluteDH(a=0.0,
                       d=0.39,
                       alpha=np.pi / 2,
                       qlim=np.array([-2.8973, 2.8973])),
            RevoluteDH(a=0.0,
                       d=0.0,
                       alpha=-np.pi / 2,
                       qlim=np.array([-0.0175, 3.7525])),
            RevoluteDH(a=0.0,
                       d=flange,
                       alpha=0.0,
                       qlim=np.array([-2.8973, 2.8973]))
        ]

        tool = transl(0, 0, tool_offset) @ trotz(-np.pi / 4)

        super().__init__(L, name='LWR-IV', manufacturer='Kuka', tool=tool)

        # tool = xyzrpy_to_trans(0, 0, d7, 0, 0, -np.pi/4)

        self.addconfiguration("qz", [0, 0, 0, 0, 0, 0, 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)
    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)
Beispiel #16
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)
Beispiel #17
0
    def __init__(self):
        deg = pi / 180

        # Updated values form ARTE git. Old values left as comments

        L1 = RevoluteDH(a=0.18, d=0.4,
                        alpha=-pi/2,  # alpha=pi / 2,
                        qlim=[-155 * deg, 155 * deg]
                        )
        L2 = RevoluteDH(a=0.6, d=0,  # d=0.135,
                        alpha=0,  # alpha=pi,
                        qlim=[-180 * deg, 65 * deg]
                        )
        L3 = RevoluteDH(a=0.12,
                        d=0,  # d=0.135,
                        alpha=pi/2,  # alpha=-pi / 2,
                        qlim=[-15 * deg, 158 * deg]
                        )
        L4 = RevoluteDH(a=0.0,
                        d=-0.62,  # d=0.62,
                        alpha=-pi/2,  # alpha=pi / 2,
                        qlim=[-350 * deg, 350 * deg]
                        )
        L5 = RevoluteDH(a=0.0,
                        d=0.0,
                        alpha=pi/2,  # alpha=-pi / 2,
                        qlim=[-130 * deg, 130 * deg]
                        )
        L6 = RevoluteDH(a=0,
                        d=-0.115,
                        alpha=pi,
                        qlim=[-350 * deg, 350 * deg]
                        )

        L = [L1, L2, L3, L4, L5, L6]

        # Create SerialLink object
        super().__init__(
            L,
            # meshdir="KUKA/KR5_arc",
            name='KR5',
            manufacturer='KUKA',
            meshdir="meshes/KUKA/KR5_arc")

        self.addconfiguration("qz", [0, 0, 0, 0, 0, 0])
        self.addconfiguration(
          "qk1", [pi / 4, pi / 3, pi / 4, pi / 6, pi / 4, pi / 6])
        self.addconfiguration(
          "qk2", [pi / 4, pi / 3, pi / 6, pi / 3, pi / 4, pi / 6])
        self.addconfiguration(
          "qk3", [pi / 6, pi / 3, pi / 6, pi / 3, pi / 6, pi / 3])
    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
Beispiel #19
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 ",)
Beispiel #20
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, )))
    def __init__(self, arm='left'):

        links = [
            RevoluteDH(d=0.27, a=0.069, alpha=-pi / 2),
            RevoluteDH(d=0, a=0, alpha=pi / 2, offset=pi / 2),
            RevoluteDH(d=0.102 + 0.262, a=0.069, alpha=-pi / 2),
            RevoluteDH(d=0, a=0, alpha=pi / 2),
            RevoluteDH(d=0.103 + 0.271, a=0.010, alpha=-pi / 2),
            RevoluteDH(d=0, a=0, alpha=pi / 2),
            RevoluteDH(d=0.28, a=0, alpha=0)
        ]

        super().__init__(
            links,
            name=f"Baxter-{arm}",
            manufacturer="Rethink Robotics",
        )

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

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

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

        # nominal table top picking pose
        self.addconfiguration("qn",
                              np.array([0, pi / 4, pi / 2, 0, pi / 4, 0, 0]))

        if arm == 'left':
            self.base = SE3(0.064614, 0.25858, 0.119) * SE3.Rz(pi / 4)
        else:
            self.base = SE3(0.063534, -0.25966, 0.119) * SE3.Rz(-pi / 4)
Beispiel #22
0
    def __init__(self):

        L1 = RevoluteDH(a=0.18,
                        d=0.4,
                        alpha=pi / 2,
                        mesh='KUKA/KR5_arc/link1.stl')
        L2 = RevoluteDH(a=0.6,
                        d=0.135,
                        alpha=pi,
                        mesh='KUKA/KR5_arc/link2.stl')
        L3 = RevoluteDH(a=0.12,
                        d=0.135,
                        alpha=-pi / 2,
                        mesh='KUKA/KR5_arc/link3.stl')
        L4 = RevoluteDH(a=0.0,
                        d=0.62,
                        alpha=pi / 2,
                        mesh='KUKA/KR5_arc/link4.stl')
        L5 = RevoluteDH(a=0.0,
                        d=0.0,
                        alpha=-pi / 2,
                        mesh='KUKA/KR5_arc/link5.stl')
        L6 = RevoluteDH(mesh='KUKA/KR5_arc/link6.stl')

        L = [L1, L2, L3, L4, L5, L6]

        # Create SerialLink object
        super().__init__(L,
                         meshdir="KUKA/KR5_arc",
                         name='KR5',
                         manufacturer='KUKA')

        self.addconfiguration("qz", [0, 0, 0, 0, 0, 0])
        self.addconfiguration("qk1",
                              [pi / 4, pi / 3, pi / 4, pi / 6, pi / 4, pi / 6])
        self.addconfiguration("qk2",
                              [pi / 4, pi / 3, pi / 6, pi / 3, pi / 4, pi / 6])
        self.addconfiguration("qk3",
                              [pi / 6, pi / 3, pi / 6, pi / 3, pi / 6, pi / 3])
    def __init__(self):

        L1 = RevoluteDH(a=0.18,
                        d=0.4,
                        alpha=pi / 2,
                        mesh='KUKA/KR5_arc/link1.stl')
        L2 = RevoluteDH(a=0.6,
                        d=0.135,
                        alpha=pi,
                        mesh='KUKA/KR5_arc/link2.stl')
        L3 = RevoluteDH(a=0.12,
                        d=0.135,
                        alpha=-pi / 2,
                        mesh='KUKA/KR5_arc/link3.stl')
        L4 = RevoluteDH(a=0.0,
                        d=0.62,
                        alpha=pi / 2,
                        mesh='KUKA/KR5_arc/link4.stl')
        L5 = RevoluteDH(a=0.0,
                        d=0.0,
                        alpha=-pi / 2,
                        mesh='KUKA/KR5_arc/link5.stl')
        L6 = RevoluteDH(mesh='KUKA/KR5_arc/link6.stl')

        L = [L1, L2, L3, L4, L5, L6]

        self._qz = [0, 0, 0, 0, 0, 0]

        self._qk1 = [pi / 4, pi / 3, pi / 4, pi / 6, pi / 4, pi / 6]

        self._qk2 = [pi / 4, pi / 3, pi / 6, pi / 3, pi / 4, pi / 6]

        self._qk3 = [pi / 6, pi / 3, pi / 6, pi / 3, pi / 6, pi / 3]

        # Create SerialLink object
        super(KR5, self).__init__(L,
                                  basemesh="KUKA/KR5_arc/link0.stl",
                                  name='KR5',
                                  manufacturer='KUKA')
    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]))
Beispiel #25
0
    def __init__(self):

        deg = pi / 180
        inch = 0.0254

        L0 = RevoluteDH(
            d=0.412,  # link length (Dennavit-Hartenberg notation)
            a=0,  # link offset (Dennavit-Hartenberg notation)
            alpha=-pi / 2,  # link twist (Dennavit-Hartenberg notation)
            # inertia tensor of link with respect to
            # center of mass I = [L_xx, L_yy, L_zz,
            # L_xy, L_yz, L_xz]
            I=[0.276, 0.255, 0.071, 0, 0, 0],
            # distance of ith origin to center of mass [x,y,z]
            # in link reference frame
            r=[0, 0.0175, -0.1105],
            m=9.29,  # mass of link
            Jm=0.953,  # actuator inertia
            G=1,  # gear ratio
            qlim=[-170 * deg, 170 * deg])  # minimum and maximum joint angle

        L1 = RevoluteDH(d=0.154,
                        a=0.,
                        alpha=pi / 2,
                        I=[0.108, 0.018, 0.100, 0, 0, 0],
                        r=[0, -1.054, 0],
                        m=5.01,
                        Jm=2.193,
                        G=1,
                        qlim=[-170 * deg, 170 * deg])

        L2 = PrismaticDH(theta=-pi / 2,
                         a=0.0203,
                         alpha=0,
                         I=[2.51, 2.51, 0.006, 0, 0, 0],
                         r=[0, 0, -6.447],
                         m=4.25,
                         Jm=0.782,
                         G=1,
                         qlim=[12 * inch, (12 + 38) * inch])

        L3 = RevoluteDH(d=0,
                        a=0,
                        alpha=-pi / 2,
                        I=[0.002, 0.001, 0.001, 0, 0, 0],
                        r=[0, 0.092, -0.054],
                        m=1.08,
                        Jm=0.106,
                        G=1,
                        qlim=[-170 * deg, 170 * deg])

        L4 = RevoluteDH(d=0,
                        a=0,
                        alpha=pi / 2,
                        I=[0.003, 0.0004, 0, 0, 0, 0],
                        r=[0, 0.566, 0.003],
                        m=0.630,
                        Jm=0.097,
                        G=1,
                        qlim=[-90 * deg, 90 * deg])

        L5 = RevoluteDH(d=0,
                        a=0,
                        alpha=0,
                        I=[0.013, 0.013, 0.0003, 0, 0, 0],
                        r=[0, 0, 1.554],
                        m=0.51,
                        Jm=0.020,
                        G=1,
                        qlim=[-170 * deg, 170 * deg])

        L = [L0, L1, L2, L3, L4, L5]

        super().__init__(L,
                         name="Stanford arm",
                         manufacturer="Victor Scheinman",
                         keywords=('dynamics', ))

        # zero angles, L shaped pose
        self.addconfiguration("qz", np.array([0, 0, 0, 0, 0, 0]))
    - qz, zero joint angle configuration, 'L' shaped configuration

    .. note::
        - SI units are used.
        - Robot has only 4 DoF.

    .. codeauthor:: Peter Corke
    """
    def __init__(self):
        deg = pi / 180

        L = [
            RevoluteDH(d=0.387, a=0.325, qlim=[-50 * deg, 50 * deg]),
            RevoluteDH(a=0.275, alpha=pi, qlim=[-88 * deg, 88 * deg]),
            PrismaticDH(qlim=[0, 0.210]),
            RevoluteDH()
        ]

        super().__init__(L, name='Cobra600', manufacturer='Adept')

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


if __name__ == '__main__':  # pragma nocover
    deg = pi / 180
    a = RevoluteDH(d=0.387, a=0.325, qlim=[-50 * deg, 50 * deg])
    cobra = Cobra600()
    print(cobra)
    def __init__(self):

        deg = pi / 180

        base = 0.672  # 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=0,
                       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=[-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=[-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=[-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=0,
                       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])
        ]

        # zero angles, L shaped pose
        self._qz = np.array([0, 0, 0, 0, 0, 0])

        # ready pose, arm up
        self._qr = np.array([0, pi / 2, -pi / 2, 0, 0, 0])

        # straight and horizontal
        self._qs = np.array([0, 0, -pi / 2, 0, 0, 0])

        # nominal table top picking pose
        self._qn = np.array([0, pi / 4, pi, 0, pi / 4, 0])

        super().__init__(L, name="Puma 560", manufacturer="Unimation")