wiki:Tutorials

Version 54 (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.

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.

We also need to create an actuator pool, which contains all legs joints actuators, in order to move them syncrhonized. In our example, actuators are standard servos. In this example, we use the Veyron board, from DFRobot, to drive our servos:

import settings


class Hexapod(Robot):
    def _createBody(self):
        return Body(settings.LEGS_ORIGIN)

    def _createLegs(self):
        legs = {}
        legIk = {}
        for legIndex in settings.LEGS_INDEX:
            legs[legIndex] = Leg3Dof(legIndex, {'coxa': Coxa(), 'femur': Femur(), 'tibia': Tibia()}, settings.FEET_NEUTRAL[legIndex])
            legIk[legIndex] = Leg3DofIk(settings.LEGS_GEOMETRY[legIndex])

        return legs, legIk

    def _createActuatorPool(self):
        driver = FakeDriver()
        pool = ServoPool(driver)

        for leg in self._legs.values():

            # Create joints actuators
            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

As you can see, we just implemented 3 virtual methods, _createBody(), _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. We will describe this module later.

To drive a robot, we need a remote control. In this tutorial, we are going to use an old gamepad, a Thrustmaster Firestorm Dual Analog 3. As I own such gamepad, I already added support in Py4bot:

class Gamepad(RemoteControl):
    def _createFrontend(self):
        return Thrustmaster(settings.THRUSTMASTER_PATH)

    def _buildComponents(self):
        self._addConfig("walk")
        self._addConfig("body")

        self._addComponent(Button, command=self.selectNextConfig, key="button_08", trigger="hold")
        self._addComponent(Button, command=self.selectPreviousConfig, key="button_09", trigger="hold")

        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))
        self._addComponent(Joystick, configs="walk", command=GaitSequencer().walk, keys=("analog_02", "analog_03", "analog_00"), mapper=MapperWalk())

        self._addComponent(Analog, configs="body", command=self.robot.setBodyExtraPosition, key="analog_00", mapper=MapperSetMultiply('yaw', coef=-15))
        self._addComponent(Analog, configs="body", command=self.robot.setBodyExtraPosition, key="analog_03", mapper=MapperSetMultiply('pitch', coef=-15))
        self._addComponent(Analog, configs="body", command=self.robot.setBodyExtraPosition, key="analog_02", mapper=MapperSetMultiply('roll', coef=15))

We won't deep into details, here; refer to the 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...

Now, let's create our robot:

def main():
    def addGait(gaitClass, gaitName):
        gait = gaitClass(gaitName, settings.GAIT_LEGS_GROUPS[gaitName], settings.GAIT_PARAMS[gaitName])
        GaitManager().add(gait)

    addGait(GaitTripod, "tripod")
    addGait(GaitTetrapod, "tetrapod")
    addGait(GaitRiple, "riple")
    addGait(GaitWave, "metachronal")
    addGait(GaitWave, "wave")
    GaitManager().select("riple")

    robot = Hexapod()

    remote = Gamepad(robot)

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

    robot.setBodyPosition(z=30)

    robot.mainLoop()

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


if __name__ == "__main__":
    main()

First, 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!

Settings

Let's discuss about settings used in the previous part. See the documentation 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': 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_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.},
}

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.

FEET_NEUTRAL = {
    'RM': LEGS_GEOMETRY['RM']['coxa'] + LEGS_GEOMETRY['RM']['femur'],
    'RF': LEGS_GEOMETRY['RF']['coxa'] + LEGS_GEOMETRY['RF']['femur'],
    'LF': LEGS_GEOMETRY['LF']['coxa'] + LEGS_GEOMETRY['LF']['femur'],
    'LM': LEGS_GEOMETRY['LM']['coxa'] + LEGS_GEOMETRY['LM']['femur'],
    'LR': LEGS_GEOMETRY['LR']['coxa'] + LEGS_GEOMETRY['LR']['femur'],
    'RR': LEGS_GEOMETRY['RR']['coxa'] + LEGS_GEOMETRY['RR']['femur'],
}

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.

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 is a table to map all joints to actuators nums.

SERVOS_CALIBRATION = {
    0: {'offset': _90., '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': -90., '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': -90., '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': -90., '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': -90., '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': -90., '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
}

SERVOS_CALIBRATION contains some calibration:

  • 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 user guide how to fine tune servos calibration.

Finally:

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

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

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

GAIT_PARAMS contains some additional gaits params:

  • length is the distance each leg will move for an entire cycle when the robot translate at full speed;
  • angle is the angle each leg will turn for an entire cycle when the robot rotate at full speed;
  • 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.

THRUSTMASTER_PATH = "/dev/input/by-id/usb-Mega_World_Thrustmaster_dual_analog_3.2-event-joystick"

No need for further explanations.

Tutorial 2

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

Here, we will see how to use the 3D simulation stuff.

Settings

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 multi-legs robots.

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

Note: See TracWiki for help on using the wiki.