[[PageOutline(2-5, Table of Contents, floated)]] = Tutorial = ''This is a draft version.'' == Vocabulary == Before we dive into this tutorial, lets define a few words. I tried to use commonly used vocabulary, and hope I did understand them correclty. Feel free to contact me if you find mistakes. * IK: Inverse Kinematic == Simple example == '''Py4bot''' is just a framework, so it is up to you to write the application matching your robot. But don't worry, it is very easy. As Py4bot has a nice 3D simulation engine, based on [http://vpython.org VPython], for this example, we are going to setup an application for a simulated 3DoF hexapod. All 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: {{{ #!python # -*- coding: utf-8 -*- from py4bot.api import * }}} Now, let's create the robot! A multi-legs robot is mainly build from a body, and several legs. In most cases, the defaut body provided by Py4bot is OK, but in any case, we need to create legs. The second thing we also need to create is an ''actuator pool'', which contains all legs joints, in order to move them syncrhonized. In our example, joints are standard (virtual) servos. So, here is what the main robot class looks like: {{{ #!python import settings class Hexapod(Robot): def _createLegs(self): legs = {} legIk = {} for legIndex in settings.LEGS_INDEX: legs[legIndex] = Leg3Dof(legIndex, {'coxa': Coxa(), 'femur': Femur(), 'tibia': Tibia()}) legIk[legIndex] = Leg3DofIk(settings.LEGS_GEOMETRY[legIndex]) return legs, legIk def _createActuatorPool(self): driver = VPython3Dof(settings.LEGS_INDEX, settings.LEGS_GEOMETRY, settings.LEGS_ORIGIN, settings.LEGS_SERVOS_MAPPING) pool = ActuatorPool(driver) for leg in self._legs.values(): # Create joints actuators num = settings.LEGS_SERVOS_MAPPING[leg.index]['coxa'] actuator = Actuator(leg.coxa, num) pool.add(actuator) num = settings.LEGS_SERVOS_MAPPING[leg.index]['femur'] actuator = Actuator(leg.femur, num) pool.add(actuator) num = settings.LEGS_SERVOS_MAPPING[leg.index]['tibia'] actuator = Actuator(leg.tibia, num) pool.add(actuator) return pool }}} As you can see, we just implemented 2 virtual methods, {{{_createLegs()}}} and {{{_createActuatorPool()}}}. Also 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. For now, it should contain something like: {{{ #!python # -*- coding: utf-8 -*- from py4bot import config # Legs index LEGS_INDEX = ('RF', 'RM', 'RR', 'LR', 'LM', 'LF') # Legs geometry LEGS_GEOMETRY = { 'RM': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'RF': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'LF': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'LM': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'LR': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'RR': {'coxa': 25, 'femur': 45, 'tibia': 50} } # Legs origin LEGS_ORIGIN = { 'RM': {'x': 50., 'y': 0., 'gamma0' : 0.}, 'RF': {'x': 35., 'y': 80., 'gamma0' : 30.}, 'LF': {'x': -35., 'y': 80., 'gamma0' : 150.}, 'LM': {'x': -50., 'y': 0., 'gamma0' : 180.}, 'LR': {'x': -35., 'y': -80., 'gamma0' : 210.}, 'RR': {'x': 35., 'y': -80., 'gamma0' : 330.}, } config.initOrigin(LEGS_INDEX, LEGS_ORIGIN) # Legs (feet) neutral position (femur horizontal, tibia vertical) LEGS_NEUTRAL = { 'RM': { 'l': LEGS_GEOMETRY['RM']['coxa'] + LEGS_GEOMETRY['RM']['femur'], 'z': LEGS_GEOMETRY['RM']['tibia'] }, 'RF': { 'l': LEGS_GEOMETRY['RF']['coxa'] + LEGS_GEOMETRY['RF']['femur'], 'z': LEGS_GEOMETRY['RF']['tibia'] }, 'LF': { 'l': LEGS_GEOMETRY['LF']['coxa'] + LEGS_GEOMETRY['LF']['femur'], 'z': LEGS_GEOMETRY['LF']['tibia'] }, 'LM': { 'l': LEGS_GEOMETRY['LM']['coxa'] + LEGS_GEOMETRY['LM']['femur'], 'z': LEGS_GEOMETRY['LM']['tibia'] }, 'LR': { 'l': LEGS_GEOMETRY['LR']['coxa'] + LEGS_GEOMETRY['LR']['femur'], 'z': LEGS_GEOMETRY['LR']['tibia'] }, 'RR': { 'l': LEGS_GEOMETRY['RR']['coxa'] + LEGS_GEOMETRY['RR']['femur'], 'z': LEGS_GEOMETRY['RR']['tibia'] } } config.initNeutral(LEGS_INDEX, LEGS_NEUTRAL) # Legs / servos mapping LEGS_SERVOS_MAPPING = { 'RF': {'coxa': 0, 'femur': 1, 'tibia': 2}, 'RM': {'coxa': 4, 'femur': 5, 'tibia': 6}, 'RR': {'coxa': 8, 'femur': 9, 'tibia': 10}, 'LR': {'coxa': 15, 'femur': 14, 'tibia': 13}, 'LM': {'coxa': 19, 'femur': 18, 'tibia': 17}, 'LF': {'coxa': 23, 'femur': 22, 'tibia': 21} } }}} Some of these values seem obvious, some don't; we'll discuss all this later. We need to create our remote control, in order to drive our simulated robot. for this example, let's 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. Back in '''{{{hexapod.py}}}''': {{{ #!python class Gamepad(RemoteControl): def _createFrontend(self): return FrontendFactory().create("thrustmaster", path="/dev/input/by-id/usb-Mega_World_Thrustmaster_dual_analog_3.2-event-joystick") def _buildComponents(self): self._addButton(command=GaitSequencer().walkStop, key="button_000") self._addButton(command=GaitSequencer().walkStep, key="button_003") self._addButton(command=GaitSequencer().selectPrevGait, key="button_009", trigger="hold") self._addButton(command=GaitSequencer().selectNextGait, key="button_008", trigger="hold") self._addJoystick(command=GaitSequencer().walk, keys=("analog_02", "analog_03", "analog_00"), mapper=MapperWalk()) self._addButton(command=self.robot.incBodyPosition, key="button_004", mapper=MapperSetValue(dz=+5)) self._addButton(command=self.robot.incBodyPosition, key="button_005", mapper=MapperSetValue(dz=-5)) self._addAnalog(command=self.robot.setBodyExtraPosition, key="analog_01", modifier="button_006", mapper=MapperSet('z')) }}} Now, let's create our robot. Still in '''{{{hexapod.py}}}''', add: {{{ #!python def main(): robot = Hexapod() }}} The main interrest of a multi-legs robot is to make it walk! But by default, the {{{Robot}}} class does not know any '''gait''', so, we have to teach it how to actually walk. Again, as Py4bot is a framework, it comes with some pre-defined gaits. So, all we have to do is to tell our robot which gaits to use (at least one), and give some params: {{{ #!python for gaitName in settings.GAITS: legsIndexGroups = settings.GAIT_LEGS_GROUPS[gaitName] gaitParams = settings.GAIT_PARAMS[gaitName] gait = GaitFactory().create(gaitName, legsIndexGroups, gaitParams) GaitManager().add(gait) }}} Let's see what wee need to add in the '''{{{settings.py}}}''' module: {{{ #!python # Gaits definitions GAITS = ("tripod", "tetrapod", "riple", "metachronal", "wave") GAIT_LEGS_GROUPS = { 'tripod': (('RM', 'LF', 'LR'), ('RF', 'LM', 'RR')), 'tetrapod': (('RR', 'LM'), ('RF', 'LR'), ('RM', 'LF')), 'riple': (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',)), 'metachronal': (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',)), 'wave': (('RR',), ('RM',), ('RF',), ('LR',), ('LM',), ('LF',)) } GAIT_PARAMS = { 'tripod': {'length': 40., 'angle': 10., 'height': 40., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.}, 'tetrapod': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.}, 'riple': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 300.}, 'metachronal': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.}, 'wave': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.} } }}} Final steps are: instanciate the gamepad, launch the gait sequencer, and run the robot! {{{ #!python remote = Gamepad(robot) GaitSequencer().start() remote.start() robot.setBodyPosition(z=-100) GaitManager().select("riple") robot.mainLoop() remote.stop() remote.join() GaitSequencer().stop() GaitSequencer().join() }}} == Settings == Let's discuss about settings used in the previous part. ''TODO: add graphics with all angles'' {{{ #!python LEGS_INDEX = ('RF', 'RM', 'RR', 'LR', 'LM', 'LF') }}} {{{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. {{{ #!python LEGS_GEOMETRY = { 'RM': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'RF': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'LF': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'LM': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'LR': {'coxa': 25, 'femur': 45, 'tibia': 50}, 'RR': {'coxa': 25, 'femur': 45, 'tibia': 50} } }}} {{{LEGS_GEOMETRY}}} dict contains the lengths of the differents parts of the legs, in mm. {{{ #!python LEGS_ORIGIN = { 'RM': {'x': 50., 'y': 0., 'gamma0' : 0.}, 'RF': {'x': 35., 'y': 80., 'gamma0' : 30.}, 'LF': {'x': -35., 'y': 80., 'gamma0' : 150.}, 'LM': {'x': -50., 'y': 0., 'gamma0' : 180.}, 'LR': {'x': -35., 'y': -80., 'gamma0' : 210.}, 'RR': {'x': 35., 'y': -80., 'gamma0' : 330.}, } config.initOrigin(LEGS_INDEX, LEGS_ORIGIN) }}} {{{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. Note that we need to call the {{{initOrigin()}}} function of the '''{{{config.py}}}''' module, in order to initialize internal configuration (some matrix are defined, in order to avoid further maths). {{{ #!python LEGS_NEUTRAL = { 'RM': { 'l': LEGS_GEOMETRY['RM']['coxa'] + LEGS_GEOMETRY['RM']['femur'], 'z': LEGS_GEOMETRY['RM']['tibia'] }, 'RF': { 'l': LEGS_GEOMETRY['RF']['coxa'] + LEGS_GEOMETRY['RF']['femur'], 'z': LEGS_GEOMETRY['RF']['tibia'] }, 'LF': { 'l': LEGS_GEOMETRY['LF']['coxa'] + LEGS_GEOMETRY['LF']['femur'], 'z': LEGS_GEOMETRY['LF']['tibia'] }, 'LM': { 'l': LEGS_GEOMETRY['LM']['coxa'] + LEGS_GEOMETRY['LM']['femur'], 'z': LEGS_GEOMETRY['LM']['tibia'] }, 'LR': { 'l': LEGS_GEOMETRY['LR']['coxa'] + LEGS_GEOMETRY['LR']['femur'], 'z': LEGS_GEOMETRY['LR']['tibia'] }, 'RR': { 'l': LEGS_GEOMETRY['RR']['coxa'] + LEGS_GEOMETRY['RR']['femur'], 'z': LEGS_GEOMETRY['RR']['tibia'] } } config.initNeutral(LEGS_INDEX, LEGS_NEUTRAL) }}} {{{LEGS_NEUTRAL}}} dict contains the Here too, we need to call the {{{initNeutral()}}} function of the '''{{{config.py}}}''' module, in order to initialize internal configuration. {{{ #!python LEGS_SERVOS_MAPPING = { 'RF': {'coxa': 0, 'femur': 1, 'tibia': 2}, 'RM': {'coxa': 4, 'femur': 5, 'tibia': 6}, 'RR': {'coxa': 8, 'femur': 9, 'tibia': 10}, 'LR': {'coxa': 15, 'femur': 14, 'tibia': 13}, 'LM': {'coxa': 19, 'femur': 18, 'tibia': 17}, 'LF': {'coxa': 23, 'femur': 22, 'tibia': 21} } }}} {{{LEGS_SERVOS_MAPPING}}} dict contains a table to map all joints to servos nums. {{{ #!python GAITS = ("tripod", "tetrapod", "riple", "metachronal", "wave") }}} {{{GAITS}}} contains names to defined used gaits. They must match the name known by the {{{GaitFactory}}} class. {{{ #!python GAIT_LEGS_GROUPS = { 'tripod': (('RM', 'LF', 'LR'), ('RF', 'LM', 'RR')), 'tetrapod': (('RR', 'LM'), ('RF', 'LR'), ('RM', 'LF')), 'riple': (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',)), 'metachronal': (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',)), 'wave': (('RR',), ('RM',), ('RF',), ('LR',), ('LM',), ('LF',)) } }}} {{{GAIT_LEGS_GROUPS}}} dict contains the legs grouped together and controlled at the same time during the gait usage. For example, the '''tripod''' gait is made of 2 groups of 3 legs. Note that we need to define sequences, so don't forget the comma to define a tuple with a unique element. {{{ #!python GAIT_PARAMS = { 'tripod': {'length': 40., 'angle': 10., 'height': 40., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.}, 'tetrapod': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.}, 'riple': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 300.}, 'metachronal': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.}, 'wave': {'length': 40., 'angle': 10., 'height': 30., 'minLength': 4., 'minAngle': 2., 'speedMin': 50., 'speedMax': 200.} } }}} {{{GAIT_PARAMS}}} dict contain some additional gaits params: * {{{length}}} is the distance each leg will move for an entire cycle when the robot translate; * {{{angle}}} is the angle each leg will turn for an entire cycle when the robot rotate; * {{{minLength}}} is the minimum translating length, even when speed is very low; * {{{minAngle}}} same as above for angle; * {{{speedMin}}}, {{{speedMax}}} are the range for speed. These values must be adjusted for each robot, to avoid legs collisions. == Complex example == Have a look at [[source:py4bot/examples/cronos|py4bot/examples/cronos]], which contain the code for my 4DoF hexapod == Conclusion == That's it for now with this tutorial. This is the first working dev. release; their are many additional things to do, and final implementation may change, according to feedback/suggestions I will get. But the core is there. Again, the goal of this framework is to provide a high level tool to build complete and powerfull applications to control you multi-legs robots.