| | 38 | |
| | 39 | == Gait tables == |
| | 40 | |
| | 41 | in '''Py4bot''', all steps of a gait are defined in a table. As we've just seen, there are 4 sequences (start, walk, hop, stop), so there are 4 tables. For example, let's see how the tripod gait tables look like, in the [https://framagit.org/fma38/Py4bot/tree/master/py4bot/gaits/gaitTripod.py py4bot/gaits/gaitTripod.py] module: |
| | 42 | |
| | 43 | {{{ |
| | 44 | #!python |
| | 45 | from py4bot.gaits.gait import Gait |
| | 46 | |
| | 47 | |
| | 48 | class GaitTripod(Gait): |
| | 49 | def _createTables(self): |
| | 50 | startTable = ( |
| | 51 | ) |
| | 52 | |
| | 53 | walkTable = ( |
| | 54 | (( 0., 1.), ( 0., 0.)), # step 0 |
| | 55 | (( 1., 0.), (-1., 0.)), |
| | 56 | (( 0., 0.), ( 0., 1.)), |
| | 57 | ((-1., 0.), ( 1., 0.)), # step 3 |
| | 58 | ) |
| | 59 | |
| | 60 | hopTable = ( |
| | 61 | (( 0., 1.), ( 0., 0.)), # step 0 |
| | 62 | (( 0., 0.), ( 0., 0.)), |
| | 63 | (( 0., 0.), ( 0., 1.)), |
| | 64 | (( 0., 0.), ( 0., 0.)), # step 3 |
| | 65 | ) |
| | 66 | |
| | 67 | stopTable = ( |
| | 68 | (( 0., 0.), ( 0., 0.)), # step 0 |
| | 69 | ) |
| | 70 | |
| | 71 | return startTable, walkTable, hopTable, stopTable |
| | 72 | }}} |
| | 73 | |
| | 74 | A table is no more than a list of feet positions. Or, to be more precise, a list of feet groups positions. In the case of the tripod gait, we have 2 groups of legs, each group containing 3 legs forming a tripod (2 legs of one side and 1 leg of the other side). Before we look closer of the tables, note that there is no specific start table, as we are able to reach the first walk step from the neutral position (see first line of images above). |
| | 75 | |
| | 76 | So, the first line of the table contains the feet positions for the first step, first tuple for the first group, second tuple for the second group. First value of tuples is the movement in the XY plane, from -1 to +1. +-1 means full stride (forward or backward), 0 means neutral position. Second value is the movement in the Z plane, from 0 to 1. 0 mean on the ground, 1 mean lifted full height. |
| | 77 | |
| | 78 | In the walk table, we have: |
| | 79 | |
| | 80 | - step 0: first group of legs lifts up at neutral position; second group of legs stays on floor, at neutral position |
| | 81 | - step 1: first group of legs moves forward and go back on floor; second group of legs moves backward on the floor |
| | 82 | - step 2: first group of legs moves backward on floor to neutral position; second group of legs lifts up toward the neutral position |
| | 83 | - step 3: first group of legs moves backward on the floor; second group of legs moves forward and go back on floor |
| | 84 | |
| | 85 | This sequence is repeated over and over. As you see, the swing phase is just a triangle (it could be more complex, with additional interpolated steps). |
| | 86 | |
| | 87 | The first group is in swing phase in steps transitions 0 -> 1 and 3 -> 0, and is is stance phase in steps transitions 1 -> 2 and 2 -> 3. |
| | 88 | The second group is in swing phase in steps transitions 1 -> 2 and 2 -> 3, and is is stance phase in steps transitions 0 -> 1 and 3 -> 0. |