Changes between Initial Version and Version 1 of Tutorial1FirstRobot


Ignore:
Timestamp:
Nov 22, 2017, 8:45:17 AM (8 years ago)
Author:
fma
Comment:

--

Legend:

Unmodified
Added
Removed
Modified
  • Tutorial1FirstRobot

    v1 v1  
     1= Tutorial 1: First robot =
     2
     3''Files for this tutorial are available in [https://framagit.org/fma38/Py4bot/tree/master/py4bot/examples/tutorial_1 py4bot/examples/tutorial_1/]. But don't just copy them here: write them from scratch, following the tutorial.''
     4
     5First, we create a new empty dir in our home dir:
     6
     7{{{
     8$ mkdir tutorial_1
     9$ cd tutorial_1
     10}}}
     11
     12All usefull classes are available from the '''{{{api.py}}}''' module. So, we just have to import things from here. Let's create a '''{{{hexapod.py}}}''' file to put our code, and import what we are going to use in this tutorial:
     13
     14{{{
     15#!python
     16
     17# -*- coding: utf-8 -*-
     18
     19from py4bot.api import *
     20}}}
     21
     22Now, let's create the robot! A multi-legs robot is mainly build from a body, and several legs.
     23
     24We also need to create an ''actuator pool'', which contains all legs joints actuators, in order to move them synchronized. In our example, actuators are standard servos, and we use the '''Veyron''' board, from '''DFRobot''', to drive them:
     25
     26{{{
     27#!python
     28
     29import settings
     30
     31
     32class Hexapod(Robot):
     33    def _createBody(self):
     34        return Body(settings.LEGS_ORIGIN)
     35
     36    def _createLegs(self):
     37        legs = {}
     38        legIk = {}
     39        for legIndex in settings.LEGS_INDEX:
     40            legs[legIndex] = Leg3Dof(legIndex, {'coxa': Coxa(), 'femur': Femur(), 'tibia': Tibia()}, settings.FEET_NEUTRAL[legIndex])
     41            legIk[legIndex] = Leg3DofIk(settings.LEGS_GEOMETRY[legIndex])
     42
     43        return legs, legIk
     44
     45    def _createActuatorPool(self):
     46        driver = Veyron()
     47        pool = ServoPool(driver)
     48
     49        for leg in self._legs.values():
     50
     51            # Create joints actuators
     52            num = settings.LEGS_SERVOS_MAPPING[leg.index]['coxa']
     53            servo = Servo(leg.coxa, num, **settings.SERVOS_CALIBRATION[num])
     54            pool.add(servo)
     55
     56            num = settings.LEGS_SERVOS_MAPPING[leg.index]['femur']
     57            servo = Servo(leg.femur, num, **settings.SERVOS_CALIBRATION[num])
     58            pool.add(servo)
     59
     60            num = settings.LEGS_SERVOS_MAPPING[leg.index]['tibia']
     61            servo = Servo(leg.tibia, num, **settings.SERVOS_CALIBRATION[num])
     62            pool.add(servo)
     63
     64        return pool
     65}}}
     66
     67As you can see, we just implemented 3 virtual methods, {{{_createBody()}}}, {{{_createLegs()}}} and {{{_createActuatorPool()}}}.
     68
     69Also note that we used some values from the '''{{{settings.py}}}''' module. This module is just a simple way to centralise the configuration of our hexapod. We will describe this module later.
     70
     71To drive a robot, we need a remote control. In this tutorial, we are going to use an old gamepad, a [http://www.thrustmaster.com/en_IN/products/firestorm-dual-analog-3 Thrustmaster Firestorm Dual Analog 3]. As I own such gamepad, I already added support in Py4bot:
     72
     73{{{
     74#!python
     75
     76class Gamepad(RemoteControl):
     77    def _createFrontend(self):
     78        return Thrustmaster(settings.THRUSTMASTER_PATH)
     79
     80    def _buildComponents(self):
     81        self._addConfig("walk")
     82        self._addConfig("body")
     83
     84        self._addComponent(Button, command=self.selectNextConfig, key="button_008", trigger="hold")
     85        self._addComponent(Button, command=self.selectPreviousConfig, key="button_009", trigger="hold")
     86
     87        self._addComponent(Button, command=self.robot.incBodyPosition, key="button_004", mapper=MapperSetValue(dz=+5))
     88        self._addComponent(Button, command=self.robot.incBodyPosition, key="button_005", mapper=MapperSetValue(dz=-5))
     89        self._addComponent(Joystick, configs="walk", command=GaitSequencer().walk, keys=("analog_02", "analog_03", "analog_00"), mapper=MapperWalk())
     90
     91        self._addComponent(Analog, configs="body", command=self.robot.setBodyExtraPosition, key="analog_00", mapper=MapperSetMultiply('yaw', coef=-15))
     92        self._addComponent(Analog, configs="body", command=self.robot.setBodyExtraPosition, key="analog_03", mapper=MapperSetMultiply('pitch', coef=-15))
     93        self._addComponent(Analog, configs="body", command=self.robot.setBodyExtraPosition, key="analog_02", mapper=MapperSetMultiply('roll', coef=15))
     94}}}
     95
     96We won't deep into details, here; refer to the [[UserGuideGit#Controllers|documentation]] for more informations about remote controls. This is an important part of the framework, and you  can do very smart things, like having several configurations, using several remotes for the same robot...
     97
     98Now, let's create our robot:
     99
     100{{{
     101#!python
     102
     103def main():
     104    def addGait(gaitClass, gaitName):
     105        group = settings.GAIT_LEGS_GROUPS[gaitName]
     106        params = settings.GAIT_PARAMS['default']
     107        for key1, value1 in settings.GAIT_PARAMS[gaitName].items():
     108            for key2, value2 in value1.items():
     109                params[key1][key2] = value2
     110        gait = gaitClass(gaitName, group, params)
     111        GaitManager().add(gait)
     112
     113    addGait(GaitTripod, "tripod")
     114    addGait(GaitTetrapod, "tetrapod")
     115    addGait(GaitRiple, "riple")
     116    addGait(GaitWave, "metachronal")
     117    addGait(GaitWave, "wave")
     118    GaitManager().select("riple")
     119
     120    robot = Hexapod()
     121
     122    remote = Gamepad(robot)
     123
     124    GaitSequencer().start()
     125    remote.start()
     126
     127    robot.setBodyPosition(z=30)
     128
     129    robot.mainLoop()
     130
     131    remote.stop()
     132    remote.join()
     133    GaitSequencer().stop()
     134    GaitSequencer().join()
     135
     136
     137if __name__ == "__main__":
     138    main()
     139}}}
     140
     141First, we add a few pre-defined gaits, in order to make it walk. Then, we create the robot itself, the remote control, and start all this little world!
     142
     143== Settings ==
     144
     145Let's discuss about settings used in the previous part. See the [[UserGuideGit#Geometrydefinition|user guide]] for the body/legs geometry conventions used.
     146
     147{{{
     148#!python
     149
     150LEGS_INDEX = ('RF', 'RM', 'RR', 'LR', 'LM', 'LF')
     151}}}
     152
     153{{{LEGS_INDEX}}} contains the names used to define legs; they can be freely chosen, but these values must be used as keys for other params.
     154
     155{{{
     156#!python
     157
     158LEGS_GEOMETRY = {
     159    'RM': {'coxa': 25, 'femur': 45, 'tibia': 65},
     160    'RF': {'coxa': 25, 'femur': 45, 'tibia': 65},
     161    'LF': {'coxa': 25, 'femur': 45, 'tibia': 65},
     162    'LM': {'coxa': 25, 'femur': 45, 'tibia': 65},
     163    'LR': {'coxa': 25, 'femur': 45, 'tibia': 65},
     164    'RR': {'coxa': 25, 'femur': 45, 'tibia': 65}
     165}
     166}}}
     167
     168{{{LEGS_GEOMETRY}}} dict contains the lengths of the different parts of the legs, in mm.
     169
     170{{{
     171#!python
     172
     173LEGS_ORIGIN = {
     174    'RM': {'x':  50., 'y':   0., 'gamma0' :   0.},
     175    'RF': {'x':  35., 'y':  80., 'gamma0' :  30.},
     176    'LF': {'x': -35., 'y':  80., 'gamma0' : 150.},
     177    'LM': {'x': -50., 'y':   0., 'gamma0' : 180.},
     178    'LR': {'x': -35., 'y': -80., 'gamma0' : 210.},
     179    'RR': {'x':  35., 'y': -80., 'gamma0' : 330.},
     180}
     181}}}
     182
     183{{{LEGS_ORIGIN}}} dict contains the positions and orientation of the origin of the legs: {{{(x, y)}}} defines the center of rotation of '''coxa''' joint, and {{{gamma0}}} is the angle of the legs at neutral position.
     184
     185{{{
     186#!python
     187
     188FEET_NEUTRAL = {
     189    'RM': LEGS_GEOMETRY['RM']['coxa'] + LEGS_GEOMETRY['RM']['femur'],
     190    'RF': LEGS_GEOMETRY['RF']['coxa'] + LEGS_GEOMETRY['RF']['femur'],
     191    'LF': LEGS_GEOMETRY['LF']['coxa'] + LEGS_GEOMETRY['LF']['femur'],
     192    'LM': LEGS_GEOMETRY['LM']['coxa'] + LEGS_GEOMETRY['LM']['femur'],
     193    'LR': LEGS_GEOMETRY['LR']['coxa'] + LEGS_GEOMETRY['LR']['femur'],
     194    'RR': LEGS_GEOMETRY['RR']['coxa'] + LEGS_GEOMETRY['RR']['femur'],
     195}
     196}}}
     197
     198{{{FEET_NEUTRAL}}} dict contains the feet neutral positions af all legs. This is just the distance from the legs origins, in the ground plane, along leg X axis.
     199
     200{{{
     201#!python
     202
     203LEGS_SERVOS_MAPPING = {
     204    'RF': {'coxa':  0, 'femur':  1, 'tibia':  2},
     205    'RM': {'coxa':  4, 'femur':  5, 'tibia':  6},
     206    'RR': {'coxa':  8, 'femur':  9, 'tibia': 10},
     207    'LR': {'coxa': 15, 'femur': 14, 'tibia': 13},
     208    'LM': {'coxa': 19, 'femur': 18, 'tibia': 17},
     209    'LF': {'coxa': 23, 'femur': 22, 'tibia': 21}
     210}
     211}}}
     212
     213{{{LEGS_SERVOS_MAPPING}}} is a table to map all joints to actuators nums.
     214
     215{{{
     216#!python
     217
     218SERVOS_CALIBRATION = {
     219     0: {'offset':   0, 'neutral': 1500, 'ratio':  0.090},  # coxa  leg RF
     220     1: {'offset': 180, 'neutral': 1500, 'ratio':  0.090},  # femur leg RF
     221     2: {'offset':  90, 'neutral': 1500, 'ratio':  0.090},  # tibia leg RF
     222
     223     4: {'offset':   0, 'neutral': 1500, 'ratio':  0.090},  # coxa  leg RM
     224     5: {'offset': 180, 'neutral': 1500, 'ratio':  0.090},  # femur leg RM
     225     6: {'offset':  90, 'neutral': 1500, 'ratio':  0.090},  # tibia leg RM
     226
     227     8: {'offset':   0, 'neutral': 1500, 'ratio':  0.090},  # coxa  leg RR
     228     9: {'offset': 180, 'neutral': 1500, 'ratio':  0.090},  # femur leg RR
     229    10: {'offset':  90, 'neutral': 1500, 'ratio':  0.090},  # tibia leg RR
     230
     231    15: {'offset':   0, 'neutral': 1500, 'ratio':  0.090},  # coxa  leg LR
     232    14: {'offset': 180, 'neutral': 1500, 'ratio': -0.090},  # femur leg LR
     233    13: {'offset':  90, 'neutral': 1500, 'ratio': -0.090},  # tibia leg LR
     234
     235    19: {'offset':   0, 'neutral': 1500, 'ratio':  0.090},  # coxa  leg LM
     236    18: {'offset': 180, 'neutral': 1500, 'ratio': -0.090},  # femur leg LM
     237    17: {'offset':  90, 'neutral': 1500, 'ratio': -0.090},  # tibia leg LM
     238
     239    23: {'offset':   0, 'neutral': 1500, 'ratio':  0.090},  # coxa  leg LF
     240    22: {'offset': 180, 'neutral': 1500, 'ratio': -0.090},  # femur leg LF
     241    21: {'offset':  90, 'neutral': 1500, 'ratio': -0.090},  # tibia leg LF
     242}
     243
     244}}}
     245
     246{{{SERVOS_CALIBRATION}}} contains some calibration:
     247
     248* {{{offset}}} is the angle between the servo reference and the real angle. See the [[FAQ#Howisgeometrydefined|FAQ]] for the real angles definition;
     249* {{{neutral}}} is the pulse value for the neutral position of the servo;
     250* {{{ratio}}} is angle per pulse width.
     251
     252Offsets may vary, depending how you mount the servos. Same, ratio sign may have to be inverted on one side, if you have a symmetrical design; all angle are always computed using trigonometric direction (CCW).
     253
     254See the [[UserGuideGit#Servoscalibration|user guide]] how to fine tune servos calibration.
     255
     256Finally:
     257
     258{{{
     259#!python
     260
     261GAIT_LEGS_GROUPS = {
     262    'tripod':      (('RM', 'LF', 'LR'), ('RF', 'LM', 'RR')),
     263    'tetrapod':    (('RR', 'LM'), ('RF', 'LR'), ('RM', 'LF')),
     264    'riple':       (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',)),
     265    'metachronal': (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',)),
     266    'wave':        (('RR',), ('RM',), ('RF',), ('LR',), ('LM',), ('LF',))
     267}
     268
     269GAIT_PARAMS = {
     270    'default': {
     271        'length': {
     272            'min': 5.,
     273            'max': 30.
     274        },
     275        'angle': {
     276            'min': 0.5,
     277            'max': 5.
     278        },
     279        'height': {
     280            'min': 20.,
     281            'max': 40.
     282        },
     283        'speed': {
     284            'min': 25.,
     285            'max': 250.
     286        }
     287    },
     288    'tripod': {
     289        'length': {
     290            'max': 40.
     291        },
     292        'angle': {
     293            'max': 10.
     294        }
     295    },
     296    'tetrapod': {},
     297    'riple': {},
     298    'metachronal': {},
     299    'wave': {}
     300}
     301}}}
     302
     303{{{GAIT_LEGS_GROUPS}}} contains the legs grouped together and controlled at the same time during the gait usage.
     304
     305Note that we need to define sequences, so don't forget the comma to define a tuple with a unique element.
     306
     307{{{GAIT_PARAMS}}} contains some additional gaits params:
     308
     309* {{{length}}} is the distance (range) each leg will move for an entire cycle when the robot translate at full speed;
     310* {{{angle}}} is the angle (range) each leg will turn for an entire cycle when the robot rotate at full speed;
     311* {{{height}}} is the height (range) the leg will lift up;
     312* {{{speed}}} is the speed (range).
     313
     314These values must be adjusted for each robot, to avoid legs collisions.
     315
     316{{{
     317#!python
     318
     319THRUSTMASTER_PATH = "/dev/input/by-id/usb-Mega_World_Thrustmaster_dual_analog_3.2-event-joystick"
     320}}}
     321
     322No need for further explanations.