wiki:Tutorials

Version 38 (modified by fma, 10 years ago) ( diff )

--

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

Tutorial 1

Files for this tutorial are available in py4bot/examples/tutorial_1/

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 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:

# -*- 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:

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_ACTUATORS_MAPPING)
        pool = ActuatorPool(driver)

        for leg in self._legs.values():

            # Create joints actuators
            num = settings.LEGS_ACTUATORS_MAPPING[leg.index]['coxa']
            actuator = Actuator(leg.coxa, num)
            pool.add(actuator)

            num = settings.LEGS_ACTUATORS_MAPPING[leg.index]['femur']
            actuator = Actuator(leg.femur, num)
            pool.add(actuator)

            num = settings.LEGS_ACTUATORS_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:

# -*- coding: utf-8 -*-

from py4bot.common import config


# Legs index
LEGS_INDEX = ('RF', 'RM', 'RR', 'LR', 'LM', 'LF')

# Legs geometry
LEGS_GEOMETRY = {
    'RM': {'coxa': 25, 'femur': 45, 'tibia': 65},
    'RF': {'coxa': 25, 'femur': 45, 'tibia': 65},
    'LF': {'coxa': 25, 'femur': 45, 'tibia': 65},
    'LM': {'coxa': 25, 'femur': 45, 'tibia': 65},
    'LR': {'coxa': 25, 'femur': 45, 'tibia': 65},
    'RR': {'coxa': 25, 'femur': 45, 'tibia': 65}
}

# 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 / actuators mapping
LEGS_ACTUATORS_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.

Now, let's create our robot. Still in hexapod.py, add:

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:

    gait = GaitRiple("riple", settings.GAIT_LEGS_GROUPS, settings.GAIT_PARAMS)
    GaitManager().add(gait)

Let's see what wee need to add in the settings.py module:

# Gaits
GAIT_LEGS_GROUPS = (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',))

GAIT_PARAMS = {
    'length': 40.,
    'angle': 10.,
    'height': 30.,
    'minLength': 4.,
    'minAngle': 2.,
    'speedMin':  50.,
    'speedMax': 300.
}

Final steps are: launch the gait sequencer, move a little bit the body position, ask the robot to start walking, and run the robot main loop:

    GaitSequencer().start()

    robot.setBodyPosition(z=-30)

    GaitSequencer().walk(0.75, 90., 0., 1)

    robot.mainLoop(5)

    GaitSequencer().walkStop()
    time.sleep(5)

    GaitSequencer().stop()
    GaitSequencer().join()


if __name__ == "__main__":
    main()

You should then see the robot walking for a few seconds:

No image "tutorial_1.png" attached to Tutorials

Settings

Let's discuss about settings used in the previous part. See the FAQ for the Body/legs geometry conventions used.

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.

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.

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).

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.

LEGS_ACTUATORS_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_ACTUATORS_MAPPING dict contains a table to map all joints to actuators nums.

GAIT_LEGS_GROUPS = (('RR',), ('LM',), ('RF',), ('LR',), ('RM',), ('LF',))

GAIT_LEGS_GROUPS contains the legs grouped together and controlled at the same time during the gait usage.

In this example, the riple gait is made of 6 groups of 1 legs.

Note that we need to define sequences, so don't forget the comma to define a tuple with a unique element.

GAIT_PARAMS = {
    'length': 40.,
    'angle': 10.,
    'height': 30.,
    'minLength': 4.,
    'minAngle': 2.,
    'speedMin':  50.,
    'speedMax': 300.
}

GAIT_PARAMS contains 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.

Tutorial 2

Files for this tutorial are available in py4bot/examples/tutorial_2/

In this tutorial, we are just going to add a remote control in order to drive our previous simulated robot.

Let's use an old gamepad, a Thrustmaster Firestorm Dual Analog 3. As I own such gamepad, I already added support in Py4bot.

Add the following code between the Hexapod class, and the main() function:

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._addComponent(Joystick, command=GaitSequencer().walk, keys=("analog_02", "analog_03", "analog_00"), mapper=MapperWalk())
        self._addComponent(Button, command=GaitSequencer().walkStop, key="button_000")
        self._addComponent(Button, command=GaitSequencer().walkStep, key="button_003")
        self._addComponent(Button, command=self.robot.incBodyPosition, key="button_004", mapper=MapperSetValue(dz=+5))
        self._addComponent(Button, command=self.robot.incBodyPosition, key="button_005", mapper=MapperSetValue(dz=-5))

Then, modify the main.py function as following:

def main():
    robot = Hexapod()

    gait = GaitRiple("riple", settings.GAIT_LEGS_GROUPS, settings.GAIT_PARAMS)
    GaitManager().add(gait)

    remote = Gamepad(robot)

    GaitSequencer().start()
    remote.start()

    robot.setBodyPosition(z=-30)

    robot.mainLoop()

    remote.stop()
    remote.join()
    GaitSequencer().stop()
    GaitSequencer().join()

See documentation for a full description of the controllers implementation.

Tutorial 3

Files for this tutorial are available in py4bot/examples/tutorial_3/

Ok, a simulated robot is cool, but a real one is much more fun!

Let's say that you built you own cool 3DoF hexapod, like one of these:

and let's say you want to use a Veyron servos driver as low-level hardware driver.

Here is the new Hexapod class:

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 = Veyron()
        pool = ServoPool(driver)

        for leg in self._legs.values():

            # Create joints servos
            num = settings.LEGS_SERVOS_MAPPING[leg.index]['coxa']
            servo = Servo(leg.coxa, num, **settings.SERVOS_CALIBRATION[num])
            pool.add(servo)

            num = settings.LEGS_SERVOS_MAPPING[leg.index]['femur']
            servo = Servo(leg.femur, num, **settings.SERVOS_CALIBRATION[num])
            pool.add(servo)

            num = settings.LEGS_SERVOS_MAPPING[leg.index]['tibia']
            servo = Servo(leg.tibia, num, **settings.SERVOS_CALIBRATION[num])
            pool.add(servo)

        return pool

In addition, we must modify/add a few things in the settings.py module:

# 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}
}

SERVOS_CALIBRATION = {
     0: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # coxa leg RF
     1: {'offset': -90., 'pulse90': 1500, 'ratio': 1000/90.},  # femur leg RF
     2: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # tibia leg RF

     4: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # coxa leg RM
     5: {'offset': -90., 'pulse90': 1500, 'ratio': 1000/90.},  # femur leg RM
     6: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # tibia leg RM

     8: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # coxa leg RR
     9: {'offset': -90., 'pulse90': 1500, 'ratio': 1000/90.},  # femur leg RR
    10: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # tibia leg RR

    15: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # coxa leg LR
    14: {'offset': -90., 'pulse90': 1500, 'ratio': 1000/90.},  # femur leg LR
    13: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # tibia leg LR

    19: {'offset':   0., 'pulse90': 1505, 'ratio': 1000/90.},  # coxa leg LM
    18: {'offset': -90., 'pulse90': 1500, 'ratio': 1000/90.},  # femur leg LM
    17: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # tibia leg LM

    23: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # coxa leg LF
    22: {'offset': -90., 'pulse90': 1500, 'ratio': 1000/90.},  # femur leg LF
    21: {'offset':   0., 'pulse90': 1500, 'ratio': 1000/90.},  # tibia leg LF
}

TBC

Settings

In this tutorial, we just renamed LEGS_ACTUATOR_MAPPING to LEGS_SERVOS_MAPPING, and added the SERVOS_CALIBRATION dict, which contains:

  • offset is the angle between the servo reference and the real angle. See the FAQ for the real angles definition;
  • pulse90 is the pulse value for the neutral position of the servo, which is usually 90°;
  • ratio is the pulse width per degree.

Offsets may vary, depending how you mount the servos. Same, ratio sign may have to be inverted on one side, if you have a symetrical design; all angle are always computed using trigonometric direction (CCW).

See the FAQ to fine tune servos calibration.

Conclusion

Thanks for reading these tutorials! This is the first working dev. release; there 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.

Have a look at py4bot/examples/cronos, which contain the code for my 4DoF hexapod, and closely follow Py4bot devs.

Note: See TracWiki for help on using the wiki.