|
| 1 | +# Creating a new robot model using Denavit-Hartenberg parameters |
| 2 | + |
| 3 | +To begin, you must know: |
| 4 | + |
| 5 | +1. The DH parameters for your robot. |
| 6 | +2. Whether the model uses standard or modified Denavit-Hartenberg parameters, DH or MDH respectively. |
| 7 | +3. The joint structure, does it have revolute, prismatic joints or both. |
| 8 | + |
| 9 | + |
| 10 | +## Write the definition |
| 11 | + |
| 12 | +Create a file called `MYROBOT.py` where `MYROBOT` is a descriptive name of your |
| 13 | +robot that is a valid filename and Python class name. |
| 14 | + |
| 15 | +Cut and paste the code blocks below into your empty file, modifying as you go. We start with the definitions: |
| 16 | + |
| 17 | + |
| 18 | +```python |
| 19 | +from math import pi |
| 20 | +import numpy as np |
| 21 | +from roboticstoolbox import DHRobot, RevoluteDH, PrismaticDH, RevoluteMDH, PrismaticMDH |
| 22 | +``` |
| 23 | + |
| 24 | +The last line is important, it defines all the classes you could possibly |
| 25 | +need. You won't use all of them, and to be tidy you could delete those you don't use. This is their purpose: |
| 26 | + |
| 27 | +* `RevoluteDH` for a revolute joint using standard DH parameters |
| 28 | +* `PrismaticDH` for a prismatic joint using standard DH parameters |
| 29 | +* `RevoluteMDH` for a revolute joint using modified DH parameters |
| 30 | +* `PrismaticMDH` for a prismatic joint using modified DH parameters |
| 31 | + |
| 32 | +Next, add as much description as you can, check out the other model files in this |
| 33 | +folder for inspiration. |
| 34 | + |
| 35 | +```python |
| 36 | +class MYROBOT(DHRobot): |
| 37 | + """ |
| 38 | + Create model of MYROBOT manipulator |
| 39 | +
|
| 40 | + . |
| 41 | + . |
| 42 | + . |
| 43 | +
|
| 44 | + :notes: |
| 45 | + . |
| 46 | + . |
| 47 | + . |
| 48 | +
|
| 49 | + :references: |
| 50 | + . |
| 51 | + . |
| 52 | + . |
| 53 | +
|
| 54 | + """ |
| 55 | +``` |
| 56 | + |
| 57 | +Always a good idea to have notes about units used, DH convention, and |
| 58 | +to include any references to the source of your model. |
| 59 | + |
| 60 | +Now for the main event:. Inside the `__init__` method, define a set of link variables by creating instances of the appropriate link class. |
| 61 | + |
| 62 | +```python |
| 63 | +def __init__(self): |
| 64 | + |
| 65 | + deg = pi/180 |
| 66 | + |
| 67 | + L0 = RevoluteDH( |
| 68 | + d=0, # link length (Dennavit-Hartenberg notation) |
| 69 | + a=0, # link offset (Dennavit-Hartenberg notation) |
| 70 | + alpha=pi/2, # link twist (Dennavit-Hartenberg notation) |
| 71 | + I=[0, 0.35, 0, 0, 0, 0], # inertia tensor of link with respect to |
| 72 | + # center of mass I = [L_xx, L_yy, L_zz, |
| 73 | + # L_xy, L_yz, L_xz] |
| 74 | + r=[0, 0, 0], # distance of ith origin to center of mass [x,y,z] |
| 75 | + # in link reference frame |
| 76 | + m=0, # mass of link |
| 77 | + Jm=200e-6, # actuator inertia |
| 78 | + G=-62.6111, # gear ratio |
| 79 | + B=1.48e-3, # actuator viscous friction coefficient (measured |
| 80 | + # at the motor) |
| 81 | + Tc=[0.395, -0.435], # actuator Coulomb friction coefficient for |
| 82 | + # direction [-,+] (measured at the motor) |
| 83 | + qlim=[-160*deg, 160*deg]) # minimum and maximum joint angle |
| 84 | + |
| 85 | + L1 = RevoluteDH( |
| 86 | + d=0, a=0.4318, alpha=0, |
| 87 | + qlim=[-45*deg, 225*deg]) |
| 88 | + |
| 89 | + . |
| 90 | + . |
| 91 | + . |
| 92 | + |
| 93 | +``` |
| 94 | + |
| 95 | +Provide as many parameters as you can. The definition of `L0` above includes |
| 96 | +kinematic and dynamic parameters, whereas `L1` has only kinematic parameters. |
| 97 | +The minimum requirement is for the kinematic parameters, and you don't even need |
| 98 | +to know the joint limits, they are only required by a small number of Toolbox |
| 99 | +functions. |
| 100 | + |
| 101 | +For a robot with N joints you must define N joint instances. |
| 102 | + |
| 103 | +Next we call the superclass constructor to do the heavy lifting. |
| 104 | + |
| 105 | +```python |
| 106 | + super(Puma560, self).__init__( |
| 107 | + [L0, L1, L2, L3, L4, L5], |
| 108 | + name="MYROBOT", |
| 109 | + manufacturer="COMPANY THAT BUILDS MYROBOTs") |
| 110 | +``` |
| 111 | + |
| 112 | +We pass in an ordered list of all the joint objects we created earlier, and add |
| 113 | +some metadata. The name gets used in plots. |
| 114 | + |
| 115 | +Finally, we might like to define some useful joint configurations, maybe the home position, or where it goes to pick up a widget. You can |
| 116 | +define as many of these as you like, but the pattern looks like this: |
| 117 | + |
| 118 | +```python |
| 119 | + # zero angles, L shaped pose |
| 120 | + self._MYCONFIG = np.array([1, 2, 3, 4, 5, 6]) # create instance attribute |
| 121 | + |
| 122 | + @property |
| 123 | + def MYCONFIG(self): |
| 124 | + return self._MYCONFIG |
| 125 | + |
| 126 | +``` |
| 127 | +where `MYCONFIG` is the name of this particular configuration. Define an instance attribute holding the joint configuration, it must be a |
| 128 | +NumPy array with N elements. Then define a property that will return that attribute. |
| 129 | + |
| 130 | +Many of the |
| 131 | +Toolbox models have a configuration called `qz` which is the set of zero |
| 132 | +joint angles. |
| 133 | + |
| 134 | + |
| 135 | +## Adding your model to the Toolbox |
| 136 | + |
| 137 | +Edit the file `__init__.py` in this folder. Add a line like: |
| 138 | + |
| 139 | +```python |
| 140 | +from roboticstoolbox.models.DH.Stanford import MYROBOT |
| 141 | +``` |
| 142 | + |
| 143 | +and then add `'MYROBOT'` to the list that defines `__all__`. |
| 144 | + |
| 145 | +## Testing |
| 146 | + |
| 147 | +Now to test your class |
| 148 | + |
| 149 | +```python |
| 150 | + myrobot = MYROBOT() # instantiate an instance of your model |
| 151 | + print(myrobot) # display its kinematic parameters |
| 152 | + print(myrobot.MYCONFIG) # check that the joint configuration works |
| 153 | +``` |
| 154 | + |
| 155 | +## Next steps |
| 156 | + |
| 157 | +You can now use the power of the Toolbox to compute forward and inverse |
| 158 | +kinematics, display a graphical model, and interactively teach the robot. |
| 159 | +If you defined dynamic parameters then you can compute forward and inverse |
| 160 | +rigid-body dyamics and simulate the response of the robot to applied torques. |
| 161 | + |
| 162 | +Good luck and enjoy! |
0 commit comments