InverseKinematicsNumericalExample.py

You can view and download this file on Github: InverseKinematicsNumericalExample.py

 1#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 2# This is an EXUDYN example
 3#
 4# Details:  example for inverse kinematics of serial manipulator UR5
 5#
 6# Author:   Peter Manzel; Johannes Gerstmayr
 7# Date:     2019-07-15
 8#
 9# Copyright:This file is part of Exudyn. Exudyn is free software. You can redistribute it and/or modify it under the terms of the Exudyn license. See 'LICENSE.txt' for more details.
10#
11#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
12
13import exudyn as exu
14from exudyn.itemInterface import *
15from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
16import exudyn.graphics as graphics #only import if it does not conflict
17from exudyn.rigidBodyUtilities import *
18from exudyn.graphicsDataUtilities import *
19from exudyn.robotics import *
20import numpy as np
21
22from exudyn.kinematicTree import KinematicTree66, JointTransformMotionSubspace
23# from exudyn.robotics import InverseKinematicsNumerical
24
25jointWidth=0.1
26jointRadius=0.06
27linkWidth=0.1
28graphicsBaseList = [graphics.Brick([0,0,-0.15], [0.12,0.12,0.1], graphics.color.grey)]
29graphicsBaseList +=[graphics.Cylinder([0,0,-jointWidth], [0,0,jointWidth], linkWidth*0.5, graphics.colorList[0])] #belongs to first body
30
31from exudyn.robotics.models import ManipulatorPuma560, ManipulatorPANDA, ManipulatorUR5
32# robotDef = ManipulatorPuma560()
33robotDef = ManipulatorUR5()
34# robotDef = ManipulatorPANDA()
35flagStdDH = True
36# LinkList2Robot() # todo: build robot using the utility function
37
38toolGraphics = [graphics.Basis(length=0.3*0)]
39robot2 = Robot(gravity=[0,0,-9.81],
40              base = RobotBase(HT=HTtranslate([0,0,0]), visualization=VRobotBase(graphicsData=graphicsBaseList)),
41              tool = RobotTool(HT=HTtranslate([0,0,0.1*0]), visualization=VRobotTool(graphicsData=toolGraphics)),
42              referenceConfiguration = []) #referenceConfiguration created with 0s automatically
43
44nLinks = len(robotDef['links'])
45# save read DH-Parameters into variables for convenience
46a,d,alpha,rz, dx = [0]*nLinks, [0]*nLinks, [0]*nLinks, [0]*nLinks, [0]*nLinks
47for cnt, link in enumerate(robotDef['links']):
48    robot2.AddLink(RobotLink(mass=link['mass'],
49                               COM=link['COM'],
50                               inertia=link['inertia'],
51                                localHT=StdDH2HT(link['stdDH']),
52                                # localHT=StdDH2HT(link['modKKDH']),
53                               PDcontrol=(10, 1),
54                               visualization=VRobotLink(linkColor=graphics.colorList[cnt], showCOM=False, showMBSjoint=True)
55                               ))
56    # save read DH-Parameters into variables for convenience
57    if flagStdDH: # std-dh
58        # stdH = [theta, d, a, alpha] with Rz(theta) * Tz(d) * Tx(a) * Rx(alpha)
59        d[cnt], a[cnt], alpha[cnt] = link['stdDH'][1],link['stdDH'][2], link['stdDH'][3]
60    else:
61        # modDH = [alpha, dx, theta, rz] as used by Khali: Rx(alpha) * Tx(d) * Rz(theta) * Tz(r)
62        # Important note:  d(khali)=a(corke)  and r(khali)=d(corke)
63        alpha[cnt], dx[cnt], rz[cnt],  = link['stdDH'][0],link['stdDH'][1], link['stdDH'][3]
64
65myIkine = InverseKinematicsNumerical(robot2, useRenderer=True)
66## test
67if 1:  # tests close to zero-configuration
68    R = RotXYZ2RotationMatrix(np.array([np.pi,0.2*0,np.pi/8*0 ]))
69    t = [0.4526, -0.1488, 0.5275]
70    T2 = [[1,0,0,0.3], [0,1,0,0.3], [0,0,1,0.3], [0,0,0,1]]
71    T3 = HomogeneousTransformation(R, t)
72    sol = myIkine.Solve(T3, q0 = [0, -np.pi/4, -np.pi/4, -np.pi/4, np.pi/4, np.pi/2])
73    print('success = {}\nq = {} rad'.format(sol[1], np.round(sol[0], 3)))