mpy_robot_tools documentation
About mpy_robot_tools
MicroPython robotics libraries
When programming robots with sensors, you want to focus on the behaviors, not the interfaces. This set of libraries contains abstractions for interfaces like Bluetooth Low Energy (BLE), Huskylens, UART communication, synchronized motor arrays, and LED lights.
With this set, you can easily create a Bluetooth-controlled robot with multiple robotic hubs, communicating and synchronizing their motors. They can run lights, read camera data, and read Arduino sensors.
The BLE library from bt.py supports UART, MIDI instruments, LEGO BLE protocol, and a simple remote control protocol.
mpy_robot_tools works on these MicroPython devices: - OpenMV - ESP32 - LEGO Robot Inventor hub - LEGO SPIKE Prime hub
Installation
SPIKE Prime / Mindstorms Robot Inventor Installation
Copy the code from the install script (click the Copy raw contents button) to an empty Python project in the LEGO MINDSTORMS or LEGO SPIKE program.
Then run it once. It will take additional time to transfer to the Hub please use patience.
Start using the modules.
EV3 Installation
Create a new VS Code EV3 project with the MINDSTORMS extension. Then git clone this repository in the new project directory.
OpenMV / ESP32 Installation
Copy the files to your device using Thonny or the USB drive feature. Then import them like any other Python file.
Alternatively you can run Pymakr in VS Code and start one of the LMS-ESP32 example projects.
FAQ
- … The Spike/Mindstorm app asks for a firmware update after installing
The LEGO software has a bug with a memory leak. The drive becomes filled up, and you lose disk space. To fix it, connect your hub via USB and go here: https://dfu.pybricks.com/fix-update/
- … How do I uninstall? Should I uninstall?
There is no reason to uninstall the libraries. Unless you call them, they do nothing. If you need disk space, you can delete the files with a file manager like Thonny or factory reset the hub through the LEGO software.
Getting Started
The easiest way to get started is to copy and tweak one of the mpy_robot_tools example projects.
Contributing
Please fork and help out this project by adding documentation. Could be docstrings, README, or tutorials.
Documentation of the mpy_robot_tools modules
mpy_robot_tools.bt module
The bt.py module abstracts low-level BLE characteristics and services. The way BLE works is well documented at https://learn.adafruit.com/introduction-to-bluetooth-low-energy/gatt. You can start communication with a UARTCentral on one side and a UART Peripheral on the other. The UARTCentral initiates the communication, and the peripheral waits for a connection, like a server.
The nRF connect smartphone app is convenient to test and debug Bluetooth.
Remote control
RCReceiver and RCTransmitter are subclasses of the UARTPeripheral and UARTCentral, respectively. They receive and transmit a short burst of bytes, enough to pass the state of any custom remote control device. You can build your own Micropython RC transmitter with any BLE Micropython device. You can also use the MINDSTORMS Ble RC Anroid app.
# RCReceiver() - Receives RC commands from the android app or RCTransmitter class.
rcv = RCReceiver(name="snake")
while rcv.is_connected():
speed, turn, delay_setting = rcv.controller_state(R_STICK_VER, L_STICK_HOR, SETTING2)
# RCTransmitter() - Connects to an RCReceiver and
# transmits the state of 9 gamepad-like controls.
remote_control = RCTransmitter()
remote_control.connect(name="snake")
remote_control.set_stick(L_STICK_HOR, steer_angle )
remote_control.set_stick(R_STICK_VER, forward)
remote_control.transmit()
Buffering
By default, the UART objects are buffered. They will remember everything written to them, and you should flush their buffer with _ = read()
to start clean. For remote control and state communication, the buffer gets in the way. You want to read the most recent state when it arrives. In that case initialize with additive_buffer=False
Example:
# Code for a snake tail segment, waiting for connections from the head.
# Creates a link to the snake head and advertises self as "tail".
# Additive buffer is disabled, since we are only interested
# in the most recent state information
head_link = UARTPeripheral(name="tail", additive_buffer=False)
Complex networks
The UARTCentral, and UARTPeripheral classes instantiate a BLEHandler automatically. You can pass your own handler for more complex BLE network setups. If you have multiple Bluetooth objects, like remote control, a Serialtalk and a plain UART, you need to pass a single BLEHandler to all of them:
from projects.mpy_robot_tools.bt import BLEHandler, UARTCentral
from projects.mpy_robot_tools.rc import RCReceiver, R_STICK_VER, L_STICK_HOR, SETTING2
ble = BLEHandler()
seg_1_link = UARTCentral(ble_handler=ble)
seg_2_link = UARTCentral(ble_handler=ble)
rcv = RCReceiver(name="snake", ble_handler=ble)
- class mpy_robot_tools.bt.BLEHandler(debug=False)
Bases:
object
Basic Bluetooth Low Energy class that can be a central or peripheral or both. The central always connects to a peripheral. The Peripheral just advertises. Instantiate a BLEHandler and pass it to the UARTCentral and UARTPeripheral class, if you want to use both classes on the same device.
- Parameters:
debug (bool) – Keep a log of events in the log property. WARNING: Debug log is kept in memory. Long transactions will lead to memory errors!
- advertise(payload, interval_us=100000)
Advertise a BLE payload for a given time interval. Create the payload with the _advertising_payload() function.
- connect_lego(time_out=10)
Connect to a LEGO Smart Hub that advertises with a LEGO service. LEGO Hubs are advertising when their leds are blinking, just after turning them on.
- connect_uart(name='robot', on_disconnect=None, on_notify=None, on_write_done=None, time_out=10)
Connect to a BLE Peripheral that advertises with a certain name, and has a UART service. This method is meant for BLE Centrals
- Parameters:
name (str) – The name of the peripheral to search for and connect to
on_disconnect (function) – Callback function to call when the peripheral disconnects
on_notify (function) – Callback function to call when the peripheral notifies the central
on_write_done (function) – Callback function to call when the peripheral is done writing to the central
- enable_notify(conn_handle, desc_handle, callback=None)
- info(*messages)
Saves messages to the log if debug is enabled.
- Parameters:
messages (str) – Messages to save to the log
- Example:
self.info(var1, var2, var3)
- lego_write(value, conn_handle=None, response=False)
- notify(data, val_handle, conn_handle=None)
Notify connected central interested in the value handle, with the given data. gatts_notify is similar to gatts_indicate, but has not acknowledgement, and thus raises no _IRQ_GATSS_INDICATE_DONE.
- Parameters:
data (bytes) – The data to send to the central(s).
val_handle (int) – The handle of the characteristic or descriptor to notify.
conn_handle – The handle of the connection to notify. If None, notify all connected centrals.
- on_write(value_handle, callback)
Register a callback on the peripheral (server) side for when a client (central) writes to a characteristic or descriptor. It’s time to process the received data!
- Parameters:
value_handle (int) – The handle of the characteristic or descriptor to register the callback for.
callback (function) – The callback function to call when a client writes to the characteristic or descriptor.
- on_write_done(conn_handle, callback)
Register a client (central) callback for when that client (central) is done writing to a characteristic or descriptor. This helps you to avoid writing too much data to the peripheral too soon.
- Parameters:
conn_handle (int) – The handle of the connection to register the callback for.
callback (function) – The callback function to call when a client writes to the characteristic or descriptor.
- print_log()
Prints the log to the console and clears it.
- scan()
Start scanning for BLE peripherals. Scan results will be returned in the IRQ handler.
- stop_scan()
Stop scanning for BLE peripherals.
- uart_write(value, conn_handle, rx_handle=12, response=False)
- class mpy_robot_tools.bt.BleUARTBase(additive_buffer=True)
Bases:
object
Base class with a buffer for UART methods any(), read()
- READS_PER_MS = 10
- any()
Returns the number of bytes in the read buffer.
- read(n=-1)
Read data from remote.
- Parameters:
n (int) – The number of bytes to read. If n is negative or omitted, read all data available.
- readline()
Read a line from remote. A line is terminated with a newline character.
\n
- writeline(data: str)
Write data to remote and terminate with an added newline character.
\n
- mpy_robot_tools.bt.CHORD_STYLES = {'7': (0, 4, 7, 10), 'M': (0, 4, 7, 12), 'M7': (0, 4, 7, 11), 'P': (0, 7, 12, 19), 'dim7': (0, 3, 6, 10), 'm': (0, 3, 7, 12), 'm7': (0, 3, 7, 10), 'sus2': (0, 2, 7, 12), 'sus4': (0, 5, 7, 12)}
Chord styles for the play_chord method of the MidiController class.
- class mpy_robot_tools.bt.MidiController(name='amh-midi', ble_handler=None)
Bases:
object
Class for a MIDI BLE Controller. Turn your MINDSTORMS hub or LMS-ESP32 into a MIDI musical instrument!
- Parameters:
name (str) – The name of the MIDI controller
ble_handler (BLEHandler) – A BLEHandler instance. If None, a new one will be created.
- chord_off(base, velocity=0, style='M')
Stop playing a MIDI chord.
- chord_on(base, velocity, style='M')
Start playing a MIDI chord.
- Parameters:
base (byte or int or str) – The base note of the chord. Can be a MIDI note number (0-127) or a string like “C4” or “C#4”
velocity (byte or int) – The velocity of the chord key press (0-127)
style – Chord style. See CHORD_STYLES for possible values.
- control_change(control, value)
Send a MIDI CC ‘control change’ message. Handy for your ableton live controller.
- Parameters:
control (byte or int) – The control number (0-127)
value (byte or int) – The value of the control (0-127)
- note_off(note, velocity=0)
Send a MIDI ‘note off’ message.
- Parameters:
note (byte or int or str) – The note to stop playing. Can be a MIDI note number (0-127) or a string like “C4” or “C#4”
velocity (byte or int) – The velocity of the note key release (0-127)
- note_on(note, velocity)
Send a MIDI ‘note on’ message.
- Parameters:
note (byte or int or str) – The note to play. Can be a MIDI note number (0-127) or a string like “C4” or “C#4”
velocity (byte or int) – The velocity of the note key press (0-127)
- play_chord(base, style='M', duration=1000)
Play a MIDI chord for a given duration.
- Parameters:
base (byte or int or str) – The base note of the chord. Can be a MIDI note number (0-127) or a string like “C4” or “C#4”
style – Chord style. See CHORD_STYLES for possible values.
duration (int) – The duration of the chord in milliseconds
- write_midi_msg(cmd, data0, data1)
Timestamps and writes a MIDI message to the BLE GATT server. See https://www.midi.org/specifications-old/item/table-1-summary-of-midi-message for MIDI message format.
- Parameters:
cmd (byte or int) – MIDI command byte
data0 (byte or int) – MIDI data byte 0
data1 (byte or int) – MIDI data byte 1
- write_midi_notes(notes, velocity=0, on=True, channel=0)
Timestamps and writes multiple MIDI notes to the BLE GATT server.
- Parameters:
notes (bytearray or list of int) – list of MIDI note numbers
velocity (byte or int) – velocity
on (bool) – Turn notes on if True, off if false. Default True.
channel (int) – MIDI Channel, default 0
- class mpy_robot_tools.bt.RCReceiver(**kwargs)
Bases:
UARTPeripheral
Class for an Remote Control Receiver. It reads and processes gamepad or remote control data. It will advertise as the given name.
- Parameters:
name (str) – The name of this peripheral to advertise as. Default: “robot”
ble_handler (BLEHandler) – A BLEHandler instance. If None, a new one will be created.
- button_pressed(button)
Returns True if the given button is pressed on the remote control.
- Parameters:
button (int) – The button number to check. 1-8
- controller_state(*indices)
Returns the controller state as a list of 9 integers: [left_stick_x, left_stick_y, right_stick_x, right_stick_y, left_trigger, right_trigger, left_setting, right_setting, buttons]
- Parameters:
indices (int) – The items of the selection of controller states to return. If omitted, the whole list is returned. Use these constants: L_STICK_HOR, L_STICK_VER, R_STICK_HOR, R_STICK_VER, L_TRIGGER, R_TRIGGER, SETTING1, SETTING2, BUTTONS
Use the controller state L_STICK indices to get only left stick values:
left_stick_x, left_stick_y, = rc.controller_state(L_STICK_HOR, L_STICK_VER)
- class mpy_robot_tools.bt.RCTransmitter(**kwargs)
Bases:
UARTCentral
Class for a Remote control transmitter. It sends gamepad or remote control data to a receiver.
- Parameters:
name (str) – The name of the peripheral to search for and connect to. Default: “robot”
ble_handler (BLEHandler) – A BLEHandler instance. If None, a new one will be created.
- static clamp_int(n, floor=-100, ceiling=100)
- set_button(num, pressed)
Set a button to pressed or not pressed.
- Parameters:
num (int) – The button number to set. 1-8
pressed (bool) – True or False
- set_setting(setting, value)
Set a parameter dial setting.
- Parameters:
setting (int) – The setting to set. Use these constants: SETTING1, SETTING2
value (int) – The value to set. Should be between -32768 and 32767.
- set_stick(stick, value)
Set a stick value. Value should be between -100 and 100.
- Parameters:
stick (int) – The stick to set. Use these constants: L_STICK_HOR, L_STICK_VER, R_STICK_HOR, R_STICK_VER
value (int) – The value to set. Should be between -100 and 100.
- set_trigger(trig, value)
Set a gamepad shoulder trigger value. Value should be between 0 and 200.
- Parameters:
trig (int) – The trigger to set. Use these constants: L_TRIGGER, R_TRIGGER
value (int) – The value to set. Should be between 0 and 200.
- transmit()
Send the controller state to the receiver. This call will wait if you write again within 15ms.
- class mpy_robot_tools.bt.UARTCentral(ble_handler: BLEHandler = None, additive_buffer=True)
Bases:
BleUARTBase
- connect(name='robot')
Search for and connect to a peripheral with a given name.
- Parameters:
name (str) – The name of the peripheral to connect to
- disconnect()
- fast_write(data)
Write to server/peripheral as fast as possible. Non-blocking. - Data is truncated to mtu - No pause after writing. Writing too often can crash the ble stack. Be careful
- Parameters:
data (bytes) – The data to write to the peripheral
- is_connected()
- write(data)
Write uart data to remote. This is a blocking call and will wait until writing is done.
- Parameters:
data (bytes) – The data to write to the peripheral
- class mpy_robot_tools.bt.UARTPeripheral(name='robot', ble_handler: BLEHandler = None, additive_buffer=True)
Bases:
BleUARTBase
Class for a Nordic UART BLE server/peripheral. It will advertise as the given name and populate the UART services and characteristics
- Parameters:
name (str) – The name of the peripheral
ble_handler (BLEHandler) – A BLEHandler instance. If None, a new one will be created.
additive_buffer (bool) – If True, the read buffer will be added to on each read. If False, the read buffer will be overwritten on each read.
- is_connected()
- write(data)
Write uart data to remote. This is a blocking call.
- mpy_robot_tools.bt.advertising_payload(limited_disc=False, br_edr=False, name=None, services=None, appearance=0)
Generate advertising payload.
- Parameters:
limited_disc (bool) – Limited discoverable mode. Determines whether the device can be discoverable for a limited period. Default value is
False
.br_edr (bool) – BR/EDR support (Basic Rate/Enhanced Data Rate). Determines whether the device supports classic Bluetooth. Default value is
False
.name (str) – Name of the device to be advertised. Default value is
None
.services (list) – List of services offered by the device, typically identified by UUIDs. Default value is
None
.appearance (int) – Appearance category code, describing the visual appearance of the device (e.g., phone, keyboard). Default value is
False
.
- Returns:
An array of bytes with the specified payload.
- Return type:
list[bytes]
- mpy_robot_tools.bt.note_parser(note)
If note is a string then it will be parsed and converted to a MIDI note (key) number, e.g. “C4” will return 60, “C#4” will return 61. If note is not a string it will simply be returned.
- Parameters:
note – Either 0-127 int or a str representing the note, e.g. “C#4”
mpy_robot_tools.sen0539 module
This contains a python API to interface with the DFRobot Sen0539 Voice Recognition sensor. This module supports I2C only, so it won’t run on an Inventor hub. Use LMS-ESP32 or OpenMV. The sensor is capable of UART, so theoretically this module could be expanded with UART support.
- mpy_robot_tools.sen0539.CMD_IDS = {0: 'Listening...', 1: 'Wake-up words for learning', 2: 'Hello robot', 5: 'The first custom command', 6: 'The second custom command', 7: 'The third custom command', 8: 'The fourth custom command', 9: 'The fifth custom command', 10: 'The sixth custom command', 11: 'The seventh custom command', 12: 'The eighth custom command', 13: 'The ninth custom command', 14: 'The tenth custom command', 15: 'The eleventh custom command', 16: 'The twelfth custom command', 17: 'The thirteenth custom command', 18: 'The fourteenth custom command', 19: 'The fifteenth custom command', 20: 'The sixteenth custom command', 21: 'The seventeenth custom command', 22: 'Go forward', 23: 'Retreat', 24: 'Park a car', 25: 'Turn left ninety degrees', 26: 'Turn left forty-five degrees', 27: 'Turn left thirty degrees', 28: 'Turn right ninety degrees', 29: 'Turn right forty-five degrees', 30: 'Turn right thirty degrees', 31: 'Shift down a gear', 32: 'Line tracking mode', 33: 'Light tracking mode', 34: 'Bluetooth mode', 35: 'Obstacle avoidance mode', 36: 'Face recognition', 37: 'Object tracking', 38: 'Object recognition', 39: 'Line tracking', 40: 'Color recognition', 41: 'Tag recognition', 42: 'Object sorting', 43: 'Qr code recognition', 44: 'General settings', 45: 'Clear screen', 46: 'Learn once', 47: 'Forget', 48: 'Load model', 49: 'Save model', 50: 'Take photos and save them', 51: 'Save and return', 52: 'Display number zero', 53: 'Display number one', 54: 'Display number two', 55: 'Display number three', 56: 'Display number four', 57: 'Display number five', 58: 'Display number six', 59: 'Display number seven', 60: 'Display number eight', 61: 'Display number nine', 62: 'Display smiley face', 63: 'Display crying face', 64: 'Display heart', 65: 'Turn off dot matrix', 66: 'Read current posture', 67: 'Read ambient light', 68: 'Read compass', 69: 'Read temperature', 70: 'Read acceleration', 71: 'Reading sound intensity', 72: 'Calibrate electronic gyroscope', 73: 'Turn on the camera', 74: 'Turn off the camera', 75: 'Turn on the fan', 76: 'Turn off the fan', 77: 'Turn fan speed to gear one', 78: 'Turn fan speed to gear two', 79: 'Turn fan speed to gear three', 80: 'Start oscillating', 81: 'Stop oscillating', 82: 'Reset', 83: 'Set servo to ten degrees', 84: 'Set servo to thirty degrees', 85: 'Set servo to forty-five degrees', 86: 'Set servo to sixty degrees', 87: 'Set servo to ninety degrees', 88: 'Turn on the buzzer', 89: 'Turn off the buzzer', 90: 'Turn on the speaker', 91: 'Turn off the speaker', 92: 'Play music', 93: 'Stop playing', 94: 'The last track', 95: 'The next track', 96: 'Repeat this track', 97: 'Volume up', 98: 'Volume down', 99: 'Change volume to maximum', 100: 'Change volume to minimum', 101: 'Change volume to medium', 102: 'Play poem', 103: 'Turn on the light', 104: 'Turn off the light', 105: 'Brighten the light', 106: 'Dim the light', 107: 'Adjust brightness to maximum', 108: 'Adjust brightness to minimum', 109: 'Increase color temperature', 110: 'Decrease color temperature', 111: 'Adjust color temperature to maximum', 112: 'Adjust color temperature to minimum', 113: 'Daylight mode', 114: 'Moonlight mode', 115: 'Color mode', 116: 'Set to red', 117: 'Set to orange', 118: 'Set to yellow', 119: 'Set to green', 120: 'Set to cyan', 121: 'Set to blue', 122: 'Set to purple', 123: 'Set to white', 124: 'Turn on ac', 125: 'Turn off ac', 126: 'Increase temperature', 127: 'Decrease temperature', 128: 'Cool mode', 129: 'Heat mode', 130: 'Auto mode', 131: 'Dry mode', 132: 'Fan mode', 133: 'Enable blowing up & down', 134: 'Disable blowing up & down', 135: 'Enable blowing right & left', 136: 'Disable blowing right & left', 137: 'Open the window', 138: 'Close the window', 139: 'Open curtain', 140: 'Close curtain', 141: 'Open the door', 142: 'Close the door', 200: 'Learning wake word', 201: 'Learning command word', 202: 'Re-learn', 203: 'Exit learning', 204: 'I want to delete', 205: 'Delete wake word', 206: 'Delete command word', 207: 'Exit deleting', 208: 'Delete all'}
All command words and their IDs
- class mpy_robot_tools.sen0539.SEN0539(scl=2, sda=26, i2c=None, addr=micropython.const)
Bases:
object
Class for SEN0539-EN Voice Recognition Module by DFRobot
- Parameters:
scl (int) – SCL pin number, default 2
sda (int) – SDA pin number, default 26
i2c (I2C) – I2C object, default None creates a new one with the scl and sda pins. If using OpenMV, it defaults to i2c on bus 4 (sda=P8, scl=P7)
addr (int) – I2C address of SEN0539 sensor, default 0x64
- get_cmd_id()
Get the command word ID of the last identified command word
- Returns:
Command word ID
- Return type:
int
- get_wake_time()
Get the wake duration, before sensor says “I’m off now” and you have to wake it again with the wake word.
- Returns:
The current set wake-up period in seconds
- Return type:
int
- play_cmd_id(cmd_id)
Play the corresponding reply audio according to the command word ID in CMD_IDS Can enter wake-up state through ID-1 in I2C mode
- Parameters:
cmd_id (int) – Command word ID
- rd(reg)
- set_mute_mode(mode)
Set mute mode
- Parameters:
mode (int) – Mute mode; set value 1: mute, 0: unmute
- set_volume(vol: int)
Set voice volume. 0 mutes.
- Parameters:
vol (int) – Volume value 0 - 20
- set_wake_time(wake_time: int)
Set wake duration
- Parameters:
wake_time (int) – Wake duration, range 0~255, unit: 1s
- wr(reg, val)
mpy_robot_tools.ctrl_plus module
This module connects to a Technic smart hhub and is able to control connected devices, read the states of the IMU, and control connected motors.
- class mpy_robot_tools.ctrl_plus.SmartHub(ble_handler: BLEHandler = None)
Bases:
object
- acc()
- connect()
- dc(port, pct)
- disconnect()
- get(port)
- gyro()
- is_connected()
- mode(port, mode, *data)
- run(port, speed, max_power=100, acceleration=100, deceleration=100)
- run_angle(port, degrees, speed=50, max_power=100, acceleration=100, deceleration=100, stop_action=0)
- run_target(port, degrees, speed=50, max_power=100, acceleration=100, deceleration=100, stop_action=0)
- run_time(port, time, speed=50, max_power=100, acceleration=100, deceleration=100, stop_action=0)
- set_led_color(idx)
- set_remote_led_color(idx)
- tilt()
- unpack_data(port, fmt='3h')
- write(*data)
- mpy_robot_tools.ctrl_plus.clamp_int(n, floor=-100, ceiling=100)
- mpy_robot_tools.ctrl_plus.const(x)
- mpy_robot_tools.ctrl_plus.sleep_ms(x)
mpy_robot_tools.helpers module
Helper modules for frequently used functions. Most of the helpers have moved to the Pybricks module.
- mpy_robot_tools.helpers.clamp_int(n, floor=-100, ceiling=100)
Limits input number to the range of -100, 100 and returns an integer
- Parameters:
n (int or floar) – input number
floor (int, optional) – lowest limit >= , defaults to -100
ceiling (int, optional) – highest limit <=, defaults to 100
- Returns:
clamped number
- Return type:
int
- mpy_robot_tools.helpers.scale(val, src, dst)
Returns the given value scaled from the scale of src to the scale of dst.
- Parameters:
val (int or float) – Value to scale. Ex: 75
src (tuple) – Original range. Ex: (0.0, 99.0)
dst (tuple) – Target range. Ex: (-1.0, +1.0)
- Returns:
Scaled value. Ex: 0.5
- mpy_robot_tools.helpers.wait_until(func, condition=True)
Calls input function every 10ms until it returns the wanted condition.
- Parameters:
func (function, callable) – Function to test against condition
condition (bool, optional) – condition to stop waiting, defaults to True
mpy_robot_tools.light module
Helper functions to control and animate LEDs on the 5x5 light matrix of the SPIKE Prime and Inventor hubs.
- class mpy_robot_tools.light.LMAnimation(frames, fps=12)
Bases:
object
Class for showing animations in your python script frames: can be a generator or list of 5x5 matrices. Frames can even be tuples of a frame duration and a 5x5 matrix.
usage:
animation = LMAnimation(my_frame_list) while True: animation.update_display()
Note that the hub can also animate using the code below. It wil not be synchronized to a timer, but you don’t have to worry about it in a control loop
from hub import display, Image IMG_1 = Image("00000:09000:09000:09000:00000") IMG_2 = Image("00000:00900:00900:00900:00000") IMG_3 = Image("00000:00090:00090:00090:00000") ANIMATION = [IMG_1, IMG_2, IMG_3] display.show(ANIMATION, delay=100, wait=False, loop=True)
- update_display(time=None)
Call this method in a tight loop to update the hub display with the animation loaded at init.
- Parameters:
time (int, optional) – pass a time in miliseconds, when None (default) it uses ticks_ms() since instantiation.
- mpy_robot_tools.light.codelines()
Generator for Tars-style codelines, as seen in insterstellar usage:
mycodelines = codelines() image_matrix = next(mycodelines)
- mpy_robot_tools.light.image_2_matrix(input)
- mpy_robot_tools.light.image_99(number)
Generates 5x5 matrix images for numbers up to 99
- Parameters:
number (integer) – number between 0 and 99
- Returns:
SPIKE2 and MINDSTORMS api type Image
- Return type:
hub.Image
- mpy_robot_tools.light.matrix_2_image(matrix)
mpy_robot_tools.motor_sync module
Synchronize motor movements with keyframed animations. Great for animating walker legs in spiders, at-at, tars, gelo etc…
- class mpy_robot_tools.motor_sync.AMHTimer(rate=1000, acceleration=0)
Bases:
object
A configurable timer which you can start, reverse, stop and pause. By default, it counts milliseconds, but you can speed it up, Slow it down or accelerate it! You can also set the time and reset it. You can even run it in reverse, so you can count down until 0. It always returns integers, even when you slow it way down.
- Usage::
my_timer = AMHTimer(): my_timer.rate = 500 # set the rate to 500 ticks/s. That is half the normal rate my_timer.acceleration = 100 # Increase the rate by 100 ticks / second squared my_timer.reset() # Reset to zero. Doesn’t change running/paused state now = mytimer.time # Read the time mytimer.time = 5000 #Set the time
- property acceleration
- pause()
- property rate
- reset()
- resume()
- reverse()
- start()
- stop()
- property time
- class mpy_robot_tools.motor_sync.Mechanism(motors, motor_functions, reset_zero=True, Kp=1.2)
Bases:
object
The class helps to control multiple motors in a tight loop python program.
- Parameters:
motors (list) – list of motor objects. Can be hub.port.X.motor or Motor(‘X’)
motor_functions (list of func) – list of functions that take time (ticks) argument and calculate motor positions
reset_zero (bool, optional) – resets the 0 point of the relative encoder to the absolute encoder position, defaults to True
Kp (float, optional) – proportional feedback factor for motor power, defaults to 1.2
- Usage:
my_mechanism = Mechanism([Motor('A'), Motor('B')], [func_a, func_b]) timer = AMHTimer() while True: my_mechanism.update_motor_pwms(timer.time)
- relative_position_reset(motors_to_reset=[])
- shortest_path_reset(ticks=0, speed=20, motors_to_reset=[])
- stop()
- update_motor_pwms(ticks, **kwargs)
- mpy_robot_tools.motor_sync.block_wave(amplitude=100, period=1000, offset=0)
- mpy_robot_tools.motor_sync.linear(factor, time_delay=0, offset=0)
Returns a function that is a linear proportion to an input.
- mpy_robot_tools.motor_sync.linear_interpolation(points, wrapping=True, scale=1, accumulation=True, time_offset=0, smoothing=0.0)
Returns a method that interpolates values between keyframes / key coordinates.
Input: list of coordinates Returns: A method(!) that interpolates a value between given points
Arguments: - scale_y: scale the y coordinates to enlarge movements or to invert them (scale_y=-1) - wrapping: True by default. If an x value is beyond the highest x value in the point list, wrapping will wrap the values and look back to the first coordinates. - accumulation: Boolean. True, by default. After each wraparound, adds the difference between the first and last keyframe. - time_offset: offset the first values in the keyframes by this number - smoothing: Increase up to 1.0 for maximum cosine smoothing. This is sometimes called ‘easing’
- Example::
my_function = linear_interpolation([(0,0), (1000,360), (2000,0)]) my_function(500) # returns 180. my_function(2500) # Also returns 180, because of wrapping.
- mpy_robot_tools.motor_sync.sine_wave(amplitude=100, period=1000, offset=0)
mpy_robot_tools.np_animation module
Animate Neopixels (ws2812) RGB leds with this module. Great for police lights, inidicator lights, knight-rider animation and more.
- class mpy_robot_tools.np_animation.NPAnimation(light_funcs: dict, pin: int = 24, n_leds: int = 1)
Bases:
object
- update_leds(time=None, **kwargs)
- mpy_robot_tools.np_animation.brake_lights(drive=b'\x00D\x00', brake=b'\x00\xff\x00', reverse=b'\xff\xff\xff')
- mpy_robot_tools.np_animation.clamp(value, min_value, max_value)
- mpy_robot_tools.np_animation.delayed_switch(on=b'\x00\xff\x00', off=b'\x00\x00\x00', delay=2000)
- mpy_robot_tools.np_animation.from_grb(grb)
- mpy_robot_tools.np_animation.hsl_to_rgb(h, s, l)
- mpy_robot_tools.np_animation.hue_shift(period=1000, offset=0)
- mpy_robot_tools.np_animation.hue_to_rgb(h)
- mpy_robot_tools.np_animation.indicators(on=b'f\xfc\x03', off=b'\x00\x00\x00', interval=500, name='indicators')
- mpy_robot_tools.np_animation.indicators_right(on=b'f\xfc\x03', off=b'\x00\x00\x00', interval=500)
- mpy_robot_tools.np_animation.keyframes(frames)
- mpy_robot_tools.np_animation.keyframes_dict(frames_dict, name='animation')
- mpy_robot_tools.np_animation.knight_rider(period=2000, width=6)
- mpy_robot_tools.np_animation.knight_rider_gen(period=2000, width=6)
- mpy_robot_tools.np_animation.rgb_to_hsl(r, g, b)
- mpy_robot_tools.np_animation.rotate(l, n)
- mpy_robot_tools.np_animation.saturate(value)
- mpy_robot_tools.np_animation.switch(on=b'\xff\xff\xff', off=b'\x00\x00\x00', name='switch')
- mpy_robot_tools.np_animation.to_grb(rgb)
mpy_robot_tools.pybricks module
The Robot Inventor Python api for motors and sensors is not very comfortable. This Pybricks module allows you to use most of the Pybricks API as documented on https://docs.pybricks.com.
Provides a Pybricks-like API for SPIKE2 and LEGO MINDSTORMS Robot Inventor.
Motors are initialized with their relative encoder zeroed to their absolute zero. You can use SI units to control motors and sensors. Motors can run in the background with wait=False
- class mpy_robot_tools.pybricks.Direction
Bases:
object
Enumerator for Directions
- CLOCKWISE = 1
- COUNTERCLOCKWISE = -1
- class mpy_robot_tools.pybricks.DriveBase(l_motor: Motor, r_motor: Motor, wheel_diameter, axle_width)
Bases:
object
- curve(radius, degrees)
- drive(speed, turn_rate)
Start driving at speed (mm/s) with turn rate (deg/s)
- settings(*args)
- stop()
- straight(distance)
- straight_acceleration = 0
- straight_speed = 300
- turn_acceleration = 0
- turn_rate = 0
- class mpy_robot_tools.pybricks.Motor(motor, direction=1)
Bases:
object
Universal motor with universal methods to write agnostic platform helpers.
This class takes any motor type object as parameter and runs it pybricks-style, with the pybricks motor methods.
- angle()
Returns the motor’s angle.
- dc(duty)
Sets the motor’s dc.
- reset_angle(*args)
Reset motor’s angle.
- Parameters:
angle (int) – Pass 0 to set current position to zero. Without arguments this resets to the absolute encoder position
- run(speed)
Runs the motor at the specified speed.
- Parameters:
speed (int?) – speed value.
- run_angle(speed, rotation_angle, wait=True, stop=0)
Runs the motor at a particular rotation angle and speed.
- Parameters:
speed (int) – Speed value.
rotation_angle (int) – Angle value.
wait (bool) – ….. Default value True.
- run_target(speed, target_angle, wait=True, stop=0)
Runs the motor at a particular target angle and speed.
- Parameters:
speed (int) – Speed value.
target_angle (int) – Angle value.
wait (bool) – ….. Default value True.
- run_time(speed, time, wait=True, stop=0)
Runs the motor at the specified speed.
- Parameters:
speed (int) – Speed value.
time (float) – Time in milliseconds.
wait (bool) – ….. Default value True.
- run_until_stalled(*args, **kwargs)
- speed()
- stop()
Stops the motor.
- track_target(*args, **kwargs)
Call this method in closed loop to ensure a motor moves to this angle target.
- Parameters:
target (int, optional) – target angle, defaults to 0
gain (float, optional) – motor power proportional to error, defaults to 1.5
- class mpy_robot_tools.pybricks.Port
Bases:
object
Enumerator for Port names
- A = 'A'
- B = 'B'
- C = 'C'
- D = 'D'
- E = 'E'
- F = 'F'
- class mpy_robot_tools.pybricks.Stop
Bases:
object
Enumerator for Stop modes
- BRAKE = 0
- COAST = 1
- HOLD = 2
- class mpy_robot_tools.pybricks.USLights(sensor)
Bases:
object
Ultrasonic sensor lights helper.
- off()
Turns off all the lights.
- on(brightness=100)
Turns on the lights at the specified brightness.
- Parameters:
brightness (tuple | int) – Brightness of each light, in the order shown above. If you give one brightness
tuple (value instead of a) –
brightness. (all lights get the same) –
- class mpy_robot_tools.pybricks.UltrasonicSensor(sensor_port)
Bases:
object
Pybricks-style ultrasonic sensor
- distance()
Measures the distance between the sensor and an object using ultrasonic sound waves.
- Returns:
Measured distance. If no valid distance was measured, it returns 2000 mm.
- mpy_robot_tools.pybricks.wait(duration_ms)
Sleep in miliseconds.
- Parameters:
duration_ms (int or float) – duration (ms)
mpy_robot_tools.rc module
Legacy module for compatibility reasons. Don’t use.
mpy_robot_tools.servo module
Simple module to control hobby servos on LMS-ESP32. Converts angles to 2000us PWM signals.
- class mpy_robot_tools.servo.Servo(pin)
Bases:
object
Controls a hobby servo with 2000 microsecond pwm
- Parameters:
pin (int) – Servo pin number
- angle(angle)
- ccw90 = 1000
- cw90 = 2000
- pwm(pwm)
Timing in microseconds 1500 is neutral, 2000 is far right, 1000 is far left. https://en.wikipedia.org/wiki/Servo_control#/media/File:Servomotor_Timing_Diagram.svg
- Parameters:
pwm (int) – microseconds pwm.
- zero = 1500
mpy_robot_tools.pyhuskylens module
Module with Python API for a Huskylens. This uses the Huskylens serial protocol and get Image AI data.
- class pyhuskylens.HuskyLens(port, baud=9600, debug=False, pwm=0)
Bases:
object
- static calc_checksum(data)
- check_ok(timeout=1)
- clear_text()
- force_read(size=1, max_tries=150, search=b'')
- get(ID=None, learned=False)
- get_arrows(ID=None, learned=False)
- get_blocks(ID=None, learned=False)
- get_version()
- knock()
- process_info()
- read_cmd()
- set_alg(algorithm)
- show_text(text, position=(10, 10))
- write_cmd(command, payload=b'')
- pyhuskylens.byte(num)
- pyhuskylens.clamp_int(r, low_cap=-100, high_cap=100)
Stubs
For programming convenience in VS Code I would love to collect stubs of all LEGO hub libraries. I’ve been looking into micropython-stubber but it didn’t work for me.
mpy_robot_tools.hub_stub module
- class mpy_robot_tools.hub_stub.Device
Bases:
Motor
- motor = <mpy_robot_tools.hub_stub.Motor object>
- mpy_robot_tools.hub_stub.Image(s)
- class mpy_robot_tools.hub_stub.port
Bases:
object
- A = <mpy_robot_tools.hub_stub.Device object>
- B = <mpy_robot_tools.hub_stub.Device object>
- C = <mpy_robot_tools.hub_stub.Device object>
- D = <mpy_robot_tools.hub_stub.Device object>
- E = <mpy_robot_tools.hub_stub.Device object>
- F = <mpy_robot_tools.hub_stub.Device object>