python-mebo’s documentation!

mebo

Mebo is a python package to control the Mebo Robot with Python. It is currently in active development, so there might be breaking changes. Some basic usage is defined below, but more extensive documentation is available at ReadTheDocs.

Note

This project is not associated with the official Mebo project or its owners, Skyrocket LLC.

Note

This package and the associated modules have been tested on Mebo version 1 only.

Installation

pip install mebo

Quickstart

Some basic usage is below. The API will change and limited documentation exists, but it works for getting started.

from mebo import Mebo
m = Mebo(auto_connect=True) # discover and connect automatically!
m.move('n', speed=255, dur=1000)  # move forward at max speed for 1 second
m.arm.up(dur=1000) # move the arm up for one second
m.claw.open(dur=1000) # open the claw for one second

Development

Requirements:

  • python >= 3.6

To get started with the project:

git clone https://github.com/crlane/python-mebo.git
python -m venv mebo-venv
. mebo-venv/bin/actvate
pip install -r requirements.txt
pip install -e .

To run the tests:

pip install -r test_requirements.txt
py.test

Todo

  • [ ] Cleaner API (better subclasses, kwargs for component methods, no metaprogramming)
  • [ ] Clean up kwargs inconsistency
  • [ ] Better documentation
  • [ ] Better tests
  • [ ] Media stream (multithreading or asyncio, http with <video> tag)

mebo.robot

Classes and methods for working with the physical Mebo robot

class mebo.robot.Component(actions)[source]

Abstract base class for all robot components

class mebo.robot.ComponentFactory[source]

Factory class for generating classes of components

class mebo.robot.Mebo(ip=None, auto_connect=False)[source]

Mebo represents a single physical robot

add_router(auth_type, ssid, password, index=1)[source]

Save a wireless network to the Mebo’s list of routers

connect()[source]

Connect to the mebo control server over HTTP

If no IP exists for the robot already, the IP will be autodiscovered via mDNS. When there is already an IP, that will be used to make a canary request to get the command server software version. If the robot has been previously connected, no request is made at all.

Raises:mebo.exceptions.MeboDiscoveryError when a mDNS discovery fails
Raises:mebo.exceptions.MeboConnectionError when a TCP ConnectionError or HTTPError occurs
get_boundary_position()[source]

Gets boundary positions for 4 axes:

Arm: s_up, s_down Claw: c_open, c_close Wrist Rotation: w_left & w_right Wrist Elevation: h_up, h_down

Returns:dictionary of functions to boundary positions
move(direction, speed=255, dur=1000)[source]

Move the robot in a given direction at a speed for a given duration

Parameters:
  • direction – map direction to move. ‘n’, ‘ne’, ‘nw’, etc.
  • speed – a value in the range [0, 255]. default: 255
  • dur – number of milliseconds the wheels should spin. default: 1000
turn(direction)[source]

Turns a very small amount in the given direction

Parameters:direction – one of R or L
visible_networks()[source]

Retrieves list of wireless networks visible to Mebo.

Returns:A dictionary of name to WirelessNetwork
>>> m = Mebo(auto_connect=True)
>>> print(m.visible_networks())
arm

The arm component of mebo

>>> m = Mebo(auto_connect=True)
>>> m.arm.up(dur=1000, **params)
>>> m.arm.down(dur=1000, **params)
>>> m.arm.stop(**params)
claw

The claw component at the end of Mebo’s arm

>>> m = Mebo(auto_connect=True)
>>> m.claw.open(dur=1000, **params)
>>> m.claw.close(dur=400, **params)
>>> m.claw.stop(**params)
ip

The IP of the robot on the LAN

This value is either provided explicitly at creation time or autodiscovered via mDNS

media

an rtsp session representing the media streams (audio and video) for the robot

speaker
>>> m = Mebo(auto_connect=True)
>>> m.speaker.set_volume(value=6)
>>> m.speaker.get_volume()
>>> m.speaker.play_sound(**params)
version

returns the software version of the robot

>>> m = Mebo(auto_connect=True)
>>> m.version == '03.02.37'
wrist

The wrist component of the robot

The wrist component has the following actions: * rotate clockwise (to the right from the robot’s perspective) OR counter-clockwise (to the left from the robot’s perspective) * raise or lower

>>> m = Mebo()
>>> m.wrist.rotate_right(**params)
>>> m.wrist.rotate_left(**params)
>>> m.wrist.inch_right(**params)
>>> m.wrist.inch_left(**params)
>>> m.wrist.rotate_stop()
>>> m.wrist.up()
>>> m.wrist.down()
>>> m.wrist.lift_stop()

mebo.stream

This module contains classes and methods for connecting to mebo’s AV streams

mebo.exceptions

Exceptions for the mebo robot

exception mebo.exceptions.MeboCommandError[source]

Exception raised when a command is incorrect

exception mebo.exceptions.MeboConfigurationError[source]

Exception raised when a Mebo misconfiguration is detected

exception mebo.exceptions.MeboConnectionError[source]

Exception raised when connection to mebo fails

exception mebo.exceptions.MeboDiscoveryError[source]

Exception raised when unable to autodiscover mebo on the LAN

exception mebo.exceptions.MeboError[source]

General Error for Mebo

exception mebo.exceptions.MeboRequestError[source]

Exception raised when a request is not accepted by Mebo command server

Indices and tables